From ef01b1017b2939ad2f39a8dce35d6b175dd5b4d9 Mon Sep 17 00:00:00 2001 From: Philippe <zanne.philippe@unistra.fr> Date: Thu, 13 Mar 2025 14:18:46 +0000 Subject: [PATCH] dc synchronization test --- CONTRIBUTING.md | 66 ++ INSTALL.md | 102 +++ LICENSE | 201 +++++ README.md | 98 +-- ethercat_driver/CMakeLists.txt | 154 ++++ ethercat_driver/ethercat_driver_plugin.xml | 12 + .../configurations/beckhoff_ek1914.yaml | 93 +++ .../configurations/beckhoff_el1918.yaml | 41 + .../configurations/estop_ethercat_safety.yaml | 11 + .../configurations/safety.ros2_control.xacro | 52 ++ .../safety_estop.ros2_control.template.xacro | 38 + .../test_config_ethercat_safety.yaml | 27 + .../update_slave_config_path.py | 68 ++ .../ethercat_driver/ethercat_driver.hpp | 135 +++ .../ethercat_safety_driver.hpp | 85 ++ .../ethercat_driver/visibility_control.h | 49 ++ ethercat_driver/package.xml | 26 + ethercat_driver/src/ethercat_driver.cpp | 786 ++++++++++++++++++ .../src/ethercat_safety_driver.cpp | 426 ++++++++++ .../testHelper_ethercat_safety_driver.hpp | 34 + .../test/test_ethercat_safety_driver.cpp | 227 +++++ ethercat_driver_ros2/CMakeLists.txt | 4 + ethercat_driver_ros2/doxygen/Doxyfile | 23 + ethercat_driver_ros2/package.xml | 17 + ethercat_driver_ros2/requirements.txt | 7 + ethercat_driver_ros2/sphinx/Makefile | 24 + .../sphinx/_static/css/custom.css | 21 + ethercat_driver_ros2/sphinx/conf.py | 102 +++ .../sphinx/developer_guide/cia402_drive.rst | 220 +++++ .../sphinx/developer_guide/coe.rst | 37 + .../developer_guide/domain_construction.rst | 98 +++ .../sphinx/developer_guide/new_plugin.rst | 166 ++++ .../sphinx/developer_guide/safety.rst | 83 ++ .../sphinx/images/logo-icube.png | Bin 0 -> 204123 bytes ethercat_driver_ros2/sphinx/index.rst | 35 + ethercat_driver_ros2/sphinx/make.bat | 35 + .../sphinx/quickstart/configuration.rst | 74 ++ .../sphinx/quickstart/installation.rst | 189 +++++ .../sphinx/quickstart/usage.rst | 40 + .../sphinx/user_guide/config_cia402_drive.rst | 125 +++ .../user_guide/config_generic_slave.rst | 238 ++++++ .../config_use_case_motor_with_gear_box.rst | 286 +++++++ .../epos4_config_with_gear_box.yaml | 92 ++ .../sphinx/user_guide/sdo_async_com.rst | 57 ++ .../CMakeLists.txt | 89 ++ .../ethercat_plugins.xml | 5 + .../cia402_common_defs.hpp | 71 ++ .../generic_ec_cia402_drive.hpp | 88 ++ .../ethercat_generic_cia402_drive/package.xml | 23 + .../src/generic_ec_cia402_drive.cpp | 285 +++++++ .../test/test_generic_ec_cia402_drive.cpp | 324 ++++++++ .../test/test_generic_ec_cia402_drive.hpp | 52 ++ .../test/test_load_ec_modules.cpp | 26 + .../ethercat_generic_slave/CMakeLists.txt | 88 ++ .../ethercat_plugins.xml | 5 + .../generic_ec_slave.hpp | 76 ++ .../ethercat_generic_slave/package.xml | 22 + .../src/generic_ec_slave.cpp | 309 +++++++ .../test/test_generic_ec_slave.cpp | 254 ++++++ .../test/test_generic_ec_slave.hpp | 51 ++ .../test/test_load_ec_modules.cpp | 26 + ethercat_interface/CMakeLists.txt | 90 ++ .../include/ethercat_interface/ec_master.hpp | 218 +++++ .../ec_pdo_channel_manager.hpp | 249 ++++++ ...ec_pdo_group_interface_channel_manager.hpp | 278 +++++++ ...c_pdo_single_interface_channel_manager.hpp | 224 +++++ .../include/ethercat_interface/ec_safety.hpp | 161 ++++ .../ethercat_interface/ec_sdo_manager.hpp | 118 +++ .../include/ethercat_interface/ec_slave.hpp | 110 +++ .../ethercat_interface/ec_sync_manager.hpp | 86 ++ .../ethercat_interface/ec_transfer.hpp | 53 ++ ethercat_interface/package.xml | 20 + ethercat_interface/src/ec_master.cpp | 586 +++++++++++++ .../src/ec_pdo_channel_manager.cpp | 311 +++++++ ...ec_pdo_group_interface_channel_manager.cpp | 438 ++++++++++ ...c_pdo_single_interface_channel_manager.cpp | 190 +++++ ethercat_interface/src/ec_safety.cpp | 273 ++++++ .../test/test_ec_pdo_channel_manager.cpp | 387 +++++++++ ethercat_manager/CMakeLists.txt | 51 ++ .../data_convertion_tools.hpp | 421 ++++++++++ .../ethercat_manager/ec_master_async.hpp | 175 ++++ .../ethercat_manager/ec_master_async_io.hpp | 62 ++ ethercat_manager/package.xml | 21 + .../src/ethercat_sdo_srv_server.cpp | 213 +++++ ethercat_msgs/CMakeLists.txt | 22 + ethercat_msgs/package.xml | 18 + ethercat_msgs/srv/GetSdo.srv | 10 + ethercat_msgs/srv/SetSdo.srv | 9 + 88 files changed, 11210 insertions(+), 82 deletions(-) create mode 100644 CONTRIBUTING.md create mode 100644 INSTALL.md create mode 100644 LICENSE create mode 100644 ethercat_driver/CMakeLists.txt create mode 100644 ethercat_driver/ethercat_driver_plugin.xml create mode 100644 ethercat_driver/examples/configurations/beckhoff_ek1914.yaml create mode 100644 ethercat_driver/examples/configurations/beckhoff_el1918.yaml create mode 100644 ethercat_driver/examples/configurations/estop_ethercat_safety.yaml create mode 100644 ethercat_driver/examples/configurations/safety.ros2_control.xacro create mode 100644 ethercat_driver/examples/configurations/safety_estop.ros2_control.template.xacro create mode 100644 ethercat_driver/examples/configurations/test_config_ethercat_safety.yaml create mode 100644 ethercat_driver/examples/configurations/update_slave_config_path.py create mode 100644 ethercat_driver/include/ethercat_driver/ethercat_driver.hpp create mode 100644 ethercat_driver/include/ethercat_driver/ethercat_safety_driver.hpp create mode 100644 ethercat_driver/include/ethercat_driver/visibility_control.h create mode 100644 ethercat_driver/package.xml create mode 100644 ethercat_driver/src/ethercat_driver.cpp create mode 100644 ethercat_driver/src/ethercat_safety_driver.cpp create mode 100644 ethercat_driver/test/testHelper_ethercat_safety_driver.hpp create mode 100644 ethercat_driver/test/test_ethercat_safety_driver.cpp create mode 100644 ethercat_driver_ros2/CMakeLists.txt create mode 100644 ethercat_driver_ros2/doxygen/Doxyfile create mode 100644 ethercat_driver_ros2/package.xml create mode 100644 ethercat_driver_ros2/requirements.txt create mode 100644 ethercat_driver_ros2/sphinx/Makefile create mode 100644 ethercat_driver_ros2/sphinx/_static/css/custom.css create mode 100644 ethercat_driver_ros2/sphinx/conf.py create mode 100644 ethercat_driver_ros2/sphinx/developer_guide/cia402_drive.rst create mode 100644 ethercat_driver_ros2/sphinx/developer_guide/coe.rst create mode 100644 ethercat_driver_ros2/sphinx/developer_guide/domain_construction.rst create mode 100644 ethercat_driver_ros2/sphinx/developer_guide/new_plugin.rst create mode 100644 ethercat_driver_ros2/sphinx/developer_guide/safety.rst create mode 100644 ethercat_driver_ros2/sphinx/images/logo-icube.png create mode 100644 ethercat_driver_ros2/sphinx/index.rst create mode 100755 ethercat_driver_ros2/sphinx/make.bat create mode 100644 ethercat_driver_ros2/sphinx/quickstart/configuration.rst create mode 100644 ethercat_driver_ros2/sphinx/quickstart/installation.rst create mode 100644 ethercat_driver_ros2/sphinx/quickstart/usage.rst create mode 100644 ethercat_driver_ros2/sphinx/user_guide/config_cia402_drive.rst create mode 100644 ethercat_driver_ros2/sphinx/user_guide/config_generic_slave.rst create mode 100644 ethercat_driver_ros2/sphinx/user_guide/config_use_case_motor_with_gear_box.rst create mode 100644 ethercat_driver_ros2/sphinx/user_guide/epos4_config_with_gear_box.yaml create mode 100644 ethercat_driver_ros2/sphinx/user_guide/sdo_async_com.rst create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/CMakeLists.txt create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/ethercat_plugins.xml create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/cia402_common_defs.hpp create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/generic_ec_cia402_drive.hpp create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/package.xml create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/src/generic_ec_cia402_drive.cpp create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.cpp create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.hpp create mode 100644 ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_load_ec_modules.cpp create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/CMakeLists.txt create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/ethercat_plugins.xml create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/include/ethercat_generic_plugins/generic_ec_slave.hpp create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/package.xml create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/src/generic_ec_slave.cpp create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.cpp create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.hpp create mode 100644 ethercat_generic_plugins/ethercat_generic_slave/test/test_load_ec_modules.cpp create mode 100644 ethercat_interface/CMakeLists.txt create mode 100644 ethercat_interface/include/ethercat_interface/ec_master.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_pdo_channel_manager.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_pdo_group_interface_channel_manager.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_pdo_single_interface_channel_manager.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_safety.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_sdo_manager.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_slave.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_sync_manager.hpp create mode 100644 ethercat_interface/include/ethercat_interface/ec_transfer.hpp create mode 100644 ethercat_interface/package.xml create mode 100644 ethercat_interface/src/ec_master.cpp create mode 100644 ethercat_interface/src/ec_pdo_channel_manager.cpp create mode 100644 ethercat_interface/src/ec_pdo_group_interface_channel_manager.cpp create mode 100644 ethercat_interface/src/ec_pdo_single_interface_channel_manager.cpp create mode 100644 ethercat_interface/src/ec_safety.cpp create mode 100644 ethercat_interface/test/test_ec_pdo_channel_manager.cpp create mode 100644 ethercat_manager/CMakeLists.txt create mode 100644 ethercat_manager/include/ethercat_manager/data_convertion_tools.hpp create mode 100644 ethercat_manager/include/ethercat_manager/ec_master_async.hpp create mode 100644 ethercat_manager/include/ethercat_manager/ec_master_async_io.hpp create mode 100644 ethercat_manager/package.xml create mode 100644 ethercat_manager/src/ethercat_sdo_srv_server.cpp create mode 100644 ethercat_msgs/CMakeLists.txt create mode 100644 ethercat_msgs/package.xml create mode 100644 ethercat_msgs/srv/GetSdo.srv create mode 100644 ethercat_msgs/srv/SetSdo.srv diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 0000000..ff08426 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,66 @@ +# Contributing Guidelines +Thank you for your interest in contributing to `ethercat_driver_ros2`. Whether it's a bug report, new feature, correction, or additional documentation, we greatly value feedback and contributions from the community. + +Please read through this document before submitting any issues or pull requests to ensure we have all the necessary information to effectively respond to your bug report or contribution. + + +## Reporting Bugs/Feature Requests +We welcome you to use the GitHub issue tracker to report bugs or suggest features. + +When filing an issue, please check [existing open][issues], or [recently closed][closed-issues], issues to make sure somebody else hasn't already reported the issue. + +Please try to include as much information as you can. Details like these are incredibly useful: + +* A reproducible test case or series of steps +* The version of our code being used +* Any modifications you've made relevant to the bug +* Anything unusual about your environment or deployment + +## Installation of pre-commit checks and hooks +To accelerate the rate of development and to ensure that the code is formatted correctly, we use pre-commit checks and hooks. To install these, please follow the instructions below: + 1. Install packages used to check the code: +```bash +$ sudo apt-get -y install clang-format-10 python3-autopep8 ament-cmake-uncrustify python3-ament-cpplint python3-ament-lint-cmake python3-ament-copyright +$ pip install doc8 +``` + 2. Install pre-commit: `pip install pre-commit` + 3. Configure hook such that it runs on every commit: `pre-commit install` + +You can run pre-commit manually on the repository to check if the code is formatted correctly. +To do so, run `pre-commit run --all-files` in the root of the repository. + +## Contributing via Pull Requests +Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that: + +1. You are working against the latest source on the *main* branch. +2. You check existing open, and recently merged, pull requests to make sure someone else hasn't addressed the problem already. +3. You have used pre-commit checks to correct any formatting issues. +4. You open an issue to discuss any significant work - we would hate for your time to be wasted. + +**NOTE:** For contributing to the documentation, contribute to the sphinx pages placed in the ethercat_driver_ros2/sphinx folder. + +To send us a pull request, please: + +1. Fork the repository. +2. Modify the source; please focus on the specific change you are contributing. + If you also reformat all the code, it will be hard for us to focus on your change. +1. Ensure local tests pass. +2. Commit to your fork using clear commit messages. +3. Send a pull request, answering any default questions in the pull request interface. +4. Pay attention to any automated CI failures reported in the pull request, and stay involved in the conversation. + +GitHub provides additional documentation on [forking a repository](https://help.github.com/articles/fork-a-repo/) and [creating a pull request](https://help.github.com/articles/creating-a-pull-request/). + + +## Licensing +Any contribution that you make to this repository will be under the Apache 2 License, as dictated by that [license](http://www.apache.org/licenses/LICENSE-2.0.html): + +~~~ +5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. +~~~ diff --git a/INSTALL.md b/INSTALL.md new file mode 100644 index 0000000..b99108b --- /dev/null +++ b/INSTALL.md @@ -0,0 +1,102 @@ +# Installation +***Required setup : Ubuntu 22.04 LTS*** + +## 1. Installing EtherLab +The proposed development builds upon the [IgH EtherCAT Master](https://etherlab.org/en/ethercat/). Installation steps are summarized here: +- Install required tools: + ```shell + $ sudo apt-get update + $ sudo apt-get upgrade + $ sudo apt-get install git autoconf libtool pkg-config make build-essential net-tools + ``` +- Setup sources for the EtherCAT Master: + ```shell + $ git clone https://gitlab.com/etherlab.org/ethercat.git + $ cd ethercat + $ git checkout stable-1.5 + $ sudo rm /usr/bin/ethercat + $ sudo rm /etc/init.d/ethercat + $ ./bootstrap # to create the configure script + ``` +- Configure, build and install libs and kernel modules: + ```shell + $ ./configure --prefix=/usr/local/etherlab --disable-8139too --disable-eoe --enable-generic + + $ make all modules + $ sudo make modules_install install + $ sudo depmod + ``` + **NOTE**: This step is needed every time the Linux kernel is updated. +- Configure system: + ```shell + $ sudo ln -s /usr/local/etherlab/bin/ethercat /usr/bin/ + $ sudo ln -s /usr/local/etherlab/etc/init.d/ethercat /etc/init.d/ethercat + $ sudo mkdir -p /etc/sysconfig + $ sudo cp /usr/local/etherlab/etc/sysconfig/ethercat /etc/sysconfig/ethercat + ``` +- Create a new `udev` rule: + ```shell + $ sudo gedit /etc/udev/rules.d/99-EtherCAT.rules + ``` + containing: + ```shell + KERNEL=="EtherCAT[0-9]*", MODE="0664" + ``` + +- Configure the network adapter for EtherCAT: + + ```shell + $ sudo gedit /etc/sysconfig/ethercat + ``` + In the configuration file specify the mac address of the network card to be used and its driver + ```shell + MASTER0_DEVICE="ff:ff:ff:ff:ff:ff" # mac address + DEVICE_MODULES="generic" + ``` + +Now you can start the EtherCAT master: +```shell +$ sudo /etc/init.d/ethercat start +``` +it should print +```shell +Starting EtherCAT master 1.5.2 done +``` + +You can check connected slaves: +```shell +$ ethercat slaves +``` +It should print information of connected slave device: +```shell +<id> <alias>:<position> <device_state> + <device_name> +``` +Example: +```shell +0 0:0 PREOP + <device_0_name> +0 0:1 PREOP + <device_1_name> +``` + +## 2. Building `ethercat_driver_ros2` +1. Install `ros2` packages. The current development is based of `ros2 humble`. Installation steps are described [here](https://docs.ros.org/en/humble/Installation.html). +2. Source your `ros2` environment: + ```shell + source /opt/ros/humble/setup.bash + ``` + **NOTE**: The ros2 environment needs to be sources in every used terminal. If only one distribution of ros2 is used, it can be added to the `~/.bashrc` file. +3. Install `colcon` and its extensions : + ```shell + sudo apt install python3-colcon-common-extensions + ``` +3. Create a new ros2 workspace: + ```shell + mkdir ~/ros2_ws/src + ``` +4. Pull relevant packages, install dependencies, compile, and source the workspace by using: + ```shell + cd ~/ros2_ws + git clone https://github.com/ICube-Robotics/ethercat_driver_ros2.git src/ethercat_driver_ros2 + rosdep install --ignore-src --from-paths . -y -r + colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --symlink-install + source install/setup.bash + ``` diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..261eeb9 --- /dev/null +++ b/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. diff --git a/README.md b/README.md index 7fa87e3..f662204 100644 --- a/README.md +++ b/README.md @@ -1,93 +1,27 @@ # ethercat_driver_ros2 +[](https://opensource.org/licenses/Apache-2.0) +[](https://zenodo.org/badge/latestdoi/491930126) +[](https://github.com/ICube-Robotics/ethercat_driver_ros2/actions/workflows/ci.yml) +Implementation of a `Hardware Interface` for simple Ethercat module integration with [`ros2_control`](https://github.com/ros-controls/ros2_control) and building upon [IgH EtherCAT Master for Linux](https://etherlab.org/en/ethercat/). +## About +[EtherCAT](https://www.ethercat.org/default.htm) provides applications with the capacity of reliable, real-time communication between systems and is therefore a common industrial standard. In order to simplify the development/deployment of new application using EtherCAT modules, the `ethercat_driver` allows to combine them with [`ros2_control`](https://github.com/ros-controls/ros2_control). This driver proposes a generic ways to parametrise and assemble `Hardware Interfaces` based on EtherCAT modules that can be defined using parameter files. -## Getting started +**For more information, please check the [documentation](https://ICube-Robotics.github.io/ethercat_driver_ros2/).** -To make it easy for you to get started with GitLab, here's a list of recommended next steps. +## Acknowledgments +Parts of the driver are based on the implementation of [`SimplECAT`](https://bitbucket.org/bsoe/simplecat/src/master/). -Already a pro? Just edit this README.md and make it your own. Want to make it easy? [Use the template at the bottom](#editing-this-readme)! +## Contacts ## + -## Add your files +[ICube Laboratory](https://icube.unistra.fr), [University of Strasbourg](https://www.unistra.fr/), France -- [ ] [Create](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#create-a-file) or [upload](https://docs.gitlab.com/ee/user/project/repository/web_editor.html#upload-a-file) files -- [ ] [Add files using the command line](https://docs.gitlab.com/ee/gitlab-basics/add-file.html#add-a-file-using-the-command-line) or push an existing Git repository with the following command: +__Manuel Yguel:__ [yguel@unistra.fr](mailto:yguel@unistra.fr) -``` -cd existing_repo -git remote add origin https://git.unistra.fr/zanne.philippe/ethercat_driver_ros2.git -git branch -M main -git push -uf origin main -``` +__Laurent Barbé:__ [laurent.barbe@unistra.fr](mailto:laurent.barbe@unistra.fr) -## Integrate with your tools +__Philippe Zanne:__ [philippe.zanne@unistra.fr](mailto:philippe.zanne@unistra.fr) -- [ ] [Set up project integrations](https://git.unistra.fr/zanne.philippe/ethercat_driver_ros2/-/settings/integrations) - -## Collaborate with your team - -- [ ] [Invite team members and collaborators](https://docs.gitlab.com/ee/user/project/members/) -- [ ] [Create a new merge request](https://docs.gitlab.com/ee/user/project/merge_requests/creating_merge_requests.html) -- [ ] [Automatically close issues from merge requests](https://docs.gitlab.com/ee/user/project/issues/managing_issues.html#closing-issues-automatically) -- [ ] [Enable merge request approvals](https://docs.gitlab.com/ee/user/project/merge_requests/approvals/) -- [ ] [Set auto-merge](https://docs.gitlab.com/ee/user/project/merge_requests/merge_when_pipeline_succeeds.html) - -## Test and Deploy - -Use the built-in continuous integration in GitLab. - -- [ ] [Get started with GitLab CI/CD](https://docs.gitlab.com/ee/ci/quick_start/index.html) -- [ ] [Analyze your code for known vulnerabilities with Static Application Security Testing (SAST)](https://docs.gitlab.com/ee/user/application_security/sast/) -- [ ] [Deploy to Kubernetes, Amazon EC2, or Amazon ECS using Auto Deploy](https://docs.gitlab.com/ee/topics/autodevops/requirements.html) -- [ ] [Use pull-based deployments for improved Kubernetes management](https://docs.gitlab.com/ee/user/clusters/agent/) -- [ ] [Set up protected environments](https://docs.gitlab.com/ee/ci/environments/protected_environments.html) - -*** - -# Editing this README - -When you're ready to make this README your own, just edit this file and use the handy template below (or feel free to structure it however you want - this is just a starting point!). Thanks to [makeareadme.com](https://www.makeareadme.com/) for this template. - -## Suggestions for a good README - -Every project is different, so consider which of these sections apply to yours. The sections used in the template are suggestions for most open source projects. Also keep in mind that while a README can be too long and detailed, too long is better than too short. If you think your README is too long, consider utilizing another form of documentation rather than cutting out information. - -## Name -Choose a self-explaining name for your project. - -## Description -Let people know what your project can do specifically. Provide context and add a link to any reference visitors might be unfamiliar with. A list of Features or a Background subsection can also be added here. If there are alternatives to your project, this is a good place to list differentiating factors. - -## Badges -On some READMEs, you may see small images that convey metadata, such as whether or not all the tests are passing for the project. You can use Shields to add some to your README. Many services also have instructions for adding a badge. - -## Visuals -Depending on what you are making, it can be a good idea to include screenshots or even a video (you'll frequently see GIFs rather than actual videos). Tools like ttygif can help, but check out Asciinema for a more sophisticated method. - -## Installation -Within a particular ecosystem, there may be a common way of installing things, such as using Yarn, NuGet, or Homebrew. However, consider the possibility that whoever is reading your README is a novice and would like more guidance. Listing specific steps helps remove ambiguity and gets people to using your project as quickly as possible. If it only runs in a specific context like a particular programming language version or operating system or has dependencies that have to be installed manually, also add a Requirements subsection. - -## Usage -Use examples liberally, and show the expected output if you can. It's helpful to have inline the smallest example of usage that you can demonstrate, while providing links to more sophisticated examples if they are too long to reasonably include in the README. - -## Support -Tell people where they can go to for help. It can be any combination of an issue tracker, a chat room, an email address, etc. - -## Roadmap -If you have ideas for releases in the future, it is a good idea to list them in the README. - -## Contributing -State if you are open to contributions and what your requirements are for accepting them. - -For people who want to make changes to your project, it's helpful to have some documentation on how to get started. Perhaps there is a script that they should run or some environment variables that they need to set. Make these steps explicit. These instructions could also be useful to your future self. - -You can also document commands to lint the code or run tests. These steps help to ensure high code quality and reduce the likelihood that the changes inadvertently break something. Having instructions for running tests is especially helpful if it requires external setup, such as starting a Selenium server for testing in a browser. - -## Authors and acknowledgment -Show your appreciation to those who have contributed to the project. - -## License -For open source projects, say how it is licensed. - -## Project status -If you have run out of energy or time for your project, put a note at the top of the README saying that development has slowed down or stopped completely. Someone may choose to fork your project or volunteer to step in as a maintainer or owner, allowing your project to keep going. You can also make an explicit request for maintainers. +__Maciej Bednarczyk:__ [m.bednarczyk@unistra.fr](mailto:m.bednarczyk@unistra.fr), @github: [mcbed](https://github.com/mcbed) diff --git a/ethercat_driver/CMakeLists.txt b/ethercat_driver/CMakeLists.txt new file mode 100644 index 0000000..65134a4 --- /dev/null +++ b/ethercat_driver/CMakeLists.txt @@ -0,0 +1,154 @@ +cmake_minimum_required(VERSION 3.8) +project(ethercat_driver) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) + +find_package(hardware_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(ethercat_interface REQUIRED) +find_package(yaml_cpp_vendor REQUIRED) + +file(GLOB_RECURSE PLUGINS_SRC src/*.cpp) + +add_library(${PROJECT_NAME} ${PLUGINS_SRC}) + +target_compile_features(${PROJECT_NAME} PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +target_include_directories(${PROJECT_NAME} PUBLIC + $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> + $<INSTALL_INTERFACE:include> +) + +ament_target_dependencies( + ${PROJECT_NAME} + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle + ethercat_interface + yaml_cpp_vendor +) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${PROJECT_NAME} PRIVATE "ETHERCAT_DRIVER_BUILDING_LIBRARY") + +# prevent pluginlib from using boost +target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +pluginlib_export_plugin_description_file(hardware_interface ethercat_driver_plugin.xml) + +# INSTALL +install( + TARGETS ${PROJECT_NAME} + DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) +install( + DIRECTORY include/ + DESTINATION include +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + find_package(ament_cmake_gtest REQUIRED) + find_package(ethercat_interface REQUIRED) + ament_lint_auto_find_test_dependencies() + + # Ensure test data is copied to the build directory + set(CFG_FILES + safety.ros2_control.xacro + safety_estop.ros2_control.template.xacro + estop_ethercat_safety.yaml + test_config_ethercat_safety.yaml + beckhoff_ek1914.yaml + beckhoff_el1918.yaml + ) + + set(CFG_IN ${CMAKE_CURRENT_SOURCE_DIR}/examples/configurations) + set(CFG_DST ${CMAKE_CURRENT_BINARY_DIR}/test_configurations) + list(TRANSFORM CFG_FILES PREPEND "${CFG_IN}" OUTPUT_VARIABLE CFG_SRC) + + # Ensure the destination directory exists + file(MAKE_DIRECTORY ${CFG_DST}) + + # List to keep track of the output files + set(CFG_OUT) + + foreach(file ${CFG_FILES}) + set(src_file "${CMAKE_CURRENT_SOURCE_DIR}/examples/configurations/${file}") + set(dst_file "${CFG_DST}/${file}") + + add_custom_command( + OUTPUT ${dst_file} + COMMAND ${CMAKE_COMMAND} -E copy ${src_file} ${dst_file} + DEPENDS ${src_file} + COMMENT "Copying ${src_file} to ${dst_file}" + ) + + list(APPEND CFG_OUT ${dst_file}) + endforeach() + # message(WARNING "Copying ${CFG_SRC} to ${CFG_DST}") + + # Create a custom target to group the copy commands + add_custom_target(copy_safety_config ALL DEPENDS ${CFG_OUT}) + + set(UP_PY ${CMAKE_CURRENT_SOURCE_DIR}/examples/configurations/update_slave_config_path.py) + set(UP_IN ${CFG_DST}/safety_estop.ros2_control.template.xacro) + set(UP_OUT ${CFG_DST}/safety_estop.ros2_control.xacro) + set(UP_DEPS ${UP_PY} ${UP_IN}) + + # message(WARNING "Running ${UP_PY} ${UP_IN} -p ${CFG_DST} -o ${UP_OUT}") + add_custom_command( + OUTPUT ${UP_OUT} + COMMAND ${CMAKE_COMMAND} -E echo "Running update_slave_config_path.py" + COMMAND ${CMAKE_COMMAND} -E env python3 ${UP_PY} ${UP_IN} -p ${CFG_DST} -o ${UP_OUT} + DEPENDS ${UP_DEPS} + COMMENT "Running update_slave_config_path.py" + ) + + add_custom_target(update_slave_config_path ALL DEPENDS ${UP_OUT}) + + ament_add_gmock(test_ethercat_safety_driver test/test_ethercat_safety_driver.cpp) + target_include_directories(test_ethercat_safety_driver PRIVATE include) + + target_compile_definitions(test_ethercat_safety_driver PRIVATE "TEST_RESOURCES_DIRECTORY=\"${CFG_DST}\"") + + target_link_libraries(test_ethercat_safety_driver + ${PROJECT_NAME} + ) + ament_target_dependencies(test_ethercat_safety_driver + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle + ethercat_interface + yaml_cpp_vendor + ) +endif() + +## EXPORTS +ament_export_include_directories( + include +) +ament_export_libraries( + ${PROJECT_NAME} +) +ament_export_dependencies( + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle + ethercat_interface + yaml_cpp_vendor +) +ament_package() diff --git a/ethercat_driver/ethercat_driver_plugin.xml b/ethercat_driver/ethercat_driver_plugin.xml new file mode 100644 index 0000000..94b9352 --- /dev/null +++ b/ethercat_driver/ethercat_driver_plugin.xml @@ -0,0 +1,12 @@ +<library path="ethercat_driver"> + <class name="ethercat_driver/EthercatDriver" type="ethercat_driver::EthercatDriver" base_class_type="hardware_interface::SystemInterface"> + <description> + EtherCAT Driver for ros2_control. + </description> + </class> + <class name="ethercat_driver/EthercatSafetyDriver" type="ethercat_driver::EthercatSafetyDriver" base_class_type="hardware_interface::SystemInterface"> + <description> + EtherCAT Safety Driver for ros2_control. + </description> + </class> +</library> diff --git a/ethercat_driver/examples/configurations/beckhoff_ek1914.yaml b/ethercat_driver/examples/configurations/beckhoff_ek1914.yaml new file mode 100644 index 0000000..fad8596 --- /dev/null +++ b/ethercat_driver/examples/configurations/beckhoff_ek1914.yaml @@ -0,0 +1,93 @@ +# Configuration file for Beckhoff EK1914 +# Description : Coupler, 4-channel digital input, +# 2-channel digital safety input, 4-channel digital output, +# 2-channel digital safety output, 24 V DC, 1 ms (TBC). +vendor_id: 0x00000002 +product_id: 0x077a2c52 +tpdo: # Slave-OUT & Master-IN + - index: 0x1a00 + channels: + - { index: 0x6000, sub_index: 0x01, type: int8 } + - { index: 0x6001, sub_index: 0x01, type: bool, mask: 1 } + - { index: 0x6001, sub_index: 0x02, type: bool, mask: 2 } + - { index: 0x0000, sub_index: 0x00, type: bit6 } + - { index: 0x6000, sub_index: 0x03, type: int16 } + - { index: 0x6000, sub_index: 0x02, type: int16 } + - index: 0x1a01 + channels: + - { + index: 0x6010, + sub_index: 0x01, + type: bool, + mask: 1, + state_interface: input_1, + } + - { + index: 0x6010, + sub_index: 0x02, + type: bool, + mask: 2, + state_interface: input_2, + } + - { + index: 0x6010, + sub_index: 0x03, + type: bool, + mask: 4, + state_interface: input_3, + } + - { + index: 0x6010, + sub_index: 0x04, + type: bool, + mask: 8, + state_interface: input_4, + } + - { index: 0x0000, sub_index: 0x00, type: bit12 } +rpdo: # Slave-IN & Master-OUT + - index: 0x1600 + channels: + - { index: 0x7000, sub_index: 0x01, type: int8 } + - { index: 0x7001, sub_index: 0x01, type: bool, mask: 1 } + - { index: 0x7001, sub_index: 0x02, type: bool, mask: 2 } + - { index: 0x0000, sub_index: 0x00, type: bit6 } + - { index: 0x7000, sub_index: 0x03, type: int16 } + - { index: 0x7000, sub_index: 0x02, type: int16 } + - index: 0x1601 + channels: + - { + index: 0x7010, + sub_index: 0x01, + type: bool, + mask: 1, + command_interface: output_1, + } + - { + index: 0x7010, + sub_index: 0x02, + type: bool, + mask: 2, + command_interface: output_2, + } + - { + index: 0x7010, + sub_index: 0x03, + type: bool, + mask: 4, + command_interface: output_3, + } + - { + index: 0x7010, + sub_index: 0x04, + type: bool, + mask: 8, + command_interface: output_4, + } + - { index: 0x7010, sub_index: 0x05, type: bool, mask: 16 } + - { index: 0x7010, sub_index: 0x06, type: bool, mask: 32 } + - { index: 0x0000, sub_index: 0x00, type: bit10 } +sm: + - { index: 0, type: output, watchdog: disable } + - { index: 1, type: input, watchdog: disable } + - { index: 2, type: output, pdo: rpdo, watchdog: disable } + - { index: 3, type: input, pdo: tpdo, watchdog: disable } diff --git a/ethercat_driver/examples/configurations/beckhoff_el1918.yaml b/ethercat_driver/examples/configurations/beckhoff_el1918.yaml new file mode 100644 index 0000000..26a6ae0 --- /dev/null +++ b/ethercat_driver/examples/configurations/beckhoff_el1918.yaml @@ -0,0 +1,41 @@ +# Configuration file for Beckhoff EL1918 +# Description : EtherCAT safety Terminal, master version, 8-channel digital safety input, 24 V DC, 10 us (TBC). +vendor_id: 0x00000002 +product_id: 0x077e3052 +tpdo: # TxPDO = transmit PDO Mapping, MASTER IN SLAVE OUT + - index: 0x1a00 + channels: + - { index: 0x6080, sub_index: 0x01, type: int8 } + - { index: 0x6081, sub_index: 0x01, type: int8 } + - { index: 0x6080, sub_index: 0x03, type: int16 } + - { index: 0x6080, sub_index: 0x02, type: int16 } + - index: 0x1bff + channels: + - { index: 0xf100, sub_index: 0x01, type: int8 } + - { index: 0xf100, sub_index: 0x02, type: int8 } +rpdo: # RxPDO = receive PDO Mapping, MASTER OUT SLAVE IN + - index: 0x1600 + channels: + - { index: 0x7080, sub_index: 0x01, type: int8 } + - { index: 0x7081, sub_index: 0x01, type: int8 } + - { index: 0x7080, sub_index: 0x03, type: int16 } + - { index: 0x7080, sub_index: 0x02, type: int16 } + - index: 0x17f0 + channels: + - { + index: 0xf788, + sub_index: 0x00, + type: int8, + command_interface: safety_states, # Bit 0 is safety error ACK and Bit 1 is safety RUN + } + - index: 0x17ff + channels: + - { index: 0x0000, sub_index: 0x00, type: bit16 } + +sm: # Sync Manager + - { index: 0, type: output, watchdog: disable } + - { index: 1, type: input, watchdog: disable } + - { index: 2, type: output, pdo: rpdo, watchdog: disable } + - { index: 3, type: input, pdo: tpdo, watchdog: disable } + - { index: 4, type: output, watchdog: disable } + - { index: 5, type: input, watchdog: disable } diff --git a/ethercat_driver/examples/configurations/estop_ethercat_safety.yaml b/ethercat_driver/examples/configurations/estop_ethercat_safety.yaml new file mode 100644 index 0000000..de8ae4b --- /dev/null +++ b/ethercat_driver/examples/configurations/estop_ethercat_safety.yaml @@ -0,0 +1,11 @@ +# Configuration file for the EtherCAT safety network of the estop test system +nets: + - name: safety_net + safety_master: el1918 + transfers: + - size: 6 + in: { ec_module: ek1914, index: 0x6000, subindex: 0x01 } + out: { ec_module: el1918, index: 0x7080, subindex: 0x01 } + - size: 6 + in: { ec_module: el1918, index: 0x6080, subindex: 0x01 } + out: { ec_module: ek1914, index: 0x7000, subindex: 0x01 } diff --git a/ethercat_driver/examples/configurations/safety.ros2_control.xacro b/ethercat_driver/examples/configurations/safety.ros2_control.xacro new file mode 100644 index 0000000..5fed374 --- /dev/null +++ b/ethercat_driver/examples/configurations/safety.ros2_control.xacro @@ -0,0 +1,52 @@ +<?xml version="1.0"?> +<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> + <ros2_control name="ec_safety_test_config" type="system"> + <hardware> + <plugin>ethercat_driver/EthercatDriver</plugin> + <param name="master_id">0</param> + <param name="control_frequency">100</param> + <param name="fsoe_config">test_config_ethercat_safety.yaml</param> + </hardware> + + <sensor name="limit_switches"> + <state_interface name="limit_switch_left" /> + <state_interface name="limit_switch_right" /> + <ec_module name="limit_switches_on_EL1018"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">6</param> + <param name="slave_config">beckhoff_el1018.yaml</param> + </ec_module> + </sensor> + + <sensor name="encoder"> + <state_interface name="position" /> + <command_interface name="reset" /> + <ec_module name="encoder_on_EL5101"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">2</param> + <param name="slave_config">beckhoff_el5101.yaml</param> + </ec_module> + </sensor> + + <joint name="base_to_charriot"> + <state_interface name="position" /> + <state_interface name="velocity" /> + <state_interface name="effort" /> + <command_interface name="position" /> + <command_interface name="velocity" /> + <command_interface name="effort" /> + <command_interface name="reset_fault" /> + <ec_module name="MAXON_on_EPOS3"> + <plugin>ethercat_generic_plugins/EcCiA402Drive</plugin> + <param name="alias">0</param> + <param name="position">0</param> + <!-- Available modes of operation = position 8, velocity 9, effort 10, homing 6 --> + <param name="mode_of_operation">9</param> + <!-- epos3 --> + <param name="slave_config">maxon_epos3.yaml</param> + </ec_module> + </joint> + </ros2_control> +</robot> diff --git a/ethercat_driver/examples/configurations/safety_estop.ros2_control.template.xacro b/ethercat_driver/examples/configurations/safety_estop.ros2_control.template.xacro new file mode 100644 index 0000000..e2ff346 --- /dev/null +++ b/ethercat_driver/examples/configurations/safety_estop.ros2_control.template.xacro @@ -0,0 +1,38 @@ +<?xml version="1.0"?> +<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> + <ros2_control name="ec_safety_estop_test_config" type="system"> + <hardware> + <plugin>ethercat_driver/EthercatSafetyDriver</plugin> + <param name="master_id">0</param> + <param name="control_frequency">100</param> + <param name="fsoe_config">estop_ethercat_safety.yaml</param> + </hardware> + + <gpio name="el1918"> + <ec_module name="el1918"> + <param name="alias">0</param> + <param name="position">1</param> + <param name="slave_config">beckhoff_el1918.yaml</param> + <command_interface name="safety_states"/> + <!-- bit 0 is safety_error_ack and bit 1 is safety_run --> + </ec_module> + </gpio> + + <gpio name="ek1914"> + <state_interface name="input_1" /> + <state_interface name="input_2" /> + <state_interface name="input_3" /> + <state_interface name="input_4" /> + <command_interface name="output_1" /> + <command_interface name="output_2" /> + <command_interface name="output_3" /> + <command_interface name="output_4" /> + <ec_module name="ek1914"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">0</param> + <param name="slave_config">beckhoff_ek1914.yaml</param> + </ec_module> + </gpio> + </ros2_control> +</robot> diff --git a/ethercat_driver/examples/configurations/test_config_ethercat_safety.yaml b/ethercat_driver/examples/configurations/test_config_ethercat_safety.yaml new file mode 100644 index 0000000..b3a29c9 --- /dev/null +++ b/ethercat_driver/examples/configurations/test_config_ethercat_safety.yaml @@ -0,0 +1,27 @@ +# Configuration file for the EtherCAT safety network of the estop test system +safety_modules: + - name: s2 + plugin: ethercat_generic_plugins/GenericEcSlave + parameters: { alias: 0, position: 1, slave_config: safety_slave_s2.yaml } + - name: m1 + plugin: ethercat_generic_plugins/GenericEcSlave + parameters: { alias: 0, position: 4, slave_config: safety_master.yaml } + - name: m2 + plugin: ethercat_generic_plugins/GenericEcSlave + parameters: { alias: 0, position: 5, slave_config: safety_master.yaml } +nets: + - name: n1 + safety_master: m1 + transfers: + - size: 18 + in: { ec_module: s1, index: 0x607a, subindex: 0x02 } + out: { ec_module: s2, index: 0x60ff, subindex: 0x04 } + - size: 42 + in: { ec_module: s1, index: 0x707a, subindex: 0x01 } + out: { ec_module: s3, index: 0x10ff, subindex: 0x01 } + - name: n2 + safety_master: m2 + transfers: + - size: 18 + in: { ec_module: q1, index: 0x607a, subindex: 0x06 } + out: { ec_module: q2, index: 0x60ff, subindex: 0x03 } diff --git a/ethercat_driver/examples/configurations/update_slave_config_path.py b/ethercat_driver/examples/configurations/update_slave_config_path.py new file mode 100644 index 0000000..da065bd --- /dev/null +++ b/ethercat_driver/examples/configurations/update_slave_config_path.py @@ -0,0 +1,68 @@ +#!/usr/bin/env python3 +# Copyright 2024 ICUBE Laboratory, University of Strasbourg +# +# 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. +# Author: Manuel YGUEL (yguel.robotics@gmail.com) + +# Executable python3 script to update the configuration of a slave device + +from lxml import etree +import os +import sys +import click + + +def prepend_slave_config_xml_tag(xml_file, prepend_path, output_file=None): + """ + Update the slave_config path in the xml file by prepending the build path. + + Open the xml file, search for the tags param in ec_module + that have name="slave_config" as attribute and update the slave_config + file path by appending the prepend_path to the existing path + """ + tree = etree.parse(xml_file) + find_all_param = tree.findall('.//param') + for param in find_all_param: + if param.attrib.get('name') == 'slave_config': + print(f"Found slave_config path: {param.text}") + param.text = os.path.join(prepend_path, param.text) + print(f"Updated slave_config path: {param.text}") + if param.attrib.get('name') == 'safety': + print(f"Found safety path: {param.text}") + param.text = os.path.join(prepend_path, param.text) + print(f"Updated safety path: {param.text}") + if output_file: + tree.write(output_file, pretty_print=True, + xml_declaration=True, encoding='UTF-8') + else: + tree.write(xml_file, pretty_print=True, + xml_declaration=True, encoding='UTF-8') + + +@click.command() +@click.argument('xml_file', type=click.Path(exists=True)) +@click.option('--prepend_path', '-p', type=click.Path(exists=True), + help='Prepend path', required=True) +@click.option('--output_file', '-o', type=click.Path(exists=False), + help='Output file', default=None) +def main(xml_file, prepend_path, output_file): + prepend_slave_config_xml_tag(xml_file, prepend_path, output_file) + msg = f"Updated the slave config path in {xml_file} with {prepend_path}" + if output_file: + msg += f" and saved to {output_file}" + else: + msg += f" and saved to {xml_file}" + print(msg) + return 0 + + +if __name__ == '__main__': + sys.exit(main()) diff --git a/ethercat_driver/include/ethercat_driver/ethercat_driver.hpp b/ethercat_driver/include/ethercat_driver/ethercat_driver.hpp new file mode 100644 index 0000000..b739931 --- /dev/null +++ b/ethercat_driver/include/ethercat_driver/ethercat_driver.hpp @@ -0,0 +1,135 @@ +// Copyright 2022 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_DRIVER__ETHERCAT_DRIVER_HPP_ +#define ETHERCAT_DRIVER__ETHERCAT_DRIVER_HPP_ + +#include <unordered_map> +#include <memory> +#include <string> +#include <vector> +#include <pluginlib/class_loader.hpp> +#include "hardware_interface/handle.hpp" +#include "hardware_interface/hardware_info.hpp" +#include "hardware_interface/system_interface.hpp" +#include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "rclcpp/macros.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include "ethercat_driver/visibility_control.h" +#include "ethercat_interface/ec_slave.hpp" +#include "ethercat_interface/ec_master.hpp" + +using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; + +namespace ethercat_driver +{ + +class EthercatDriver : public hardware_interface::SystemInterface +{ +public: + RCLCPP_SHARED_PTR_DEFINITIONS(EthercatDriver) + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_cleanup(const rclcpp_lifecycle::State & previous_state) override; + + ETHERCAT_DRIVER_PUBLIC + std::vector<hardware_interface::StateInterface> export_state_interfaces() override; + + ETHERCAT_DRIVER_PUBLIC + std::vector<hardware_interface::CommandInterface> export_command_interfaces() override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_activate(const rclcpp_lifecycle::State & previous_state) override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_shutdown(const rclcpp_lifecycle::State & previous_state) override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_error(const rclcpp_lifecycle::State & previous_state) override; + + ETHERCAT_DRIVER_PUBLIC + hardware_interface::return_type read(const rclcpp::Time &, const rclcpp::Duration &) override; + + ETHERCAT_DRIVER_PUBLIC + hardware_interface::return_type write(const rclcpp::Time &, const rclcpp::Duration &) override; + +protected: + std::vector<std::unordered_map<std::string, std::string>> getEcModuleParam( + const std::string & urdf, + const std::string & component_name, + const std::string & component_type); + + uint16_t getAliasOrDefaultAlias( + const std::unordered_map<std::string, + std::string> & slave_parameters); + + virtual CallbackReturn setupMaster(); + + CallbackReturn configClockReference(); + + CallbackReturn configNetwork(); + + bool deactivate_all_modules(const rclcpp::Duration & timeout); + +protected: + bool deactivate_all_modules_once(); + +protected: + std::vector<std::shared_ptr<ethercat_interface::EcSlave>> ec_modules_; + std::vector<std::unordered_map<std::string, std::string>> ec_module_parameters_; + + std::vector<std::vector<double>> hw_joint_commands_; + std::vector<std::vector<double>> hw_sensor_commands_; + std::vector<std::vector<double>> hw_gpio_commands_; + std::vector<std::vector<double>> hw_joint_states_; + std::vector<std::vector<double>> hw_sensor_states_; + std::vector<std::vector<double>> hw_gpio_states_; + + pluginlib::ClassLoader<ethercat_interface::EcSlave> ec_loader_{ + "ethercat_interface", "ethercat_interface::EcSlave"}; + + double control_frequency_; + + std::shared_ptr<ethercat_interface::EcMaster> master_; + std::mutex ec_configure_mutex_; + bool configured_; + std::mutex ec_activate_mutex_; + bool activated_; + +protected: + rclcpp::Clock monotonic_clock_; + rclcpp::Clock system_clock_; + rclcpp::Duration activate_timeout_ = rclcpp::Duration(10, 0); // 10 seconds + rclcpp::Duration deactivate_timeout_ = rclcpp::Duration(10, 0); // 10 seconds + rclcpp::Duration cleanup_timeout_ = rclcpp::Duration(10, 0); // 10 seconds + + bool in_past = false; + rclcpp::Time past_time_; + + bool write_data_ = false; + +}; +} // namespace ethercat_driver + +#endif // ETHERCAT_DRIVER__ETHERCAT_DRIVER_HPP_ diff --git a/ethercat_driver/include/ethercat_driver/ethercat_safety_driver.hpp b/ethercat_driver/include/ethercat_driver/ethercat_safety_driver.hpp new file mode 100644 index 0000000..b35c6de --- /dev/null +++ b/ethercat_driver/include/ethercat_driver/ethercat_safety_driver.hpp @@ -0,0 +1,85 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_DRIVER__ETHERCAT_SAFETY_DRIVER_HPP_ +#define ETHERCAT_DRIVER__ETHERCAT_SAFETY_DRIVER_HPP_ + +#include <vector> +#include <unordered_map> +#include <memory> +#include <string> + +#include "yaml-cpp/yaml.h" + +#include "ethercat_driver/ethercat_driver.hpp" +#include "ethercat_interface/ec_safety.hpp" + +namespace ethercat_driver +{ + +class EthercatSafetyDriver : public EthercatDriver +{ +public: + RCLCPP_SHARED_PTR_DEFINITIONS(EthercatSafetyDriver) + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; + + ETHERCAT_DRIVER_PUBLIC + CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override; + +protected: + /** @brief Load FailSafe Over EtherCAT Safety config YAML file + * @param[out] node YAML node containing the safety configuration root + * @param[in] path Path to the YAML file, if empty, the file is loaded from the *fsoe_config* of the YAML document + */ + void loadFsoeConfigYamlFile(YAML::Node & node, const std::string & path = ""); + + /** @brief Get safety module parameters from YAML filer + * @param[in] config YAML node containing the safety configuration root + * @return Vector of maps containing safety module parameters, each map corresponds to a safety module + */ + std::vector<std::unordered_map<std::string, std::string>> getEcSafetyModuleParam( + const YAML::Node & config); + + /** @brief Get safety nets from YAML file + * @param[in] config YAML node containing the safety configuration root + * @return Vector of safety nets + */ + std::vector<ethercat_interface::EcSafetyNet> getEcSafetyNets(const YAML::Node & config); + + CallbackReturn setupMaster() override; + + /** @brief Configure the safety network + */ + void configSafetyNetwork(); + +protected: + /** Master hable to manage a safety network */ + std::shared_ptr<ethercat_interface::EcSafety> safety_; + + /** Safety nets */ + std::vector<ethercat_interface::EcSafetyNet> ec_safety_nets_; + + /** Indexes of modules inside ec_modules_ vector that are safety masters */ + std::vector<size_t> ec_safety_masters_; + /** Indexes of modules inside ec_modules_ vector that are safety slaves only */ + std::vector<size_t> ec_safety_slaves_; + + /** Empty interfaces */ + std::vector<double> empty_interface_; +}; +} // namespace ethercat_driver + +#endif // ETHERCAT_DRIVER__ETHERCAT_SAFETY_DRIVER_HPP_ diff --git a/ethercat_driver/include/ethercat_driver/visibility_control.h b/ethercat_driver/include/ethercat_driver/visibility_control.h new file mode 100644 index 0000000..845be48 --- /dev/null +++ b/ethercat_driver/include/ethercat_driver/visibility_control.h @@ -0,0 +1,49 @@ +// Copyright 2022 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_DRIVER__VISIBILITY_CONTROL_H_ +#define ETHERCAT_DRIVER__VISIBILITY_CONTROL_H_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ + #ifdef __GNUC__ + #define ETHERCAT_DRIVER_EXPORT __attribute__ ((dllexport)) + #define ETHERCAT_DRIVER_IMPORT __attribute__ ((dllimport)) + #else + #define ETHERCAT_DRIVER_EXPORT __declspec(dllexport) + #define ETHERCAT_DRIVER_IMPORT __declspec(dllimport) + #endif + #ifdef ETHERCAT_DRIVER_BUILDING_LIBRARY + #define ETHERCAT_DRIVER_PUBLIC ETHERCAT_DRIVER_EXPORT + #else + #define ETHERCAT_DRIVER_PUBLIC ETHERCAT_DRIVER_IMPORT + #endif + #define ETHERCAT_DRIVER_PUBLIC_TYPE ETHERCAT_DRIVER_PUBLIC + #define ETHERCAT_DRIVER_LOCAL +#else + #define ETHERCAT_DRIVER_EXPORT __attribute__ ((visibility("default"))) + #define ETHERCAT_DRIVER_IMPORT + #if __GNUC__ >= 4 + #define ETHERCAT_DRIVER_PUBLIC __attribute__ ((visibility("default"))) + #define ETHERCAT_DRIVER_LOCAL __attribute__ ((visibility("hidden"))) + #else + #define ETHERCAT_DRIVER_PUBLIC + #define ETHERCAT_DRIVER_LOCAL + #endif + #define ETHERCAT_DRIVER_PUBLIC_TYPE +#endif + +#endif // ETHERCAT_DRIVER__VISIBILITY_CONTROL_H_ diff --git a/ethercat_driver/package.xml b/ethercat_driver/package.xml new file mode 100644 index 0000000..29d6d4d --- /dev/null +++ b/ethercat_driver/package.xml @@ -0,0 +1,26 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_driver</name> + <version>1.2.0</version> + <description>EtherCAT Driver for `ros2_control`</description> + <maintainer email="mcbed.robotics@gamil.com">Maciej Bednarczyk</maintainer> + <license>Apache-2.0</license> + + <buildtool_depend>ament_cmake_ros</buildtool_depend> + + <depend>hardware_interface</depend> + <depend>pluginlib</depend> + <depend>rclcpp</depend> + <depend>rclcpp_lifecycle</depend> + <depend>ethercat_interface</depend> + <depend>yaml_cpp_vendor</depend> + <depend>yaml-cpp</depend> + + <test_depend>ament_lint_auto</test_depend> + <test_depend>ament_lint_common</test_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> diff --git a/ethercat_driver/src/ethercat_driver.cpp b/ethercat_driver/src/ethercat_driver.cpp new file mode 100644 index 0000000..302b174 --- /dev/null +++ b/ethercat_driver/src/ethercat_driver.cpp @@ -0,0 +1,786 @@ +// Copyright 2022 ICUBE Laboratory, University of Strasbourg +// +// 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 "ethercat_driver/ethercat_driver.hpp" + +#include <tinyxml2.h> +#include <string> +#include <regex> + +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/rclcpp.hpp" + +namespace ethercat_driver +{ + + +uint16_t EthercatDriver::getAliasOrDefaultAlias( + const std::unordered_map<std::string, + std::string> & slave_parameters) +{ + if (slave_parameters.find("alias") != slave_parameters.end()) { + return std::stoul(slave_parameters.at("alias")); + } else { + return 0; + } +} + +CallbackReturn EthercatDriver::on_init( + const hardware_interface::HardwareInfo & info) +{ + if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) { + return CallbackReturn::ERROR; + } + + // Prevent the driver from being initialized while being configured + const std::lock_guard<std::mutex> lock(ec_configure_mutex_); + activated_ = false; + configured_ = false; + monotonic_clock_ = rclcpp::Clock(RCL_STEADY_TIME); +// system_clock_ = rclcpp::Clock(RCL_SYSTEM_TIME); + system_clock_ = rclcpp::Clock(RCL_ROS_TIME); + + hw_joint_states_.resize(info_.joints.size()); + for (uint j = 0; j < info_.joints.size(); j++) { + hw_joint_states_[j].resize( + info_.joints[j].state_interfaces.size(), + std::numeric_limits<double>::quiet_NaN()); + } + hw_sensor_states_.resize(info_.sensors.size()); + for (uint s = 0; s < info_.sensors.size(); s++) { + hw_sensor_states_[s].resize( + info_.sensors[s].state_interfaces.size(), + std::numeric_limits<double>::quiet_NaN()); + } + hw_gpio_states_.resize(info_.gpios.size()); + for (uint g = 0; g < info_.gpios.size(); g++) { + hw_gpio_states_[g].resize( + info_.gpios[g].state_interfaces.size(), + std::numeric_limits<double>::quiet_NaN()); + } + hw_joint_commands_.resize(info_.joints.size()); + for (uint j = 0; j < info_.joints.size(); j++) { + hw_joint_commands_[j].resize( + info_.joints[j].command_interfaces.size(), + std::numeric_limits<double>::quiet_NaN()); + } + hw_sensor_commands_.resize(info_.sensors.size()); + for (uint s = 0; s < info_.sensors.size(); s++) { + hw_sensor_commands_[s].resize( + info_.sensors[s].command_interfaces.size(), + std::numeric_limits<double>::quiet_NaN()); + } + hw_gpio_commands_.resize(info_.gpios.size()); + for (uint g = 0; g < info_.gpios.size(); g++) { + hw_gpio_commands_[g].resize( + info_.gpios[g].command_interfaces.size(), + std::numeric_limits<double>::quiet_NaN()); + } + + for (uint j = 0; j < info_.joints.size(); j++) { + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "joints"); + // check all joints for EC modules and load into ec_modules_ + auto module_params = getEcModuleParam(info_.original_xml, info_.joints[j].name, "joint"); + ec_module_parameters_.insert( + ec_module_parameters_.end(), module_params.begin(), module_params.end()); + for (auto i = 0ul; i < module_params.size(); i++) { + for (auto k = 0ul; k < info_.joints[j].state_interfaces.size(); k++) { + module_params[i]["state_interface/" + + info_.joints[j].state_interfaces[k].name] = std::to_string(k); + } + for (auto k = 0ul; k < info_.joints[j].command_interfaces.size(); k++) { + module_params[i]["command_interface/" + + info_.joints[j].command_interfaces[k].name] = std::to_string(k); + } + try { + auto module = ec_loader_.createSharedInstance(module_params[i].at("plugin")); + if (!module->setupSlave( + module_params[i], &hw_joint_states_[j], &hw_joint_commands_[j])) + { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "Setup of Joint module %li FAILED.", i + 1); + return CallbackReturn::ERROR; + } + module->setAliasAndPosition( + getAliasOrDefaultAlias(module_params[i]), + std::stoul(module_params[i].at("position"))); + ec_modules_.push_back(module); + } catch (pluginlib::PluginlibException & ex) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "The plugin of %s failed to load for some reason. Error: %s\n", + info_.joints[j].name.c_str(), ex.what()); + } + } + } + for (uint g = 0; g < info_.gpios.size(); g++) { + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "gpios"); + // check all gpios for EC modules and load into ec_modules_ + auto module_params = getEcModuleParam(info_.original_xml, info_.gpios[g].name, "gpio"); + ec_module_parameters_.insert( + ec_module_parameters_.end(), module_params.begin(), module_params.end()); + for (auto i = 0ul; i < module_params.size(); i++) { + for (auto k = 0ul; k < info_.gpios[g].state_interfaces.size(); k++) { + module_params[i]["state_interface/" + + info_.gpios[g].state_interfaces[k].name] = std::to_string(k); + } + for (auto k = 0ul; k < info_.gpios[g].command_interfaces.size(); k++) { + module_params[i]["command_interface/" + + info_.gpios[g].command_interfaces[k].name] = std::to_string(k); + } + try { + auto module = ec_loader_.createSharedInstance(module_params[i].at("plugin")); + if (!module->setupSlave( + module_params[i], &hw_gpio_states_[g], &hw_gpio_commands_[g])) + { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "Setup of GPIO module %li FAILED.", i + 1); + return CallbackReturn::ERROR; + } + module->setAliasAndPosition( + getAliasOrDefaultAlias(module_params[i]), + std::stoul(module_params[i].at("position"))); + ec_modules_.push_back(module); + } catch (pluginlib::PluginlibException & ex) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "The plugin of %s failed to load for some reason. Error: %s\n", + info_.gpios[g].name.c_str(), ex.what()); + } + } + } + for (uint s = 0; s < info_.sensors.size(); s++) { + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "sensors"); + // check all sensors for EC modules and load into ec_modules_ + auto module_params = getEcModuleParam(info_.original_xml, info_.sensors[s].name, "sensor"); + ec_module_parameters_.insert( + ec_module_parameters_.end(), module_params.begin(), module_params.end()); + for (auto i = 0ul; i < module_params.size(); i++) { + for (auto k = 0ul; k < info_.sensors[s].state_interfaces.size(); k++) { + module_params[i]["state_interface/" + + info_.sensors[s].state_interfaces[k].name] = std::to_string(k); + } + for (auto k = 0ul; k < info_.sensors[s].command_interfaces.size(); k++) { + module_params[i]["command_interface/" + + info_.sensors[s].command_interfaces[k].name] = std::to_string(k); + } + try { + auto module = ec_loader_.createSharedInstance(module_params[i].at("plugin")); + if (!module->setupSlave( + module_params[i], &hw_sensor_states_[s], &hw_sensor_commands_[s])) + { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "Setup of Sensor module %li FAILED.", i + 1); + return CallbackReturn::ERROR; + } + module->setAliasAndPosition( + getAliasOrDefaultAlias(module_params[i]), + std::stoul(module_params[i].at("position"))); + ec_modules_.push_back(module); + } catch (pluginlib::PluginlibException & ex) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "The plugin of %s failed to load for some reason. Error: %s\n", + info_.sensors[s].name.c_str(), ex.what()); + } + } + } + + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Got %li modules", ec_modules_.size()); + + return CallbackReturn::SUCCESS; +} + +bool EthercatDriver::deactivate_all_modules_once() +{ + bool deactivate_success = true; + + for (auto & module : ec_modules_) { + deactivate_success = deactivate_success && module->deactivate(); + } + return deactivate_success; +} + +bool EthercatDriver::deactivate_all_modules(const rclcpp::Duration & timeout) +{ + const rclcpp::Time start = monotonic_clock_.now(); + + bool running = true; + rclcpp::Duration sleep_duration(0, 0); + + while (running) { + const rclcpp::Time time_iter_start = monotonic_clock_.now(); + if (time_iter_start - start > timeout) { + RCLCPP_WARN( + rclcpp::get_logger("EthercatDriver"), + "Timeout reached while deactivating modules"); + return false; + } + + // Try deactivating all modules + bool all_deactivated = deactivate_all_modules_once(); + if (all_deactivated) { + running = false; + break; + } + + // calculate next shot. + const rclcpp::Time time_iter_end = time_iter_start + rclcpp::Duration( + 0, + master_->getInterval()); + sleep_duration = time_iter_end - monotonic_clock_.now(); + + // wait until next shot + rclcpp::sleep_for(std::chrono::nanoseconds(sleep_duration.nanoseconds())); + } + return true; +} + +CallbackReturn EthercatDriver::on_configure( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + const std::lock_guard<std::mutex> lock(ec_configure_mutex_); + if (configured_) { + RCLCPP_FATAL(rclcpp::get_logger("EthercatDriver"), "Double on_configure()"); + return CallbackReturn::ERROR; + } + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Starting ...please wait..."); + + // setup master + CallbackReturn master_return_; + master_return_ = setupMaster(); + if (master_return_ != CallbackReturn::SUCCESS) + return master_return_; + // setup the reference clock slave + master_return_ = configClockReference(); + if (master_return_ != CallbackReturn::SUCCESS) + return master_return_; + // configure network + CallbackReturn config_return_; + config_return_ = configNetwork(); + if (config_return_ != CallbackReturn::SUCCESS) { + master_->stop(); + master_.reset(); + return config_return_; + } + + + if (!master_->activate()) { + RCLCPP_ERROR(rclcpp::get_logger("EthercatDriver"), "Activate EtherCAT Master failed"); + master_->stop(); + master_.reset(); + return CallbackReturn::ERROR; + } + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Activated EtherCAT Master!"); + + // Wait during one cycle period + const rclcpp::Duration cycle_period = rclcpp::Duration(0, master_->getInterval()); + rclcpp::Duration sleep_duration = cycle_period; + //const rclcpp::Time time_iter_start = monotonic_clock_.now(); + //rclcpp::Time time_iter_end = time_iter_start + cycle_period; + auto time_iter_end = monotonic_clock_.now() + cycle_period; + bool running = true; + while (running) { + // wait until next shot + //rclcpp::sleep_for(std::chrono::nanoseconds(sleep_duration.nanoseconds())); + //rclcpp::sleep_until(time_iter_end); + monotonic_clock_.sleep_until(time_iter_end); + + //const rclcpp::Time time_iter_start = monotonic_clock_.now(); + + // make one communication cycle + //RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "master update!"); + master_->update(); + + // check if all slaves are operational + bool allOp = master_->checkAllSlavesOperational(); + + // check if configured + bool all_configured = true; + for (auto & module : ec_modules_) { + all_configured = all_configured && module->configure(); + } + if (allOp && all_configured) { + running = false; + } + + // calculate next shot. + //const rclcpp::Time time_iter_end = time_iter_start + cycle_period; + time_iter_end += cycle_period; + sleep_duration = time_iter_end - monotonic_clock_.now(); + } + + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), "EtherCAT communication successfully configured!"); + + configured_ = true; + return CallbackReturn::SUCCESS; +} + +std::vector<hardware_interface::StateInterface> +EthercatDriver::export_state_interfaces() +{ + std::vector<hardware_interface::StateInterface> state_interfaces; + // export joint state interface + for (uint j = 0; j < info_.joints.size(); j++) { + for (uint i = 0; i < info_.joints[j].state_interfaces.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + info_.joints[j].name, + info_.joints[j].state_interfaces[i].name, + &hw_joint_states_[j][i])); + } + } + // export sensor state interface + for (uint s = 0; s < info_.sensors.size(); s++) { + for (uint i = 0; i < info_.sensors[s].state_interfaces.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + info_.sensors[s].name, + info_.sensors[s].state_interfaces[i].name, + &hw_sensor_states_[s][i])); + } + } + // export gpio state interface + for (uint g = 0; g < info_.gpios.size(); g++) { + for (uint i = 0; i < info_.gpios[g].state_interfaces.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + info_.gpios[g].name, + info_.gpios[g].state_interfaces[i].name, + &hw_gpio_states_[g][i])); + } + } + return state_interfaces; +} + +std::vector<hardware_interface::CommandInterface> +EthercatDriver::export_command_interfaces() +{ + std::vector<hardware_interface::CommandInterface> command_interfaces; + // export joint command interface + std::vector<double> test; + for (uint j = 0; j < info_.joints.size(); j++) { + for (uint i = 0; i < info_.joints[j].command_interfaces.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + info_.joints[j].name, + info_.joints[j].command_interfaces[i].name, + &hw_joint_commands_[j][i])); + } + } + // export sensor command interface + for (uint s = 0; s < info_.sensors.size(); s++) { + for (uint i = 0; i < info_.sensors[s].command_interfaces.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + info_.sensors[s].name, + info_.sensors[s].command_interfaces[i].name, + &hw_sensor_commands_[s][i])); + } + } + // export gpio command interface + for (uint g = 0; g < info_.gpios.size(); g++) { + for (uint i = 0; i < info_.gpios[g].command_interfaces.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + info_.gpios[g].name, + info_.gpios[g].command_interfaces[i].name, + &hw_gpio_commands_[g][i])); + } + } + return command_interfaces; +} + +CallbackReturn EthercatDriver::setupMaster() +{ + unsigned int master_id = 666; + // Get master id + if (info_.hardware_parameters.find("master_id") == info_.hardware_parameters.end()) { + // Master id was not provided, default to 0 + master_id = 0; + } else { + try { + master_id = std::stoul(info_.hardware_parameters["master_id"]); + } catch (std::exception & e) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), "Invalid master id (%s)!", e.what()); + return CallbackReturn::ERROR; + } + } + master_ = std::make_shared<ethercat_interface::EcMaster>(master_id); + if (!master_->checkMaster()) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), "Master id (%d) not available!", master_id); + return CallbackReturn::FAILURE; + } + + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::configClockReference() { + + uint16_t clock_reference_id = 666; + // Get clock reference id + if (info_.hardware_parameters.find("clock_reference_id") == info_.hardware_parameters.end()) { + // clock reference id was not provided, default to 0 + clock_reference_id = 0; + } else { + try { + clock_reference_id = std::stoul(info_.hardware_parameters["clock_reference_id"]); + } catch (std::exception & e) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), "Invalid clock reference id (%s)!", e.what()); + return CallbackReturn::ERROR; + } + } + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), "reference clock id (%u)!", clock_reference_id); + master_->setClockReferenceId(clock_reference_id); + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::configNetwork() +{ + // Get control frequency + if (info_.hardware_parameters.find("control_frequency") == info_.hardware_parameters.end()) { + // Control frequency was not provided, default to 100 Hz + control_frequency_ = 100.0; + } else { + try { + control_frequency_ = std::stod(info_.hardware_parameters["control_frequency"]); + } catch (std::exception & e) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), "Invalid control frequency (%s)!", e.what()); + return CallbackReturn::ERROR; + } + } + + // start EC and wait until state operative + + master_->setCtrlFrequency(control_frequency_); + + for (auto i = 0ul; i < ec_modules_.size(); i++) { + if (!master_->addSlave(ec_modules_[i].get())) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), "Error add slave"); + return CallbackReturn::FAILURE; + } + } + + // configure SDO + for (auto i = 0ul; i < ec_modules_.size(); i++) { + for (auto & sdo : ec_modules_[i]->sdo_config) { + uint32_t abort_code; + int ret = master_->configSlaveSdo( + std::stod(ec_module_parameters_[i]["position"]), + sdo, + &abort_code); + if (ret) { + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "Failed to download config SDO for module at position %s with Error: %d", + ec_module_parameters_[i]["position"].c_str(), + abort_code); + } + } + } + + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + const std::lock_guard<std::mutex> lock(ec_activate_mutex_); + if (activated_) { + RCLCPP_FATAL(rclcpp::get_logger("EthercatDriver"), "Double on_activate()"); + return CallbackReturn::ERROR; + } + if (!configured_) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "on_activate called without being configured"); + return CallbackReturn::ERROR; + } + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Starting ...please wait..."); + + rclcpp::Time time_begin = monotonic_clock_.now(); + + rclcpp::Duration sleep_duration(0, 0); + + bool running = true; + while (running) { + const rclcpp::Time time_iter_start = monotonic_clock_.now(); + + // Activate all modules + bool all_activated = true; + for (auto & module : ec_modules_) { + all_activated = all_activated && module->activate(); + } + if (all_activated) { + running = false; + break; + } + + // Check if we have reached the timeout + if ((monotonic_clock_.now() - time_begin) > activate_timeout_) { + RCLCPP_WARN( + rclcpp::get_logger("EthercatDriver"), + "Activate. Timeout reached. Not all slaves activated."); + bool deactivate_success = deactivate_all_modules(deactivate_timeout_); + if (!deactivate_success) { + RCLCPP_ERROR( + rclcpp::get_logger("EthercatDriver"), + "Failed to deactivate all modules after timeout"); + return CallbackReturn::ERROR; + } + return CallbackReturn::FAILURE; + } + + // calculate next shot. + const rclcpp::Time time_iter_end = time_iter_start + + rclcpp::Duration(0, master_->getInterval()); + sleep_duration = time_iter_end - monotonic_clock_.now(); + // wait until next shot + rclcpp::sleep_for(std::chrono::nanoseconds(sleep_duration.nanoseconds())); + } + + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), "All EtherCAT slaves activated!"); + + activated_ = true; + + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::on_cleanup( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + const std::lock_guard<std::mutex> lock(ec_configure_mutex_); + if (configured_) { + if (activated_) { + RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"), "on_cleanup called while activated"); + } + + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Stopping communication ...please wait..."); + + rclcpp::Duration sleep_duration(0, 0); + const rclcpp::Time time_begin = monotonic_clock_.now(); + + bool running = true; + while (running) { + const rclcpp::Time time_iter_start = monotonic_clock_.now(); + if (time_iter_start - time_begin > cleanup_timeout_) { + RCLCPP_ERROR( + rclcpp::get_logger("EthercatDriver"), + "Timeout reached while cleaning up modules"); + running = false; + break; + } + + // Try calling cleanup on all modules + bool all_cleanup = true; + for (auto & module : ec_modules_) { + all_cleanup = all_cleanup && module->cleanup(); + } + if (all_cleanup) { + running = false; + break; + } + + // calculate next shot. + const rclcpp::Time time_iter_end = time_iter_start + rclcpp::Duration( + 0, + master_->getInterval()); + sleep_duration = time_iter_end - monotonic_clock_.now(); + // wait until next shot + rclcpp::sleep_for(std::chrono::nanoseconds(sleep_duration.nanoseconds())); + } + + // stop EC and disconnect + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "disconnect master"); + master_->stop(); + + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "free master"); + master_.reset(); + configured_ = false; + } + + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), "EtherCAT communication successfully stopped!"); + + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::on_deactivate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + const std::lock_guard<std::mutex> lock(ec_activate_mutex_); + if (configured_ && activated_) { + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Deactivating ...please wait..."); + + rclcpp::Duration sleep_duration(0, 0); + + deactivate_all_modules(deactivate_timeout_); + activated_ = false; + } + + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), "All slaves successfully deactivated!"); + + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::on_error( + const rclcpp_lifecycle::State & previous_state) +{ + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Error state reached"); + on_cleanup(previous_state); + + return CallbackReturn::SUCCESS; +} + +CallbackReturn EthercatDriver::on_shutdown( + const rclcpp_lifecycle::State & previous_state) +{ + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Shutting down ...please wait..."); + on_deactivate(previous_state); + on_cleanup(previous_state); + return CallbackReturn::SUCCESS; +} + +hardware_interface::return_type EthercatDriver::read( + const rclcpp::Time & time, + const rclcpp::Duration & period) +{ + hardware_interface::return_type err = hardware_interface::return_type::OK; + const rclcpp::Time time_begin_read = system_clock_.now(); + + if (in_past) + { + past_time_ +=rclcpp::Duration(0, master_->getInterval()); + if ((time_begin_read - past_time_).nanoseconds() > 0 || period < rclcpp::Duration(0, master_->getInterval())*0.75 ) { + return hardware_interface::return_type::OK; + } + in_past = 0; + } + + if ( (time_begin_read - time) > rclcpp::Duration(0, master_->getInterval())*1.75 ) { + + in_past = 1; + past_time_ = time; + write_data_ = false; + + return hardware_interface::return_type::OK; + } + + + + write_data_ = true; + // try to lock so we can avoid blocking the read/write loop on the lock. + const std::unique_lock<std::mutex> lock(ec_configure_mutex_, std::try_to_lock); + if (lock.owns_lock() && configured_) { + //RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "master read!"); + if ( !master_->readData()) + err = hardware_interface::return_type::ERROR; + } + //return hardware_interface::return_type::OK; + return err; +} + +hardware_interface::return_type EthercatDriver::write( + const rclcpp::Time & /*time*/, + const rclcpp::Duration & /*period*/) +{ + // try to lock so we can avoid blocking the read/write loop on the lock. + if (write_data_) { + const std::unique_lock<std::mutex> lock(ec_configure_mutex_, std::try_to_lock); + if (lock.owns_lock() && configured_) { + //RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "master write!"); + master_->writeData(); + } + } + return hardware_interface::return_type::OK; +} + +std::vector<std::unordered_map<std::string, std::string>> EthercatDriver::getEcModuleParam( + const std::string & urdf, + const std::string & component_name, + const std::string & component_type) +{ + // Check if everything OK with URDF string + if (urdf.empty()) { + throw std::runtime_error("empty URDF passed to robot"); + } + tinyxml2::XMLDocument doc; + if (!doc.Parse(urdf.c_str()) && doc.Error()) { + throw std::runtime_error("invalid URDF passed in to robot parser"); + } + if (doc.Error()) { + throw std::runtime_error("invalid URDF passed in to robot parser"); + } + + tinyxml2::XMLElement * robot_it = doc.RootElement(); + if (std::string("robot").compare(robot_it->Name())) { + throw std::runtime_error("the robot tag is not root element in URDF"); + } + + const tinyxml2::XMLElement * ros2_control_it = robot_it->FirstChildElement("ros2_control"); + if (!ros2_control_it) { + throw std::runtime_error("no ros2_control tag"); + } + + std::vector<std::unordered_map<std::string, std::string>> module_params; + std::unordered_map<std::string, std::string> module_param; + + while (ros2_control_it) { + const auto * ros2_control_child_it = + ros2_control_it->FirstChildElement(component_type.c_str()); + while (ros2_control_child_it) { + if (!component_name.compare(ros2_control_child_it->Attribute("name"))) { + const auto * ec_module_it = ros2_control_child_it->FirstChildElement("ec_module"); + while (ec_module_it) { + module_param.clear(); + module_param["name"] = ec_module_it->Attribute("name"); + const auto * plugin_it = ec_module_it->FirstChildElement("plugin"); + if (NULL != plugin_it) { + module_param["plugin"] = plugin_it->GetText(); + } + const auto * param_it = ec_module_it->FirstChildElement("param"); + while (param_it) { + module_param[param_it->Attribute("name")] = param_it->GetText(); + param_it = param_it->NextSiblingElement("param"); + } + module_params.push_back(module_param); + ec_module_it = ec_module_it->NextSiblingElement("ec_module"); + } + } + ros2_control_child_it = ros2_control_child_it->NextSiblingElement(component_type.c_str()); + } + ros2_control_it = ros2_control_it->NextSiblingElement("ros2_control"); + } + + return module_params; +} + +} // namespace ethercat_driver + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + ethercat_driver::EthercatDriver, hardware_interface::SystemInterface) diff --git a/ethercat_driver/src/ethercat_safety_driver.cpp b/ethercat_driver/src/ethercat_safety_driver.cpp new file mode 100644 index 0000000..ae8de8c --- /dev/null +++ b/ethercat_driver/src/ethercat_safety_driver.cpp @@ -0,0 +1,426 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#include <string> +#include <regex> + +#include "ethercat_driver/ethercat_safety_driver.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/rclcpp.hpp" + +#ifndef CLASSM +#define CLASSM EthercatSafetyDriver +#else +#error alias CLASSM already defined! +#endif //< CLASSM + +namespace ethercat_driver +{ + +void CLASSM::loadFsoeConfigYamlFile(YAML::Node & node, const std::string & path) +{ + std::string file_path; + if (path.empty()) { + // Get the fsoe_config parameter of the ethercat_driver hardware plugin + if (info_.hardware_parameters.find("fsoe_config") == info_.hardware_parameters.end()) { + std::string msg("fsoe_config parameter is missing!"); + // Safety fsoe config file was not provided + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); + } + file_path = info_.hardware_parameters.at("fsoe_config"); + } else { + file_path = path; + } + + try { + node = YAML::LoadFile(file_path); + } catch (const YAML::ParserException & ex) { + std::string msg = + std::string( + "EthercatSafetyDriver : failed to load fsoe configuration " + "(YAML file is incorrect): ") + std::string(ex.what()); + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str() ); + throw std::runtime_error(msg); + } catch (const YAML::BadFile & ex) { + std::string msg = + std::string( + "EthercatSafetyDriver : failed to load fsoe configuration " + "(file path is incorrect or file is damaged): " + std::string(ex.what())); + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str() ); + throw std::runtime_error(msg); + } catch (std::exception & e) { + std::string msg = + std::string( + "EthercatSafetyDriver : error while loading fsoe configuration: ") + std::string(e.what()); + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str() ); + throw std::runtime_error(msg); + } +} + +std::vector<std::unordered_map<std::string, std::string>> CLASSM::getEcSafetyModuleParam( + const YAML::Node & config) +{ + if (0 == config.size() ) { + std::string msg = "Empty fsoe_config file!"; + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); + } + std::vector<std::unordered_map<std::string, std::string>> module_params; + std::unordered_map<std::string, std::string> module_param; + + if (config["safety_modules"]) { + for (const auto & module : config["safety_modules"]) { + module_param.clear(); + module_param["name"] = module["name"].as<std::string>(); + module_param["plugin"] = module["plugin"].as<std::string>(); + for (const auto & param : module["parameters"]) { + module_param[param.first.as<std::string>()] = param.second.as<std::string>(); + } + module_params.push_back(module_param); + } + } + + return module_params; +} + +unsigned int uint_from_string(const std::string & str) +{ + // Strip leading and trailing whitespaces + std::string s = std::regex_replace(str, std::regex("^ +| +$|( ) +"), "$1"); + // Test if the number is in hexadecimal format + if (s.find("0x") == 0) { + return std::stoul(s, nullptr, 16); + } + return std::stoul(s); +} + +void getTransferMemoryInfo( + const YAML::Node & element, + ethercat_interface::EcMemoryEntry & entry, + const std::string & dir, + const std::string & safety_net_name) +{ + if (!element["ec_module"]) { + std::string msg = "Transfer definition without ec_module entry, net: " + + safety_net_name + " direction: " + dir; + throw std::runtime_error(msg); + } + if (!element["index"]) { + std::string msg = "Transfer definition without index entry, net: " + + safety_net_name + " direction: " + dir; + throw std::runtime_error(msg); + } + if (!element["subindex"]) { + std::string msg = "Transfer definition without subindex entry, net: " + + safety_net_name + " direction: " + dir; + throw std::runtime_error(msg); + } + + entry.module_name = element["ec_module"].as<std::string>(); + entry.index = uint_from_string(element["index"].as<std::string>()); + entry.subindex = uint_from_string(element["subindex"].as<std::string>()); +} + +std::vector<ethercat_interface::EcSafetyNet> CLASSM::getEcSafetyNets(const YAML::Node & config) +{ + if (0 == config.size() ) { + std::string msg = "Empty fsoe_config file!"; + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); + } + + std::vector<ethercat_interface::EcSafetyNet> safety_nets; + ethercat_interface::EcSafetyNet safety_net; + + if (config["nets"]) { + for (const auto & net : config["nets"]) { + safety_net.reset(net["name"].as<std::string>()); + safety_net.master = net["safety_master"].as<std::string>(); + for (const auto & transfer : net["transfers"]) { + ethercat_interface::EcTransferEntry transfer_entry; + if (!transfer["size"]) { + std::string msg = "ERROR: transfer n°" + std::to_string(safety_nets.size()) + " of net " + + safety_net.name + " : definition without «size» parameter"; + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); + } + if (!transfer["in"]) { + std::string msg = "ERROR: transfer n°" + std::to_string(safety_nets.size()) + " of net " + + safety_net.name + " : definition without «in» parameter"; + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); + } + if (!transfer["out"]) { + std::string msg = "ERROR: transfer n°" + std::to_string(safety_nets.size()) + " of net " + + safety_net.name + " : definition without «out» parameter"; + RCLCPP_FATAL( + rclcpp::get_logger("EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); + } + transfer_entry.size = transfer["size"].as<size_t>(); + getTransferMemoryInfo( + transfer["in"], transfer_entry.input, + "in", safety_net.name); + getTransferMemoryInfo( + transfer["out"], transfer_entry.output, + "out", safety_net.name); + safety_net.transfers.push_back(transfer_entry); + } + safety_nets.push_back(safety_net); + } + } + + return safety_nets; +} + +void throwErrorIfModuleParametersNotFound( + const ethercat_interface::EcTransferEntry & transfer, + const std::string & module_name, + const std::string & safety_net_name, + const std::string & direction) +{ + std::string msg = "In safety net: " + safety_net_name + ", for transfer " + + transfer.to_simple_string() + ", the module name of the " + direction + "( " + module_name + + ") among all the recorded modules."; + RCLCPP_ERROR( + rclcpp::get_logger( + "EthercatSafetyDriver"), msg.c_str()); + throw std::runtime_error(msg); +} + +CallbackReturn CLASSM::on_init( + const hardware_interface::HardwareInfo & info) +{ + auto res = this->EthercatDriver::on_init(info); + if (res != CallbackReturn::SUCCESS) { + return res; + } + + // Prevent the driver from being initialized while being configured + const std::lock_guard<std::mutex> lock(ec_configure_mutex_); + activated_ = false; + configured_ = false; + + YAML::Node config; + // Load the fsoe_config file + loadFsoeConfigYamlFile(config); + + // Parse safety modules from the safety yaml file defined + // in fsoe_config attribute of a param tag of the the URDF + auto safety_module_params = getEcSafetyModuleParam(config); + + // Append the safety modules parameters to the list of modules parameters + size_t idx_1st = ec_module_parameters_.size(); + ec_module_parameters_.insert( + ec_module_parameters_.end(), safety_module_params.begin(), safety_module_params.end()); + for (size_t i = 0; i < safety_module_params.size(); i++) { + ec_safety_slaves_.push_back(idx_1st + i); + } + + // Parse safety nets from the safety yaml file defined + // in fsoe_config attribute of a param tag of the the URDF + ec_safety_nets_ = getEcSafetyNets(config); + + // Append the safety modules to the list of modules and load them + for (const auto & safety_module_param : safety_module_params) { + try { + auto ec_module = ec_loader_.createSharedInstance(safety_module_param.at("plugin")); + if (!ec_module->setupSlave( + safety_module_param, &empty_interface_, &empty_interface_)) + { + const std::string & module_name = safety_module_param.at("name"); + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), + "Setup of safety only module %s FAILED.", module_name.c_str() ); + return CallbackReturn::ERROR; + } + + auto idx = ec_modules_.size(); + ec_module->setAliasAndPosition( + getAliasOrDefaultAlias(safety_module_param), + std::stoul(safety_module_param.at("position"))); + ec_modules_.push_back(ec_module); + ec_safety_slaves_.push_back(idx); + } catch (const pluginlib::PluginlibException & ex) { + const std::string & module_name = safety_module_param.at("name"); + RCLCPP_ERROR( + rclcpp::get_logger( + "EthercatSafetyDriver"), + "The plugin failed to load for safety module %s. Error: %s\n", + module_name.c_str(), ex.what()); + } + } + + // Find all masters from the nets + { + std::vector<std::string> master_names; + for (const auto & net : ec_safety_nets_) { + master_names.push_back(net.master); + } + for (size_t i = 0; i < ec_module_parameters_.size(); i++) { + if (std::find( + master_names.begin(), master_names.end(), + ec_module_parameters_[i].at("name")) != + master_names.end()) + { + ec_safety_masters_.push_back(i); + } + } + } + + // Identify (alias,position) all the modules participating in transfers + for (auto & net : ec_safety_nets_) { + for (auto & transfer : net.transfers) { + // Update each EcMemoryEntry with the alias and position of the module + size_t in_idx = ec_module_parameters_.size(); + for (in_idx = 0; in_idx < ec_module_parameters_.size(); ++in_idx) { + if (ec_module_parameters_[in_idx].at("name") == transfer.input.module_name) { + break; + } + } + size_t out_idx = ec_module_parameters_.size(); + for (out_idx = 0; out_idx < ec_module_parameters_.size(); ++out_idx) { + if (ec_module_parameters_[out_idx].at("name") == transfer.output.module_name) { + break; + } + } + if (in_idx == ec_module_parameters_.size()) { + throwErrorIfModuleParametersNotFound( + transfer, transfer.input.module_name, net.name, "input"); + } + if (out_idx == ec_module_parameters_.size()) { + throwErrorIfModuleParametersNotFound( + transfer, transfer.output.module_name, net.name, "output"); + } + + const auto & input_module = ec_modules_[in_idx]; + const auto & output_module = ec_modules_[out_idx]; + + transfer.input.alias = input_module->alias_; + transfer.input.position = input_module->position_; + transfer.output.alias = output_module->alias_; + transfer.output.position = output_module->position_; + } + } + + return CallbackReturn::SUCCESS; +} + +CallbackReturn CLASSM::setupMaster() +{ + unsigned int master_id = 666; + // Get master id + if (info_.hardware_parameters.find("master_id") == info_.hardware_parameters.end()) { + // Master id was not provided, default to 0 + master_id = 0; + } else { + try { + master_id = std::stoul(info_.hardware_parameters["master_id"]); + } catch (std::exception & e) { + RCLCPP_FATAL( + rclcpp::get_logger("EthercatDriver"), "Invalid master id (%s)!", e.what()); + return CallbackReturn::ERROR; + } + } + + // Safety master + safety_ = std::make_shared<ethercat_interface::EcSafety>(master_id); + master_ = safety_; + + return CallbackReturn::SUCCESS; +} + +CallbackReturn CLASSM::on_configure( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + const std::lock_guard<std::mutex> lock(ec_configure_mutex_); + if (configured_) { + RCLCPP_FATAL(rclcpp::get_logger("EthercatSafetyDriver"), "Double on_configure()"); + return CallbackReturn::ERROR; + } + RCLCPP_INFO(rclcpp::get_logger("EthercatSafetyDriver"), "Starting ...please wait..."); + + // Setup master + setupMaster(); + + // Standard Network configuration + configNetwork(); + + if (!master_->activate()) { + RCLCPP_ERROR(rclcpp::get_logger("EthercatSafetyDriver"), "Activate EcSafety failed"); + return CallbackReturn::ERROR; + } + RCLCPP_INFO(rclcpp::get_logger("EthercatSafetyDriver"), "Activated EcSafety!"); + + // Safety Network configuration + safety_->registerTransferInDomain(ec_safety_nets_); + + // start after one second + // Create a monotonic clock + rclcpp::Clock steady_clock(RCL_STEADY_TIME); + rclcpp::Duration sleep_duration = rclcpp::Duration(1, 0); + + + bool running = true; + while (running) { + // wait until next shot + rclcpp::sleep_for(std::chrono::nanoseconds(sleep_duration.nanoseconds())); + const rclcpp::Time time_iter_start = steady_clock.now(); + + // update EtherCAT bus + master_->update(); + RCLCPP_INFO(rclcpp::get_logger("EthercatSafetyDriver"), "updated!"); + + // check if all slaves are operational + bool allOp = master_->checkAllSlavesOperational(); + // check if configured + bool all_configured = true; + for (auto & module : ec_modules_) { + all_configured = all_configured && module->configure(); + } + if (allOp && all_configured) { + running = false; + } + // calculate next shot. + rclcpp::Time time_iter_end = time_iter_start + rclcpp::Duration(0, master_->getInterval()); + sleep_duration = time_iter_end - steady_clock.now(); + } + + RCLCPP_INFO( + rclcpp::get_logger("EthercatSafetyDriver"), "System Successfully started!"); + + configured_ = true; + + return CallbackReturn::SUCCESS; +} + +} // namespace ethercat_driver + +#undef CLASSM + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + ethercat_driver::EthercatSafetyDriver, hardware_interface::SystemInterface) diff --git a/ethercat_driver/test/testHelper_ethercat_safety_driver.hpp b/ethercat_driver/test/testHelper_ethercat_safety_driver.hpp new file mode 100644 index 0000000..4fa0596 --- /dev/null +++ b/ethercat_driver/test/testHelper_ethercat_safety_driver.hpp @@ -0,0 +1,34 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#ifndef TESTHELPER_ETHERCAT_SAFETY_DRIVER_HPP_ +#define TESTHELPER_ETHERCAT_SAFETY_DRIVER_HPP_ + +#include "ethercat_driver/ethercat_safety_driver.hpp" + +namespace ethercat_driver +{ + +class TestHelperEthercatSafetyDriver : public ethercat_driver::EthercatSafetyDriver +{ +public: + using EthercatSafetyDriver::getEcSafetyModuleParam; + using EthercatSafetyDriver::getEcSafetyNets; +}; + +} // namespace ethercat_driver + +#endif // TESTHELPER_ETHERCAT_SAFETY_DRIVER_HPP_ diff --git a/ethercat_driver/test/test_ethercat_safety_driver.cpp b/ethercat_driver/test/test_ethercat_safety_driver.cpp new file mode 100644 index 0000000..2d23c16 --- /dev/null +++ b/ethercat_driver/test/test_ethercat_safety_driver.cpp @@ -0,0 +1,227 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +// Executes directly the gtest, call: +// ./build/ethercat_driver/test_ethercat_safety_driver +// from the root directory of the workspace + +#include <gtest/gtest.h> +#include <fstream> +#include <sstream> +#include <filesystem> + +#include "testHelper_ethercat_safety_driver.hpp" + +TEST(TestEthercatSafetyDriver, getEcSafetyModuleParam) +{ + ethercat_driver::TestHelperEthercatSafetyDriver driver; + std::filesystem::path dir = TEST_RESOURCES_DIRECTORY; + const std::string test_config_path = dir / "test_config_ethercat_safety.yaml"; + + std::cout << "Test config path: " << test_config_path << std::endl; + + YAML::Node config = YAML::LoadFile(test_config_path); + + auto modules = driver.getEcSafetyModuleParam(config); + std::set<std::string> names; + for (auto & module : modules) { + auto it = module.find("name"); + EXPECT_TRUE( + it != + nullptr) << "name is not a field of the ec safety module" << std::endl; + names.insert(it->second); + } + std::set<std::string> expected_names = { + "s2", "m1", "m2" + }; + EXPECT_EQ(names, expected_names) << "Ec module names are not as expected" << std::endl; +} + +TEST(TestEthercatSafetyDriver, getEcSafetyNet) +{ + ethercat_driver::TestHelperEthercatSafetyDriver driver; + std::string yaml; + { + std::filesystem::path dir = TEST_RESOURCES_DIRECTORY; + const std::string test_config_path = dir / "test_config_ethercat_safety.yaml"; + std::ifstream file(test_config_path); + std::stringstream buffer; + buffer << file.rdbuf(); + yaml = buffer.str(); + } + + YAML::Node config = YAML::Load(yaml); + + auto nets = driver.getEcSafetyNets(config); + std::set<std::string> net_names; + + EXPECT_EQ(nets.size(), 2) << "Number of safety nets is not as expected" << std::endl; + for (auto & net : nets) { + net_names.insert(net.name); + } + std::set<std::string> expected_net_names = { + "n1", "n2" + }; + EXPECT_EQ(net_names, expected_net_names) << "Net names are not as expected" << std::endl; + + int net_1_index = nets[0].name == "n1" ? 0 : 1; + int net_2_index = (net_1_index + 1) % 2; + + auto & net1 = nets[net_1_index]; + auto & net2 = nets[net_2_index]; + + // Net 1 + EXPECT_EQ(net1.master, "m1") << "Master name is not as expected" << std::endl; + EXPECT_EQ( + net1.transfers.size(), + 2) << "Number of transfers is not as expected for net n1" << std::endl; + { + { + auto & tr = net1.transfers[0]; + EXPECT_EQ( + tr.input.module_name, + "s1") << "Input module name is not as expected for 1st transfer of net n1" << std::endl; + EXPECT_EQ( + tr.input.index, + 0x607a) << "Input index is not as expected for 1st transfer of net n1" << std::endl; + + EXPECT_EQ( + tr.output.module_name, + "s2") << "Output module name is not as expected for 1st transfer of net n1" << std::endl; + EXPECT_EQ( + tr.output.index, + 0x60ff) << "Output index is not as expected for 1st transfer of net n1" << std::endl; + + EXPECT_EQ( + tr.size, + 18) << "Size is not as expected for 1st transfer of net n1" << std::endl; + } + + { + auto & tr = net1.transfers[1]; + EXPECT_EQ( + tr.input.module_name, + "s1") << "Input module name is not as expected for 2nd transfer of net n1" << std::endl; + EXPECT_EQ( + tr.input.index, + 0x707a) << "Input index is not as expected for 2nd transfer of net n1" << std::endl; + + + EXPECT_EQ( + tr.output.module_name, + "s3") << "Output module name is not as expected for 2nd transfer of net n1" << std::endl; + EXPECT_EQ( + tr.output.index, + 0x10ff) << "Output index is not as expected for 2nd transfer of net n1" << std::endl; + + EXPECT_EQ( + tr.size, + 42) << "Size is not as expected for 2nd transfer of net n1" << std::endl; + } + } + + // Net 2 + EXPECT_EQ(net2.master, "m2") << "Master name is not as expected" << std::endl; + EXPECT_EQ( + net2.transfers.size(), + 1) << "Number of transfers is not as expected for net n2" << std::endl; + { + auto & tr = net2.transfers[0]; + EXPECT_EQ( + tr.input.module_name, + "q1") << "Input module name is not as expected for 1st transfer of net n2" << std::endl; + EXPECT_EQ( + tr.input.index, + 0x607a) << "Input index is not as expected for 1st transfer of net n2" << std::endl; + + EXPECT_EQ( + tr.output.module_name, + "q2") << "Output module name is not as expected for 1st transfer of net n2" << std::endl; + EXPECT_EQ( + tr.output.index, + 0x60ff) << "Output index is not as expected for 1st transfer of net n2" << std::endl; + + EXPECT_EQ( + tr.size, + 18) << "Size is not as expected for 1st transfer of net n2" << std::endl; + } +} + +TEST(TestEthercatSafetyDriver, estopParseConfigFile) +{ + ethercat_driver::TestHelperEthercatSafetyDriver driver; + std::string yaml; + { + std::filesystem::path dir = TEST_RESOURCES_DIRECTORY; + const std::string test_config_path = dir / "estop_ethercat_safety.yaml"; + std::ifstream file(test_config_path); + std::stringstream buffer; + buffer << file.rdbuf(); + yaml = buffer.str(); + } + + YAML::Node config = YAML::Load(yaml); + + auto nets = driver.getEcSafetyNets(config); + EXPECT_EQ(1, nets.size()) << "Number of safety nets is not as expected" << std::endl; + + auto & net = nets[0]; + EXPECT_EQ(net.master, "el1918") << "Master name is not as expected" << std::endl; + + EXPECT_EQ( + net.transfers.size(), + 2) << "Number of transfers is not as expected for net n1" << std::endl; + { + auto & tr = net.transfers[0]; + EXPECT_EQ( + tr.input.module_name, + "ek1914") << "Input module name is not as expected for 1st transfer of net n1" << std::endl; + EXPECT_EQ( + tr.input.index, + 0x6000) << "Input index is not as expected for 1st transfer" << std::endl; + + EXPECT_EQ( + tr.output.module_name, + "el1918") << "Output module name is not as expected for 1st transfer" << std::endl; + EXPECT_EQ( + tr.output.index, + 0x7080) << "Output index is not as expected for 1st transfer" << std::endl; + + EXPECT_EQ( + tr.size, + 6) << "Size is not as expected for 1st transfer" << std::endl; + } + { + auto & tr = net.transfers[1]; + EXPECT_EQ( + tr.input.module_name, + "el1918") << "Input module name is not as expected for 2nd transfer" << std::endl; + EXPECT_EQ( + tr.input.index, + 0x6080) << "Input index is not as expected for 2nd transfer" << std::endl; + + EXPECT_EQ( + tr.output.module_name, + "ek1914") << "Output module name is not as expected for 2nd transfer" << std::endl; + EXPECT_EQ( + tr.output.index, + 0x7000) << "Output index is not as expected for 2nd transfer" << std::endl; + + EXPECT_EQ( + tr.size, + 6) << "Size is not as expected for 2nd transfer" << std::endl; + } +} diff --git a/ethercat_driver_ros2/CMakeLists.txt b/ethercat_driver_ros2/CMakeLists.txt new file mode 100644 index 0000000..f372d94 --- /dev/null +++ b/ethercat_driver_ros2/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.8) +project(ethercat_driver_ros2 NONE) +find_package(ament_cmake REQUIRED) +ament_package() diff --git a/ethercat_driver_ros2/doxygen/Doxyfile b/ethercat_driver_ros2/doxygen/Doxyfile new file mode 100644 index 0000000..7a3e19f --- /dev/null +++ b/ethercat_driver_ros2/doxygen/Doxyfile @@ -0,0 +1,23 @@ +# All settings not listed here will use the Doxygen default values. + +PROJECT_NAME = "ethercat_driver_ros2" +PROJECT_NUMBER = main +PROJECT_BRIEF = "C++ ROS test" + +# Use these lines to include the generated logging.hpp (update install path if needed) +INPUT = ../../ethercat_driver/include ../../ethercat_interface/include + +RECURSIVE = YES +OUTPUT_DIRECTORY = _build + +EXTRACT_ALL = YES +SORT_MEMBER_DOCS = NO + +GENERATE_LATEX = NO +GENERATE_XML = YES + +ENABLE_PREPROCESSING = YES + +DOT_GRAPH_MAX_NODES = 101 + +FILE_PATTERNS = *.cpp *.h *.hpp *.md diff --git a/ethercat_driver_ros2/package.xml b/ethercat_driver_ros2/package.xml new file mode 100644 index 0000000..f72b505 --- /dev/null +++ b/ethercat_driver_ros2/package.xml @@ -0,0 +1,17 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_driver_ros2</name> + <version>1.2.0</version> + <description>Meta-package aggregating the ethercat_driver_ros2 packages and documentation</description> + <maintainer email="mcbed.robotics@gamil.com">Maciej Bednarczyk</maintainer> + <license>Apache License 2.0</license> + + <buildtool_depend>ament_cmake</buildtool_depend> + <exec_depend>ethercat_driver</exec_depend> + <exec_depend>ethercat_interface</exec_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> diff --git a/ethercat_driver_ros2/requirements.txt b/ethercat_driver_ros2/requirements.txt new file mode 100644 index 0000000..ba7320c --- /dev/null +++ b/ethercat_driver_ros2/requirements.txt @@ -0,0 +1,7 @@ +sphinx-rtd-theme +sphinxcontrib-plantuml +sphinx-mdinclude +breathe +exhale +sphinx-copybutton +sphinx-tabs diff --git a/ethercat_driver_ros2/sphinx/Makefile b/ethercat_driver_ros2/sphinx/Makefile new file mode 100644 index 0000000..7c64489 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/Makefile @@ -0,0 +1,24 @@ +# Minimal makefile for Sphinx documentation +# + +# You can set these variables from the command line, and also +# from the environment for the first two. +SPHINXOPTS ?= +SPHINXBUILD ?= sphinx-build +SOURCEDIR = . +BUILDDIR = _build + +# Put it first so that "make" without argument is like "make help". +help: + @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +.PHONY: help Makefile clean + +clean: + rm -rf "_doxygen/" "api/" + @$(SPHINXBUILD) -M clean "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +# Catch-all target: route all unknown targets to Sphinx using the new +# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). +%: Makefile + @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) diff --git a/ethercat_driver_ros2/sphinx/_static/css/custom.css b/ethercat_driver_ros2/sphinx/_static/css/custom.css new file mode 100644 index 0000000..3da4fe3 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/_static/css/custom.css @@ -0,0 +1,21 @@ +.wy-table-responsive table td, +.wy-table-responsive table th { + white-space: normal; +} + +tr { + white-space: normal; +} + +thead { + white-space: normal; +} + +table { + white-space: normal; +} + +pre { + white-space: pre-wrap !important; + word-break: break-all; +} diff --git a/ethercat_driver_ros2/sphinx/conf.py b/ethercat_driver_ros2/sphinx/conf.py new file mode 100644 index 0000000..93c2e0a --- /dev/null +++ b/ethercat_driver_ros2/sphinx/conf.py @@ -0,0 +1,102 @@ +# Copyright 2022 ICube Laboratory, University of Strasbourg +# +# 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. + +# Configuration file for the Sphinx documentation builder. +# +# This file only contains a selection of the most common options. For a full +# list see the documentation: +# https://www.sphinx-doc.org/en/master/usage/configuration.html + +# -- Path setup -------------------------------------------------------------- + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +# +from pathlib import Path + +# -- Project information ----------------------------------------------------- + +project = "ethercat_driver_ros2" +copyright = "2023, ICUBE Laboratory, University of Strasbourg" +author = "Maciej Bednarczyk, Philippe Zanne, Laurent Barbé" + +# The full version, including alpha/beta/rc tags +release = "1.0.0" + + +# -- General configuration --------------------------------------------------- + +# Add any Sphinx extension module names here, as strings. They can be +# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom +# ones. +extensions = [ + "sphinx_rtd_theme", + "sphinx_mdinclude", + "sphinx.ext.mathjax", + "sphinx.ext.todo", + "sphinx.ext.graphviz", + "sphinxcontrib.plantuml", + "sphinx_copybutton", + "sphinx_tabs.tabs", + "breathe", +] + +breathe_default_project = "ethercat_driver_ros2" + + +def get_package(package: str): + path = Path(__file__).parent.parent.parent.joinpath(f"{package}/include/{package}") + files_gen = path.glob("*.hpp") + files = [] + for file in files_gen: + files.append(file.name) + return (path, files) + + +breathe_projects = { + "ethercat_driver_ros2": "../doxygen/_build/xml/", +} + + +# Tell sphinx what the primary language being documented is. +primary_domain = "cpp" + +# Tell sphinx what the pygments highlight language should be. +highlight_language = "cpp" + + +# Add any paths that contain templates here, relative to this directory. +templates_path = ["_templates"] + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +# This pattern also affects html_static_path and html_extra_path. +exclude_patterns = ["_build", "Thumbs.db", ".DS_Store"] + + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +html_theme = "sphinx_rtd_theme" + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = ["_static"] +html_logo = "images/logo-icube.png" +html_css_files = ["css/custom.css"] +pygments_style = "sphinx" diff --git a/ethercat_driver_ros2/sphinx/developer_guide/cia402_drive.rst b/ethercat_driver_ros2/sphinx/developer_guide/cia402_drive.rst new file mode 100644 index 0000000..ee18044 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/developer_guide/cia402_drive.rst @@ -0,0 +1,220 @@ +CANopen over EtherCAT for electrical drives +=========================================== + +CANopen also defines several device profiles by establishing standard behavior and communication objects for similar devices. In the case of electrical drives, the profile is given by the **CiA402** ("CANopen device profile for drives and motion control") norm compliant with the `IEC <https://webstore.iec.ch/publication/23757>`_ standard that defines programming languages for programmable control systems. The CiA402 norm specifies specific objects in OD in range :code:`0x6000` to :code:`0x67fe`, what guarantees, that for a drive compatible with CiA402, typical process values such as position, velocity, or torque set-points and actual values will always be defined in the same objects with the same address regardless of the manufacturer and by such simplifies the commissioning of different drives. CIA402 also defines a state machine that corresponds to the drive’s actual operating state (:code:`Disabled`, :code:`Fault`, :code:`Switch ON`, etc.). This state machine is controlled and monitored by two mandatory PDO entries: :code:`Control Word` and :code:`Status Word`. The drive cannot be started until the state machine has been put into the appropriate state. + +The device states and possible control sequences of the drive are described by the CANopen state machine as follows: + +.. image:: https://webhelp.kollmorgen.com/kas/Content/Resources/Images/CoE%20status%20machine.png + :width: 400 + :alt: ecm_lifecycle + :align: center + +The possible drive states are : + +.. list-table:: CiA402 Drive States + :widths: 15 35 + :header-rows: 1 + + * - State + - Description + * - :code:`NOT_READY_TO_SWITCH_ON` + - The drive is not ready to switch on. The drive is in boot phase. Drive motion functions are disabled. No communication established. + * - :code:`SWITCH_ON_DISABLED` + - The drive cannot be enabled via the EtherCAT interface. Drive motion functions are disabled. + * - :code:`READY_TO_SWITCH_ON` + - The drive can be enabled. Parameters can be transferred. Power may be applied. Drive motion functions are disabled. + * - :code:`SWITCHED_ON` + - The drive is enabled but idle No fault detected. Power is enabled Drive motion functions are disabled. Parameters can be transferred. No set-points are transferred from the EtherCAT interface. + * - :code:`OPERATION_ENABLED` + - Normal operation mode No fault detected. Drive motion functions and power are enabled. Power enabled. Set-points are transferred from the EtherCAT interface. + * - :code:`QUICK_STOP_ACTIVE` + - The quick stop process is executed. Drive motion functions are disabled. Power is enabled. + * - :code:`FAULT_REACTION_ACTIVE` + - A fault has occurred, fault reaction processes are executed. + * - :code:`FAULT` + - A fault is active, Drive is stopped and its functions are disabled. + +State transitions are the result of events that can be either internal or triggers through the :code:`Control Word`. When a command trigger for state change is received, the transition is performed before any other command is processed. + +The possible transition states, their trigger events and performed actions are : + +.. list-table:: CiA402 Drive State Transitions + :widths: 1 20 24 + :header-rows: 1 + + * - State Transition + - Event + - Action + * - :code:`0` + - **Automatic transition** after power-on or reset application + - Drive device self-test and/or self initialization has to be performed + * - :code:`1` + - **Automatic transition** + - Communication has to be activated + * - :code:`2` + - Shutdown command from control device or local signal + - None + * - :code:`3` + - Switch on command received from control device or local signal + - The high-level power has to be switched ON, if possible + * - :code:`4` + - Enable operation command received from control device or local signal + - The drive function has to be enabled. All internal set-points cleared. + * - :code:`5` + - Disable operation command received from control device or local signal + - The drive function has to be disabled. + * - :code:`6` + - Shutdown command received from control device or local signal + - The high-level power has to be switched OFF, if possible. + * - :code:`7` + - Quick stop or disable voltage command from control device or local signal + - None + * - :code:`8` + - Shutdown command from control device or local signal + - The drive function has to be disabled. The high-level power has to be switched OFF, if possible. + * - :code:`9` + - Disable voltage command from control device or local signal + - The drive function has to be disabled. The high-level power has to be switched OFF, if possible. + * - :code:`10` + - Disable voltage or quick stop command from control device or local signal + - The high-level power has to be switched OFF, if possible. + * - :code:`11` + - Quick stop command from control device or local signal + - The quick stop function has to be started. + * - :code:`12` + - Either: - **Automatic transition** when the quick stop function is completed and quick stop option code is 1, 2, 3 or 4. - Disable voltage command received from control device (depends on the quick stop option code) + - The drive function has to be disabled. The high-level power has to be switched OFF, if possible. + * - :code:`13` + - Fault signal + - The configured fault reaction function has to be executed. + * - :code:`14` + - **Automatic transition** + - The drive function has to be disabled. The high-level power has to be switched OFF, if possible. + * - :code:`15` + - Fault reset command from control device or local signal. + - A reset of the fault condition is performed if no fault exists currently on the drive device. After leaving the Fault state, the Fault reset bit in the control word has to be cleared by the control device. + * - :code:`16` + - If the quick stop option code is 5, 6, 7, or 8, enable operation command from control device + - The drive function has to be enabled + +CANopen uses 16-bits :code:`Status Word` and :code:`Control Word` to monitor and control the state machine. These PDO entries have the following bit assignment : + +.. list-table:: CiA402 Drive Words + :widths: 1 20 24 + :header-rows: 1 + + * - Bit + - :code:`Status Word` Name + - :code:`Control Word` Name + * - :code:`0` + - Ready to switch on + - Switch On + * - :code:`1` + - Switched on + - Disable Voltage + * - :code:`2` + - Operation Enabled + - Quick Stop + * - :code:`3` + - Fault + - Enable Operation + * - :code:`4` + - Voltage Enabled + - Operation-mode Specific + * - :code:`5` + - Quick Stop + - Operation-mode Specific + * - :code:`6` + - Switch On Disabled + - Operation-mode Specific + * - :code:`7` + - Warning + - Reset Fault (only effective for faults) + * - :code:`8` + - Manufacturer-specific (reserved) + - Pause/halt + * - :code:`9` + - Remote (always 1) + - Reserved + * - :code:`10` + - Target Reached + - Reserved + * - :code:`11` + - Internal Limit Active + - Reserved + * - :code:`12` + - Operation-mode Specific (reserved) + - Reserved + * - :code:`13` + - Operation-mode Specific (reserved) + - Manufacturer-specific + * - :code:`14` + - Manufacturer-specific (reserved) + - Manufacturer-specific + * - :code:`15` + - Manufacturer-specific (reserved) + - Manufacturer-specific + +.. image:: https://infosys.beckhoff.com/content/1033/ax2000-b110/Images/StateMachine04.gif + :width: 700 + :alt: words + +The :code:`Status Word` is only updated and written by the drive in :code:`Safe-Op` and :code:`Operational` states. The current drive state can be decoded from the logical combination of the bits in the :code:`Status Word`: + +.. list-table:: CiA402 Drive State form :code:`Status Word` + :widths: 50 50 + :header-rows: 1 + + * - :code:`Status Word` + - State + * - :code:`xxxx xxxx x0xx 0000` + - Not ready to switch on + * - :code:`xxxx xxxx x1xx 0000` + - Switch on disabled + * - :code:`xxxx xxxx x01x 0001` + - Ready to switch on + * - :code:`xxxx xxxx x01x 0011` + - Switched on + * - :code:`xxxx xxxx x01x 0111` + - Operation enabled + * - :code:`xxxx xxxx x00x 0111` + - Quick stop active + * - :code:`xxxx xxxx x0xx 1111` + - Fault reaction active + * - :code:`xxxx xxxx x0xx 1000` + - Fault + +The control commands allow the manipulation of the state of a drive by setting its control word. Commands are built up from the logical combination of the bits in the :code:`Control Word`: + +.. list-table:: CiA402 Drive Commands to :code:`Control Word` + :widths: 25 25 25 + :header-rows: 1 + + * - :code:`Control Word` + - Command + - State Transitions + * - :code:`xxxx 0xxx x110` + - Shutdown + - 2, 6, 8 + * - :code:`xxxx 0xxx 0111` + - Switch On + - 3 + * - :code:`xxxx 0xxx 1111` + - Switch On + Enable Operation + - 3 + 4 + * - :code:`xxxx 0xxx xx0x` + - Disable + - 7, 9, 10, 12 + * - :code:`xxxx 0xxx x01x` + - Quick Stop + - 7, 10, 11 + * - :code:`xxxx 0xxx 0111` + - Disable Operation + - 5 + * - :code:`xxxx 0xxx 1111` + - Enable Operation + - 4, 16 + * - :code:`xxxx 1xxx xxxx` + - Fault Reset + - 15 diff --git a/ethercat_driver_ros2/sphinx/developer_guide/coe.rst b/ethercat_driver_ros2/sphinx/developer_guide/coe.rst new file mode 100644 index 0000000..c1b745a --- /dev/null +++ b/ethercat_driver_ros2/sphinx/developer_guide/coe.rst @@ -0,0 +1,37 @@ +CANopen over EtherCAT +===================== + +The CANopen over EtherCAT (CoE) protocol allows devices equipped with CANopen to be used on EtherCAT-based Industrial Ethernet networks. + +CANopen +------- + +CANopen is a communication protocol based on the `CAN (Controller Area Network) <https://www.ni.com/en-us/innovations/white-papers/06/controller-area-network--can--overview.html>`_ physical communication standard. In the `OSI communication model <https://www.motioncontroltips.com/what-is-industrial-ethernet-and-how-does-it-differ-from-standard-ethernet/>`_, CAN specifies the physical and data link layers, while CANopen addresses the higher layers — network, transport, session, presentation, and application. + +The CANopen protocol defines how automation devices are configured and accessed, and how messages are exchanged between them. CANopen is object-based, meaning that each node (drives, controllers, encoders, I/O, and other devices) in the network has an Object Dictionary (OD), which contains communication objects. These communication objects cover network management data; special functions; acyclic configuration data, which is handled by Service Data Objects (SDOs); cyclic real-time data, which is handled by Process Data Objects (PDOs): + +- **Process Data Objects (PDO)** contain OD entries that are cyclically transferred as process variables. Before cyclic communication is started during the configuration phase, particular OD objects are mapped to this structure. Each PDO entry has a defined offset in the exchanged dataset, encapsulated in the Ethernet frame, so that, during the cyclic phase, the slaves’ hardware can locate the relevant data. After cyclic communication is started, PDO entries are exchanged between master and slaves in every cycle and cannot be changed without reconfiguring the communication configuration of the network. +- **Service Data Objects (SDO)** contain object dictionary entries that can be exchanged acyclically. SDO works as a mailbox sending and buffering received data. This communication is acyclic and is dependent on available bandwidth in the communication cycle. This communication is not deterministic and is best suited for transmitting configuration data. + +The use of object dictionaries, Service Data Objects, and Process Data Objects is a key component of the CANopen protocol, with SDOs being the mechanism for read-write access to the object dictionary. + +Every entry of the OD objects is given an index address and sometimes a sub-index sub-address and each OD object consists of 16-bits and data indexes. In this context, addresses between :code:`0x1000` and :code:`0x1fff` contain communication objects, between :code:`0x2000` and :code:`0x5999` manufacturer specific objects and from :code:`0x6000` device profile objects. + +CANopen is widely used thanks to its low hardware cost, wide range of device and application profiles, and simple implementation. It’s also extremely reliable and provides real-time communication, making it suitable for industrial applications. + +EtherCAT +-------- + +EtherCAT is an Industrial Ethernet network. It’s based on standard Ethernet hardware but uses a “processing-on-the-fly†method for transporting and routing messages. In addition to being a real-time networking protocol, EtherCAT is deterministic, meaning it guarantees that a message will be transmitted (or an event will occur) in a specified, predictable period of time — not slower or faster. EtherCAT allows up to 100 meters between nodes (devices) and can provide data transmission rates up to 100 Mbps, with cycle times of less than 100 μs and extremely low jitter, thanks to distributed synchronized clocks. + +CANopen over EtherCAT (CoE) protocol +------------------------------------ + +CANopen over EtherCAT (CoE) allows the CANopen communication protocol to be implemented over an EtherCAT network, providing a user-friendly, cost-effective solution that provides deterministic data delivery along with faster transmission speeds over longer network lengths. + +The use of CANopen over EtherCAT is possible in significant part because EtherCAT implements the same communication system, including object dictionaries, SDOs (the SDO protocol is implemented directly from CANopen, without changes) and PDOs. And on an EtherCAT network, PDO frames are sent deterministically and without the 8-byte limit imposed by CANopen. CANopen over EtherCAT also supports the CANopen device profiles, which specify the parameters and behavior of the device, as well as the device class-specific state machines. + +.. image:: https://b2600047.smushcdn.com/2600047/wp-content/uploads/2021/12/Applied-Motion-CANopen-over-EtherCAT.png + :width: 400 + :alt: coe + :align: center diff --git a/ethercat_driver_ros2/sphinx/developer_guide/domain_construction.rst b/ethercat_driver_ros2/sphinx/developer_guide/domain_construction.rst new file mode 100644 index 0000000..cd5cfd4 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/developer_guide/domain_construction.rst @@ -0,0 +1,98 @@ +How domain construction is done +=============================== + + +Interface between the master and the application +------------------------------------------------ + +The link between the data used by the application and the one that transit on the EtherCAT network as EtherCAT frames is explicitly provided via the definition of domains. +Domains are contiguous memory areas that transit on the EtherCAT network. + +This mapping is provided to the application as offsets inside the communication frames in the domains. +For instance, is a 32bit integer is used by the application, the application got a pointer :math:`\text{pd}` to the start of the domain and an offset :math:`o` that give the pointer :math:`p` to the first octet of the integer via pointer arithmetic: :math:`\text{p} = \text{pd} + o`. + +The application has access to objects of type :code:`ec_pdo_entry_reg_t` (IgH master data structures) that contains the information to access the data in the domain: + +.. code-block:: cpp + + typedef struct { + uint16_t alias; /**< Slave alias address. */ + uint16_t position; /**< Slave position. */ + uint32_t vendor_id; /**< Slave vendor ID. */ + uint32_t product_code; /**< Slave product code. */ + uint16_t index; /**< PDO entry index. */ + uint8_t subindex; /**< PDO entry subindex. */ + unsigned int *offset; /**< Pointer to a variable to store the PDO entry's + (byte-)offset in the process data. */ + unsigned int *bit_position; /**< Pointer to a variable to store a bit + position (0-7) within the \a offset. Can be + NULL, in which case an error is raised if the + PDO entry does not byte-align. */ + } ec_pdo_entry_reg_t; + +In this structure the :code:`offset` and :code:`bit_position` are pointers to the offset and bit position of the data in the domain because this structure is given to the master that fill in those values establishing the link for the application with its data. + +The application configures its link with the EtherCAT master via separate API calls. +It first creates domains with: +1. :code:`ec_domain_t * ecrt_master_create_domain(const ec_master_t *master)` +Then it provides the master with: +2. the list of slaves that are used in the domain + +.. code-block:: cpp + + ec_slave_config_t *ecrt_master_slave_config( + ec_master_t *master, /**< EtherCAT master */ + uint16_t alias, /**< Slave alias. */ + uint16_t position, /**< Slave position. */ + uint32_t vendor_id, /**< Expected vendor ID. */ + uint32_t product_code /**< Expected product code. */ + ); + +3. the list of PDO entries that are used in the domain, via an array of :code:`ec_pdo_entry_reg_t` objects, where offset and bit_position points to the data the application will use and have to be filled by the master: :code:`bool ecrt_domain_reg_pdo_entry_list(ec_domain_t *domain, ec_pdo_entry_reg_t *entries)` +4. It asks for pointer to the start of the domain memory: :code:`uint8_t * ecrt_domain_data(ec_domain_t *domain)` +One domain can be used for read and one for writing data for instance, so the application may make several calls to the above functions to create the domains it needs. + +ethercat_driver_ros2 data structure organization +------------------------------------------------ + +The library keeps a representation of the masters used as :code:`EcMaster` objects. +Each :code:`EcMaster` object keeps a collection of domain configurations as :code:`DomainInfo` objects organised in a map with the domain index as key. +In a :code:`DomainInfo` a vector of :code:`ec_pdo_entry_reg_t` objects is kept that records the PDO entries used by the application with the links/offsets into that domain data. + +.. code-block:: cpp + + struct DomainInfo { + explicit DomainInfo(ec_master_t * master); + ~DomainInfo(); + + ec_domain_t * domain = NULL; + ec_domain_state_t domain_state = {}; + uint8_t * domain_pd = NULL; + + /** domain pdo registration array. + * do not modify after active(), or may invalidate */ + std::vector<ec_pdo_entry_reg_t> domain_regs; + + /** slave's pdo entries in the domain */ + struct Entry + { + EcSlave * slave = NULL; + int num_pdos = 0; + uint32_t * offset = NULL; + uint32_t * bit_position = NULL; + }; + + std::vector<Entry> entries; + }; + + struct EcMaster { + ... + ec_master_t *master; + ... + std::map<int, DomainInfo> domains; + ... + }; + +All the :code:`DomainInfo` data structures are created during the calls to the :code:`addSlave` method of the :code:`EcMaster` object. :code:`ec_pdo_entry_reg_t` objects are effectively created by :code:`addSlave` with a call of the :code:`registerPDOInDomain` method. + +The link is made at the :code:`on_activate` stage of the hardware interface life-cycle in ros2 control. diff --git a/ethercat_driver_ros2/sphinx/developer_guide/new_plugin.rst b/ethercat_driver_ros2/sphinx/developer_guide/new_plugin.rst new file mode 100644 index 0000000..3de5dd6 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/developer_guide/new_plugin.rst @@ -0,0 +1,166 @@ +Creating a new device driver +============================ + +Creating a new device driver to work with the :code:`ethercat_driver_ros2` is fairly easy. You should do this if you need to create a driver for a specific device or a specific device profile that is not yet supported. If you create a driver for a device profile we are happy to integrate the package into this repository - simply create a PR. + +What you need to do +------------------- + +To create a dedicated driver for an EtherCAT module, you need to create a new package containing the module driver plugin and register it so that it can be called by the :code:`ethercat_driver_ros2`. + +How to do it +------------ + +Create a package +~~~~~~~~~~~~~~~~ + +Create a new package using the standard ros2 pkg commands. Make sure you add the following dependencies: + +* :code:`ethercat_interface` +* :code:`pluginlib` + +Create your plugin class +~~~~~~~~~~~~~~~~~~~~~~~~ + +To be loaded by the :code:`ethercat_driver_ros2`, the new module plugin needs to inherit from the :code:`EcSlave` class and implement some of its virtual functions. To do so create in your package :code:`src` folder a new file :code:`my_ec_device_driver.cpp`: + +.. code-block:: cpp + + #include "ethercat_interface/ec_slave.hpp" + + namespace ethercat_plugins + { + + class MyEcDeviceDriver : public ethercat_interface::EcSlave + { + public: + MyEcDeviceDriver() + : EcSlave(<vendor_id>, <product_id>) {} + virtual ~MyEcDeviceDriver() {} + // data processing method that will be called cyclically for every channel + // the index corresponds to the values registered in domains_ + virtual void processData(size_t index, uint8_t * domain_address) + { + // Your process data logic goes here + } + virtual const ec_sync_info_t * syncs() {return &syncs_[0];} + virtual size_t syncSize() + { + return sizeof(syncs_) / sizeof(ec_sync_info_t); + } + virtual const ec_pdo_entry_info_t * channels() + { + return channels_; + } + virtual void domains(DomainMap & domains) const + { + domains = domains_; + } + // configure the slave module with urdf parameters + // and link ros2_control command and stat interface + virtual bool setupSlave( + std::unordered_map<std::string, std::string> slave_parameters, + std::vector<double> * state_interface, + std::vector<double> * command_interface) + { + state_interface_ptr_ = state_interface; + command_interface_ptr_ = command_interface; + parameters_ = slave_parameters; + + // Your module setup logic goes here + + return true; + } + + private: + // configure module channels + ec_pdo_entry_info_t channels_[X] = { + {<index>, <sub_index>, <type>}, + }; + // configure module pdos + ec_pdo_info_t pdos_[X] = { + {<index>, <nbr_channels>, <channel_ptr>}, + }; + // configure module syncs + ec_sync_info_t syncs_[X] = { + {<index>, <type>, <nbr_pdos>, <pdos_ptr>, <watchdog>}, + {0xff} + }; + // configure module domain + DomainMap domains_ = { + {0, {0}} // index of channels that should call processData() + }; + }; + + } // namespace ethercat_plugins + + #include <pluginlib/class_list_macros.hpp> + + PLUGINLIB_EXPORT_CLASS(ethercat_plugins::MyEcDeviceDriver, ethercat_interface::EcSlave) + +Export your plugin +~~~~~~~~~~~~~~~~~~ + +In the package root directory create a plugin description file :code:`ethercat_plugins.xml` : + +.. code-block:: xml + + <library path="ethercat_plugins"> + <class name="ethercat_plugins/MyEcDeviceDriver" + type="ethercat_plugins::MyEcDeviceDriver" + base_class_type="ethercat_interface::EcSlave"> + <description>Description of the device driver.</description> + </class> + </library> + +Modify your :code:`CMakeLists.txt` file so that it looks like this: + +.. code-block:: cmake + + cmake_minimum_required(VERSION 3.8) + project(<your_package>) + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + # find dependencies + find_package(ament_cmake REQUIRED) + find_package(ament_cmake_ros REQUIRED) + find_package(ethercat_interface REQUIRED) + find_package(pluginlib REQUIRED) + + file(GLOB_RECURSE PLUGINS_SRC src/*.cpp) + add_library(${PROJECT_NAME} ${PLUGINS_SRC}) + target_compile_features(${PROJECT_NAME} PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + target_include_directories(${PROJECT_NAME} PUBLIC + $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> + $<INSTALL_INTERFACE:include> + ) + ament_target_dependencies( + ${PROJECT_NAME} + "ethercat_interface" + "pluginlib" + ) + pluginlib_export_plugin_description_file(ethercat_interface ethercat_plugins.xml) + install( + DIRECTORY include/ + DESTINATION include + ) + install( + TARGETS ${PROJECT_NAME} + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + ) + ament_export_include_directories( + include + ) + ament_export_libraries( + ethercat_plugins + ) + ament_export_targets( + export_${PROJECT_NAME} + ) + ament_package() diff --git a/ethercat_driver_ros2/sphinx/developer_guide/safety.rst b/ethercat_driver_ros2/sphinx/developer_guide/safety.rst new file mode 100644 index 0000000..dce8158 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/developer_guide/safety.rst @@ -0,0 +1,83 @@ +FailSafe over EtherCAT (FSoE) : Safety and the Ethercat Driver for ROS2 +======================================================================= + +In order to have safe robotic systems, it is important to have a safety layer that can monitor the system and take action in case of a failure. The FailSafe over EtherCAT (FSoE) protocol is a safety protocol that can be used to monitor the system and take action in case of a failure. +In order to use the FSoE protocol with ROS2, the Ethercat Driver for ROS2 has been extended to be compatible with EtherCAT communications using the FSoE protocol. + +This document describes the integration of FSoE communications in the Ethercat Driver for ROS2 and how to use it to monitor the system and take action in case of a failure. + +In addition to the standard EtherCAT slaves, safety is implemented by adding safety slaves and safety masters to the EtherCAT network, all being «viewed» by the EtherCAT master as standard slaves. +One safety master handles a set of safety slaves creating a safety sub-network within the EtherCAT network. +All the communications between the safety slaves and their respective safety masters are done inside the standard EtherCAT frames and must not be tampered with or an error will be raised. +The ethercat_driver_ros2 package has been extended: + +1. to be able to record safety slaves and safety masters in the ros2_control URDF configuration file +2. to extend communication frames to include safety data +3. to handle safety data transfer between safety slaves and safety masters. + +Safety module declaration +------------------------- + +There are 2 types of safety slaves or masters: + +1. the ones that expose safety data to ROS2 and will be either joints, sensors or gpios, we call them «ros2 safety» slaves or masters. +2. the ones that are not visible to ROS2, we call them «safety only» slaves or masters. + +The «ros2 safety» slaves or masters are declared in the URDF configuration file as usual inside the gpio, sensor or joint tags. + +The «safety only» slaves or masters are declared in the URDF configuration file in a new tag called «safety», inside standard «ec_module» tags. + +For each FSoE net, a «net» tag is added as a child of the «safety» tag. The «net» tag has a the following attributes: + +1. a «name» attribute, +2. a «safety_master» attribute providing the name of an «ec_module» that will act as the net safety master. + +The «net» tag has children «transfer» tags describing the safety data transfers. + +Safety data transfer specification +---------------------------------- + +A safety data transfer is a continuous memory array that has to be copied from one part of the communication frame to another part of the communication frame. The data to transfer is defined by: + + 1. a first offset in the communication frame where the data must be read + 2. a second offset in the communication frame where the data must be written to + 3. the length of the data to transfer. + +From a user perspective, the question is how to easily specify where the data is located in the communication frame for read and for write. +Our solution is to specify in the URDF configuration file the first data for read and for write by specifying: + +1. the name of the module, the data is coming from or going to +2. the channel index and sub-index of the data in the module + +The read location is defined in the the <in> tag and the write location is defined in the <out> tag of a <transfer> tag. +The length of the data to transfer is defined the attribute «size» of the <transfer> tag. + +The <transfer> tag is a child of a <net> tag inside the <safety> tag. + +Configuration of the field bus communication and ROS2 data exchanges +-------------------------------------------------------------------- + +From the user perspective modules are identified by their name, however in the EtherCAT network, modules are identified by their position (or alias) in the network. + + +on_init stage +~~~~~~~~~~~~~ + +At the «on_init» stage, the Ethercat Driver for ROS2 will: + +1. first, look for all the EtherCAT modules in the URDF configuration that are exposed to ROS2 and load the corresponding plugins and their configuration. It effectively called the :code:`addSlave` method of the :code:`EcMaster` class for each of these modules. +2. then, look for all the EtherCAT modules in the URDF that are «safety only» modules and load the corresponding plugins and their configuration. It effectively called the :code:`addSlave` method of the :code:`EcMaster` class for each of these modules. +3. Compute the map between transfers in terms of module, name, channel index and sub-index and the corresponding offsets in the communication frame. + +For each slave, in the add_slave method of the EcMaster class, the domain info are updated to prepare the ec_pdo_entry_reg_t data structures. +EcSafety is a derived class of EcMaster incorporating the safety data transfers. +So after each slave has been added, the safety data transfers are prepared such that all pointers to the offsets necessary for the safety data transfers are stored in the EcSafety class and will be ready when after the «on_activate» stage, the values pointed will contained the correct offset values. + + + +on_activate stage +~~~~~~~~~~~~~~~~~ + +At the «on_activate» stage, the Ethercat Driver for ROS2 will: + +1. Populate the ec_pdo_entry_reg_t data structures with the data with a call to the ecrt_domain_reg_pdo_entry_list function. diff --git a/ethercat_driver_ros2/sphinx/images/logo-icube.png b/ethercat_driver_ros2/sphinx/images/logo-icube.png new file mode 100644 index 0000000000000000000000000000000000000000..cf22f48a3abdcb1f5d91dba020b68c3a425acde5 GIT binary patch literal 204123 zcmZU)2|SeT7dK9uiY!IST2zQ^Ep|iM+Q^<=NwSS)#@LNgk!A28vX?DnEym1X$Xa8~ znlZ>=Y=glV+wi~jJpA7G{ZF4%^Xa~>bDis)@A;nPe)mXM`_xIElMD<Dr|#-#7%(uL zoMvD+a`gBy;2X2J;jh3S$DZET)?nD(`;}Rf7YBTE!d=G<!oVOYy!V^YCkF%rzGQ;l zeW=Ma!NS6P;Y^Q?I6DKw1%|sC>P9|8^Mt?{;SFEGHPS#*8lfi5|94FwipcLfL7+5o z&Qu8v{bQJ4{xI#CNP>>OM!0SQ&Liil_TBe6@?{z#l{iU@{MM(&mXl%sEdJCro)G=k zA(apV<@=!h+tXSiw&hZ#=x;=mzlbkV>3W^*2#iT>cbTax>DaNAa;cR=Z6w2+M>8>$ z!%NUCjKfp}lNgDQft@23f{6d++KF%9+|+XMs!X4ODoPEbednI$;iGi(&RAGjFrjz1 zw*%VR+nYXIhj^^bqvVx9yS=}^I@qYfcZNS!k0|*@0f+wgL;NRLvTg<{_5Cwd2JGtE z)ZE;Bop+AcrrLMqxywlP`97H|Ih?djAIQQm>ha?$c2Y;$*22~TX0hq($_l17*J(4T z#7vEQf4M5|BT&Y3GGf_i3wJLsuWKel<m%d5fizu*OUM0tJJOW6X;Ko6-@m{4R$5w0 z^j+i{i3$r$JiPz7yeOkpu;Dzc;WGg&)!*Nr?ov{Ttu6mGqMFqEy~tkx%33u{sC}=M z#X%c|!<ARZLS}ZhxLH?|TQKyKGl%w<@xG_VJ;sR_|6<NoP+VNBi6L~fn>fpZgx2QY zTV!}AS$T<g{V38C4;PZOLZ3^Nw0_{wnNFa3>7k|em#9l)?>cJx3D77G*IqsBqE#|5 zCwSu+V?R+I*4t1^b;KNX6?v%Sy<lmH3fRbh^X5$=X^O{0cK>;IQ9u#8D2gPqu+X`z zx;k~Be;{-v{8L!DM3!hco^=|*<g_@sQX8j>R3N>$!Q(+0Z>ri}%DDjo!3XRPPSSf~ z`Vf1KwUl{LLWZ@a`KD1`&u<y*$>M&gJTv-+O|_4Vq*Zkia2?yN&PVq5t};A?W-u%k z5KZHhB#65Y%|M?zIw~MdOg`bsYiuk`$HzJh)R5(+rR=69mb%Q$%(t%YKRQ-?eELx8 z?KEAHVjFC1N|DJ#Dj@EY7^DR551G(*TMfB`o;!Q??D%Y-xZ|JiZ~l}k&K?Mhyraf# zdu)C{6IotS!4(m4-xu|pPtx>_r|{EJTQHsS{G+wK*}{;AkMd{c{SDn8?a4X|Q^bH> zTpEA<^0anDdP9E{F?ki*eGjthG+-iZ&gDBjDrutAq#6@&i9O%Hf9D?%+<#u)3ea=z zV0O%lz#+gREU_LcZZ0l}*KWK~TC09F?-+ZoR-p$dPu?p{FI3Kh)d?YA&g?%s2Ic5F zn&cUG=;PcRuLrR?s=BsJX8tTMN5dqHc}=Ua_RsKUd5`5+rF>@%z-Dh-*7#kvs#>g7 znLDw+M5^_k_%6!l(6zN3a%Z_$hK7bp@3=I=rYiyULwE7M!;U5RB{g}IxSH7%10G55 zwfWywe$=1dAi#K~`tz9or#@h%>zOB~ic3ng8~-r9(7VG#2uaS!h;|+*4x%-M3iy@r zSm+#hnywt+Dq==&)BwY>1FpBEsEF!4TTzS(rLXr`WBpx~KV$HUXU2~HCu;C-kxXXy zHn3dj2M7X&;diSERPn|TV#gdbH1s*U=cueVk6g{f)Ql87f*LPwY;5dFDI#T6y<T0! zyMJ6=5n$6Z#Y1{|@lWmTFOSp)341H1#cmis`ewdXN+TaaXW4OSmf5wTP$-}EUpZ9) z8-IFV+;C~#U%)*aurI!>5NId=Vv@yCk2xB@ptc&#CmkM0SXDZoC?huzCY~tuKdsb> z2?1iiiez%NC`u418LgsF3+%x6#D11XeiD6)Gwqq%f-n-Ye0So|B$K&P3CIl|&3OCs z3N4M93)#VI>bLRxTi5-#0<84lidW4;F-;^s0*0Z_M>RE({AxxJ(lg*E!&gQ9IJdkQ z31q6VRsX<!vnd@%5;{B#a8Alt2wQVSq3N&f?d^2@fuBjI?fG~Z7|D%mpPYRD)vF9o z)@poV`*k+mf-rJz%;K7N(h;cLfY&2VycJ|?&Xu-hgZ7arw!$P&kx1Ijr+W`BXJ${f zHoqEc2`M=nbMP%}ph3&9lE>f{jFFH=H0F<NX<1~--QxFxr1K5dKxck6BG3m1gP!g> zD*x2jyVtse`#vs<AF?=U$G7I3wC3f0x>-*wN&*A8dbB0xy`*K;A_7@RnLBv2`%Kr- zsylJFW8!ZAL&SM0roE^zu{Jli-dO{1N&@FEkjvSXhS;3o)90kKVl>P6`>h^74s$jw z$p#P)KeV%!%(}l8A3tClcTA36K~`2i_3#h_@J5KFoT@saSrL?h@oj4ede~E|tNVRj zLEESh6{PZM)QUF$`>V&~&q+ONv=3#2UddK(xxbpc0-)Q4M-{unB@vE!J@0rU?xXsg zPLUGr&ui*O9`PzHTWAV0Q}b4wjr#?o4ewAr&-E6e=cZDLZ6B^vrn900{<@4uNekcN z2+RJed~AS>{x7tpY0cxMc3>501u~;KBLO1_ueJkwVNN=lCKA;N+5)JxA54NiV;fpo zALAtVA5PtaD(@G_3lrH06p_Z!rLyDYeY&|sae5&kugJTph*OgT0MvKlrjmIDXI6Yl zP5<Yuh-e_ps>DDL?d|PVL3T0#Mm<QiVSDi2UO`69x8zmAA+!iqHSRkq?mOPtf#BCd zkR^#4gntqp|2c`<QxV`r)f|lfi8A&Y2u@Y^Q&LhWYxsec=BcS#+(Mr^QlO&-pIIEd z03FC1((*)zh6lwUMJtghsluMCchG%ztkA2Els(Dj0IJY(_suxi4zRt_Xu|h$00qmc zzQqsp_k)!lDE-w8Q2;(~o4#q~Wth#cPN0yH0;jRugyelef&mYBX}Aar3FqbI^`JLD z9T^;~A{HYLp<A#WdH&n=>dLO(Jr8BjWR-xKr<T=FnQN9+?$e70_-Pvt=;cUXZJB_9 zrJ30~WXWhN0ZdDef)94W&09bPRHYgsn<P{H@YT;ssW!~>BUtx~0=^Tm&_CY;mD01= z4=#s~6}VXyAX?R+c?N)00LCHjYEbH7@Y%b>gKf)KZ)IJ(%o-4BkmD!8BUmp>eS`@J zW6KG+nR+IHL8`*&UAY(gH*E{R+*t3B)a$D9^3!r>6PE!h@^S&9#Hh_kAllG+RCZn@ z4sTMe*w#bp7PhxP_^fto*KUp9VXKkf33%hVubr_G;F><?D^876l_ddQA(X?ZK*G<8 z`o-8Eg+{|w^l0n;-d#nvuudr1MV2KKbwa2>z*5uZT7mz;xrSAMbA?UA{JYH^Yr0%2 zRYzu^n@X+f^4@aZXP$9(saSvQ1unjs;1MJE8WIuzb|pec(`@R`_H~Dj#s)SJADaz2 zX=-X}{=f&u1OTaYi&7x~OtwFtdy_Lc8BO!6;r}>Hzm4vbNAmV^?O8U6KooRGojXM` z>1oEyXlb;y-yC0VU~5SbPc+QxE)Ch&RWRm4CUe_2CqX%ZOfuE)ObCkU#KZ`WWWP-$ zNalKP``^&LR%hXbSGg|7ohTS24=}Ezj#P!OZtL4%#k>2=ukH(gVYx%u?qk+3>j4-8 zNLS+fly<j8svn*I$+dX#On=#C(_MNqXd*789#8s}bKiqHn*fCc?Wir5;LY|p|KHE^ z55bbs6|AQ_ioif*sw%6Bw<zkL)?Erago;bYP@=u@9~LN!e;&sQYZlaqY!XS+Ae~qP z%Y9gORwvL$BK8+^PX_3hVbRD2>>n_acfd_z%B0Y1OnO28H7p7)TbVM$zbg<ab9~C= z<?!aJP);jKu>aZ$ESUC@NiYltpuihu?zI5&_XDI(g&jiI^$v+2ADn@XH%B!Mo14un z&O3d?6N;nf`PdY)fn#ptI{@2Y(`7jJ2Y)rv;$dO&KnR++U{l3DAb`4cx|gf%AZWM( zs~HvEe%UwK-)|xzd5x5ikPsU)p?(Od-K~J!sg8nI<J*D7qMOgpeX<}3EPk?JBbyMQ z!kg-ZJ@EjDtLr$ve^@8Ll|PiCQ0F7=<9uCRUA3j<gx1JOO67LSuQH1%(TTwe3;dpi zY70K01iwe#+dC^O4&$-f#evJenj$*!y!%!k3|zqEEjc;jW>gcv{cCqw7mq7VENH8l z(ig#iIdoijW+C`><g&MNypk%sI;%MIz}Qy-b&FVc_?{~+QXJpogX6yptZhaIyJft2 z)|?NaXW`z&j4m|mA*@43>bpYI;%zcOi>8?X<}JKvwSN%#Q@}~iI2(L+3k(!~|9-1} zcvH5gQtC{X@h*mU_jMoSOCh)~0Vx_@<u`fH66LADrRkx)=)3=Tk`|!WvJafi_-mO1 zPDRS7Z{Jp_x=1A!(9|9m7R8lg@1%SJV77R3l&~%`ts&$J%9!=z8Y}{L0zLxZwbCne z9NO-{v?Tz4L-c{`tDQ!_mH!Izbab4Vvq;m;j{hWq<9}I8nd@0bN0sb&tL~hTf2p$t ziuQ9LgoSBkg+*{nHTQ`p_5iHIb@71s*_s0ss^xjL|8sgd0o*eF%X4ICh=<@v?!Jsn zRy~ylJqqpHU1$c?SMa~~giMGU@c0%}>lPXkC7b)4O?!T;KQfg&(AD#I!IJJmMjxva zU`l5J`!3QI@$Be+aRU(T9Y3T{di2IZ%aMQA`zXRyQH-X}5!0Y^0=3XR8lyP>Sv+%} z%Gdopr<K|Jvg+Z0Cyu@wM0+!>|A-o}Tv(WBxRB5lCc&dn2e$y~sN1$!{>o!+Ld`35 zqNEDvK(Q4s?0<a75r|2ADX9<%Ny(aT!!AMoT#fu0Hk?hxABX+439<b6%&!Y~;bZ_3 zlmvH=q(90gWDNK`LMEHM@tRv{Q92;ibvFQ9S@@}rMby?>*4TkNd`B4;)SJ_r(dTXG zivio`2^lP}&{0~##g?^viBh0co~Y*Zt=E(p<k!W0g9vT_C@5b6MHhMhK2A#FniRYm zU`G8jCTiYme=#Ye{>(q-Oe3?K!<NFuRyCV_00V$O3xLZy?g}LxsORp*Oy*(3xZ9pU zas`%<oCKUzB@vU-lG?2JpDd%%EQ&Ml6|}QNpMt@XBh+H=TmV7lpY3~A(n-KFt$vHY zzylebhocx0UkLE_Pom*~ZgH~VpU$0-8F?sY#Yp(gYeT2;!r$sW_|-9xD6AdMNgKto z1IH}`(n~B!Rp);OfJgxhpwsAMRZ&sVV{7nKf2JLntMwXg`B5#x`rv?Nak1ZM&O8~r z0I_NWi0~!%eVOFT0B6G(unmo%y~F{;t}g#2aE!CCql(IkQXuj3Ll@T+9@r5g|Jt{h z!rlC%kU~jx!p6pRN+V_@0brzVEwwsK2L}09o`GApZtbP4C2lT}3$_N~<q~Xk%7NV& zLO+%3c@qjvC0qImO?!qd?H>F8IUtUI7ij4pkbCOu>mcp@OvI3RrXMq{HP4@oNsCDf zUYG}bZ7T|XQumQl{a(o1gE6Z`KL@n?XrQnaX8&MgRmZ2li^++#nmpviewpu=@h)kR zpC6Ep@{+6F9Nk!7vx>8<@l+V0Ahdg|=QP~+{WCZVh=+Vtapa*Pa|yW=Upu>%$`;T( z2^4knzXvUZsbPFkpTexon%`_KL;!y8qX-mc5P>Nj2a$r0i_yyV1#)TV9)=%Cq)|OH zE{n>?(!AId7oLC?9lumi`gS{7kl3O7S^AB3i#{ztriNY*2pk3c=0Cfw(+9F!7+Kbg zZ7O#UYW{d4&p^+dO{+;hJ}p37U$ao~%+?VeFq|F8MbnpZA}H&`=*w2n{qxH^9YVW@ z^R3Q};K_YJ9F_kigB*ET4%9AAUN{-iVg2w3G}=F4>ubEw&(tg($4l`kcK+rXjT<YZ z@tM5z2b%iFr}hg2?#}=lX;skfP%s(j-@DgQw3qXxR+FQUIozmj*TcuqH7B7=|6wBD z?Ub|rTsD5xh8lvQBG3+<9W9s)AE7i5T(^GT9pz60g55J-q^Ck|q!eXX1Idb!+4}}* zFxPh=vAbC#&|8xhQ(QVd->0EQt7<{A;VW*1u%f9kV6*o!a&p{ywIr39?{Bs^_ep5* z9UwE#d&E^|1-@nT;+BQrA`Ek;q0$?#fDFPm1gZ2?vHmsRTKZtI$Sucjs>Zf*q#dfr z2({yH;^LdIf6y`M6Vu-#e@kgtyq}a#0)8y1hSF1WeFJWOh)V7>p_Av<RO;_y24>!g zjBF6N1^uR*DD<hcpyT^WXJ`f%U?~i3S4`8Dkh4G$z}jZ-g;!o{MmrGB?EzN67V_|b zQ<plj4WB4xP(5cA4gVW{qeDI499&%$_f$NCZtdNdW%S$jePp196><MQieOEEC<lKS za$|jkiZz_zi+!q;odRi`E5UA9YBc6VaA%Z^cGhzIr{-XPbv5o>wVEDRufSj5?sX^t zx#{p@OU|~Vx;cKxVZX=7<g+rzXQsmLCsy7;ukDpq|9*y<#kSI2l1?&h@T{dmpcukm zQ2F`OH7anhGcdWuH17B34VS)ARZ6AvS-LIw9)0uF9SjGhmZqB4kpYrQJuqJt;Y?=3 z7Y2{LA&~1s<UW8a{r-ws0Mh_pQfem_{&49HsGM~J`DDhWatiZ9geyaU;1s3Bp$DQG z?fFysmhQe#du7EWSz>)zdwYt99Yt$oxY~DY>p?P*W%&M2q}ruA5k)&7>djHXXbuii zXGR1~m2Px3{C4;LLRA0>kv>`w?5gqtv&WQx5|<rh1+f59-7U@7y%Ak<<*WY6?*c4+ z+%;pV7d_J-f&$E#P1OfpO(HDzD;|IZ2Jlnu2{2Z+2E9u@0&#PgZwMmyDAy*pX|+2P z?yTk0<~2m4`d7-lmH!JTzk>X+Y)borsA;Nkv;GD%mf)>|atMei&+DT@Luk?;=_lR9 z-;)2DYv7!U5(m!_=o~)`w6sIZg^)VLSoat3exSyUXw81)8fZ?n=CgSYERvHmIXnY} z@sq5Tk^iqW*@$koiT;v2P7k0C>@(`0p^G6qdv)zoQCkq;lPt|4sJK_w;$)bFloY9` zs3TTckSIvMWg9@nu29I@i@)D>y=Fy=Y3`+<mKfMg{%7!0`|=P0lVu&qb~jZStFUPq zu4z6z)?tL{zB-=@aq;eH=NR>yBUeFZo~9~5o{!fa6r|P+L>c*tYra<{luOuoIL^E= zwGO<ArS{{`G@uk5{#XY4Um~fu40FZ`w`5z*0k$4n7>IP^+uwBzHVxc^twCw!$>Cc7 zn1CzIGiIrN4Zg<bz6hKw9JP7GJ+{ClM!kcMeQK}+^Kw-IGQp=$p46)z+$8=V=<ARy z!=ujrHP&Cge9HhpB%_cCqCJwTJy=F56?7Onu=$<U^t9tSKW?_iX6cCS)xsCyqy9bX zK?maOon{zSbK56wYBJT%7qu~uE2&QAPJ9nLMOu)%#XxfcsVXd`eiHmn7#xm#UPx`r z22bsurIeQ+`iFHG%+v&gasbABa|i+>v`aNKD8zWB=h0uYT+%lOYWRSMWIsC~-AuRg zj<|2J@^p})ie=xvrQ!<<g<q=F`vf}<4$vC93Z0$HDr*Ipxg|ySS}lJ+OaLJY&74ib zo12~g5cErtbf^?lE+L#FWRU$rQf}q@8)o$MJ|?<f08E2zB2_qt6X;C<+^|iYyjG0U zbnzbJ>OU&~af{ljsInaP=aUQOhW*2?OB^go3di!#oG4T5ixs_i!0Q;_3Pa@bfK zUuwm$wUtU&)przwh-o;deMhX53M8eypZV$m=~lmVQGF2aGk`|}6_>~6;3+DVn&ws< zzsB-sL2g&xI*Za5@ZMR~f{JugU3I<WnSGA1m;r)Ij_lUbuJrBWu`LL4kHH^*EeQk2 zJ;%$78F9b{r@JfH{V>kvRM5`mY`_7K(hX#DK-KBwenq7&{p97~?$UW5_sSrDAO{)Q zZkAi&bqf+Mc{rVn!JlJzfcJQ^Jo)q9*3tiCr@JvRJ(48l`F||1)&t;@=H+G2ky$8E zGXQ9`K4-&)g>Tqs)~yY_t#v0^-kTXkn|N=*-<78o46^@B-eFT^Uksw1xof|FMT5B1 z)9yU;XRD*aVrPgrqxxY$`%3S{ah?M*j7g`A<&ipKK;W+UWx~1t$lB#hTz;u(3{1H? z1%g;}0wn=FQ&<QF#kDI$KR9gLkKoNp3x_O(dI<~l14ZXQ-;ZkU-?FXgA#|!Au&M;^ zv6V#xfJfeF!jtt|IX74)O>ibX3`r0BBvo_5TB)qF9COZdzQDuRdiT{lm=G+PcTWXs zA%>GpZtvHVvnbLtRv-2|heYeu*cAgMA~E^r8Uk-2g$T60S@TqTO8CJ=ryqeT7z4<I zYoB5kFG`4}{q#KdlW;A-BE#gGcs8?iLrbJitT0WA39|*Xjes(hu;9f0iGw`=sTG0t ziiyckr=(m;=VU5S^xVr+HW^1|VF0UGGUjSd>owyJ{%xEcB=3z00V4olTY7vk`yftT zI)r}khGILPt=1bvV8IZ;-|&T<w=9bG3d_<^i^bO#SS!K8WT~*D?n4MrR$@YXirk*= zjvnYvh|wzdd(fX@rw@14hk!x@kY?;TFG6PIA~yrL1%RBd9)G^CT-{e!-6gST<m-?# zFO+?h#6ByH&@1ue=3k!Ik$CbS)7WV5wwi%Xx1l-bfSbs6J={8ixrH3-Y)S-j^^JI@ z{j;B$$;26*V<Yy5RQ1_cJV4^3CZCHVnfL)trtQMy3t;=0E}`1XdBE4-%YXl=F(`YN z{nfq(y}rq*spr5!eZ5?-d3FFj$xosH#f+Ww>=5SnVjP2cVF*^F6QunkUI6wg2z7M> z8j5@EG~bmegd_@JWL!f<X!1$YA@{t>%1YRS9)$x~4G)$y%n_(AdWGUmNfBPTDwZRP z^Q;QEcXz;&Vc{Kc2aUvzY~ns!VaNmOtA>|zIDwL=Fp%$8-{Wd5k}NDn*_#1vLHAC? z-2^{TQ~CYX85pe)O+McB1n_{Asp-H|FRz<`XehV3%48dxV%4(@!vKU9B>}ycFf*3P zwNGuDoE)*vB~scNKRIGI2OyGJI+_#15u8zB@xru4_TA0N=ho)<@KL{t^X*h!PLA$& z4hJD^q>hZ~l+XMSoif<R?6FaMol=`8nQH_O4r`4Sp6rEJrwSW{hw+IS?8+Dl3u&{Q z%};;AQeuKM+`XyE8REZh;e3*Sv_>^4u2w4Y78w}^;XvZ}qUhU7kp=Rtl{;_L+stbW zEd@O@%|Mv|!IseWR*RD^;j(J@m7~FS{=#Z<0fP%7tTzn4?(8-NUruprD#4bWma6s4 z%19;)wq<1u@gH$1WFfEHYXoh^G7;HScOGr0=vhWCZdc+c^&*10G64dP?9F7G+|M0H ze}-9V=!$vj>SvQ5ff2oI93-L5Kg0ER?jGQMsKf~cPtG;wYY&r0|3$HdH9z4$1g8yr z;C4e$U{7sOWXV+Jh9l3Y$K)lS&3xM5R)XTl!{16dux=n(;nbhv)4VF=*$ARXAy=e! zh>67OHe1gdi@+L^!Ui(FSq~lkcQSDcOEN;*@!f14x#mp65Qp(IdRB<V-Bu+cTVRXb z%u8kmAp_7?3)Ye2^a~z5un}@e$PT-GvA0}Dh-EQ!Kl-_^1MuNVEhT4P=mAo#_Q~f9 zP)ru@T&Dj*+L4Sqv4o%dvjDHT95AYf&`v>{vx|>C=kbpwd`5fp@|d|7c#BtlpP14O zs-Z8S=zR0cHhv1bv7Ld}6vcVF-Her{vn`AWo`CT?{~0ECRO)+;k_E@KF*7DT5uY+j zi{8KEgRh4yhD8TXl=)22l#>N4<v~8+ny}uabC`C(Q1}3{E~F`m(a%;mzn><Lb)A^@ zoMt_3eibJRaAOgm#yJ4A?xe#k-uOT|^f{Y!ri+rjyGZVXB_2Zqv6Q~yTcC$TrOMPJ zdLa5U^D6fzCTt`0+;7xN&WLsDXjM9Bb70re<%^3JD2X?u)VaVl)lPl*$zi;#P<UF8 zGg13yuXL%!VwDB_aQ6Cy_Q?6&AA&wtRhK`Ci{*R*VFXr-6lYl%;tCKo3P1_(KZps{ zRZFxpesBNHT>LK{{w(Ly6&#f;40hw{ts&^5zlVRd5@fWx2@0foZ_BTp`OHb_0FvP! z_qnB1L0<`w6&Pu_f2c?VK1~Xu&tX?BMtSC77F^HfVK>!OPNW!Un5{|8;qnF-%9R4f z%<p-7IuHL@9i_B}P!elNffTx6pez@MzLs2g67Q6I=$ymSxjyH8+2kJ_Li4@5%4djm zxn<E={LM6dj{5USk}ERC(Cj@>|9U$xNAP0XTo0vh<_6Nw*|fW^^xUW={=B>NUj^jX zgJV!<#z84KnY_&pr|w2p^?j(e^s>)BW{e!#Y^T^?aT)B}j@7NQv+ENqMC&0$1(XFd zc90|dok5FCzrMfO;BWWD0hzPdPd@$D1E36jpq6;Ylugo@A7UXc-he>$ZT}q@h_$u2 zxd{7Sg;5D@2#V^dMeO@f8Q?>!vCbakp}zA7zp3@PjIG^e_@?*nsJeXR`yu|tV1NGx z#E9FaNTnwmci#<Bq}_U(m6f>R8#Jt3(8QK%%vs6Q^Q$=i)%JFKjjJxz|6N|)$1`1% z#k~zke=qiV7^d6Y%=aU~n(k9F5FwNks~lB2PASnQ7NT5(lAFD^6;9+TWh&`3nAGFr zg-F)fFEn)NI&;xG^Cgp=0h1Nvrcj4yJEY#kd9X%mT13VMeKE=bOFKMM&%8n(Naz`( zCUA70n<-aPj{d=6zltFvuxozW*8hnTTyuQdbKuGwXd!MdI0Eqljpp%P>igweYN?Vf z{>5i|u4~;1oRX1C;rG{l<;Xg{Mnw5y6v)y!JRD*GJV{|qE}Lp&`gHH8$vwsVUd+r| zfUkDb8i~=v88DNlrS1sPta<N+=o_1-7!<Vcapa%8dH-OTWQ)CPQmuge3=2l}t?rG3 zw3}F4SVhUYd4CkARgLN^?>h4De(o>%>tol5N|I?udIY=3Hgl7lQQvCFJL?X$sk@kx zYMzk8-Yoy*D>2Fc2p@t7s*du(x4p4Ss?-ocgts-OWK^W;<fPUtyiQc;m(Ov9Q^(F# zc9JzU8V*vO!MI>aq&+qh43se&>r>`Wh^I$Vo%UnAwn+UACMXg!&iX1(UrU1nzJT3z z+R3+}lgS;ZSSMTpM}87w0mVTdh!3xyi;9h*2=2C?q1e#JLW$jlB!hc)Pw;%PS@0mk zz*14o-8)(w`J*1^{<{HN!9(cbGbt%@Sp+btqN3tS%kbv=3Y$l!k10O+*kt@vo@+o$ zTAVHVFq+QplpVzVJ1h*lC2rFxxFu*kr1~PSOi81Lm;4SMr_Jd&sDRw<?LiDs8w7oY zcG}p2L<KN@PrBsgsJxS`o;cLz+2GhMvgm%MTE`0P{hq>#2DZ2J^;G}@wL+>*J1^TL zV$}OrRVckW&ucr&yrkI_g5UlYx#$Bu{lH5NIVyZhh@>MnZc{z{Q*hfY=<?G-i}sO@ zOcMeOg2gRBQ~xvzl-RkT_$XP}t#|8L@Ub831i|WmJUL=L!)1R0{k0oqsfLJ42j#T+ zJ8Fr6eRq%v6k9O0uTzsemsvQ2@%mL1{nr8q_bo65ut2tH6MlQhPl{5|a^ecs&)?qP zgkEQb#TnJqPBVGhb+O7d!E}&on{z#&%>^9A20q_FNfWG1-n4q_A0m6>ZA8oK6`_6W z2RJHle%poCW=`*P0*8sR_3YpH$vaA!zLYc-45ofeZUye!tvVh)3*X&*f&3kNYC%9? zDSDno4py7aS5dbhiDOY-NykyRcYzMxB0Y^QPnJ8xJR#PQ!x5>tPb+(mPoL(9!%Xy( zihvOm=bSV*Lbbv_j;O?F_+W`!atkP&>h{;%de#vZBK1F5r>E43gPgJcu?AW1HOZO? zt!zF@ij>?+=*~EZ&&9}5@jFu6^X)KpeHtUxqDQX_9j67Yn-@440`|!f>lf0DiK^c! z=a#8TKh`$_?!tpQf5r;mrTvG|b@>-E{ZCHf*PW*N`YIlSZ$W@D08To>Uo59Jq{Dwh zKsB!+sJ%ydN8jbl-^;%dwfGoz`hg}BA(iPwchEXaDI1SnQ-SX^Z8w=FK9v`{t>caH z2|-{uqL@0G9I(6I%`JfbjS>pl#CRH#r=CP@5#ALpCpIuFy0_JP0{V9^2*L?$h4icM zYVRpYy8Q_Bd;ybpp)DBM^A14n^2qpKtw?o%EkKEaO=!8=Jy&oHX!#O1c8LiZYKDIz z<n5kwa$c*Ed3R}Y`<+dIm{1}|{-7!vUwf=6B22agHgs#e?GA~^jiue8P#i|$gz|#= zZ)s0VYu;<htgc`HFO<BlPK*544(r4W=xHv<;D0-2(zqi~y^nxnP=To~ryCYUPo(8M z1%AvJ;rcN%BZVaBU<pv%0)@MN-#1O1?yI;_b?+|xO`1~ul)A$JFc*+5ze3Ew**mKU zh0A}_8+)*5{nTB+sP7s3Q-R)cO5MhK&h8j~oT+v$-{@KoPJt(OHh(%6@`XHC@okSo zwavQqR{#!Sm}tPWV}#t(()0Gz)2XUN`1DT&Z43bcG?u(86@_~Y@5LU2%Zs;sM`_-Z zRc3Ji6}_cT&ngsbd&oiYu3hz%G`%HU04@m`6KjaeA!m9b!bF`2p^#ORTSPnTQlID! zX|xSKx21XxK21}N-3wY08J{A<ZhVFnXTT>1ixu{y`Rpg^y`8to@4M}=j=2teQ^(S+ zPKz(tIoA&aFqpmlB+9yk?}&CKW<F<DRx4$8^3HM6>=nOle8@gWLZlrL!G?e}I%;(C zWvaSCNu)4&n#fLKb>GPF`E%EBVV}A*z0a8!GePVylEjZwUm=w1*xedR!zk_LH}@w& zRhAzhoSHnvp*tJKHvtJ4+H&_=?F!Xjf@T>Bz|0b;&y{hH$JzEDpH9CG%sHA2m}EFs znA=GBPukv}4uyo;pe>n6T9L3$mB?#a|0l$j$BjK>f^KQA^7*dUC%1}uE;Msvmti|0 zAR0XK*aIA&{-yfiKj)VvFY{+4GLatHpYIkG>fofzMAw2;Hx{v=YZ7hR;no^ADmzO& zHM04Dc@{vvf&v8{uAe~f9%v?AIR*s==Wg&s#by@A>|L<*eZb0MfsQ;-wfRa;Sc4F( z-IRD_j}zBQa>)~>)X-9OcbfDGaRDjnUjU9;OoE+GT?edkjm8mch~N~fo$JIV!6y@P z$iDgg=5mu^^MX&5PJZ|WQ<<Z-SJ*;o<`z(>_0>iHtEwA;f)8jJdK^u|V>S2)ol_J` zK!WEq<aC)k7>O^sjqaRE&4>)s5vv(~aU<RB1`klrM+*N<#ihlMK=U36K)<R?Zvz8a zMG5`Pg@uKJQvUYCcSmmlV;lUSUicJ%oO?ZFrL*ZrL{u{|X>DY;IL$`6(UI2Z-A2+K zrhx|41_8@-*TxJwg4W1J_g{=|DZZAyqhPLq*kSr)a8G}#eDse`7e!ukXaSyz1G1s3 zPo+hKZtRWOjlJesOvjU9g&7XG@_<|koP&^1_$Qw-(Qt0k)Kq##N=gI@rSP}I68zyt z-Vu>epRrq~6i51{M6LlY{1k<%t{$?kkxvD|;9^n?N%fG>FdYRdFELl$a65JUD|Xov z+fYc{{ZkSg7G_biz8Bp8{qZMSIem9naL3An`twb%4xStpVWgpfNcE5X#1Z@ST=&C# znQ3>+n~EKMd^dqfiLqz9PRhsUScB5}jz9}{jg{jJ{7|)f10r=2SL4SfQdS))PDAU} z@di*#O;r%FdD*$7=Kb8C;V|`viqz0Vz^l@gG&D5M(;EU8yt|{Uw`X?exLS6z%o!cs zixY%|Cf7GgYR@mO8)ig+C?9Naqdxw^q#;taCqgGb%rj}8KXr6+)0RGGc94<hz6xGA zA-6L_sZqT<LWYIb55xSaPqWo=)$yN#N`m_DR2^n`zRvP#R7_4NTt{CE0jJJ7Efl%D z4Ip(Fz0%2te?T6t1no`^j8ih!Z*RBS(DOE;kONG4_Vh8=*tZT&9I?WAe6d?)1W)<T z!FzrwVskHlXT?*WQ|hc{H{W)3(*JajZ1^h9)gW{@Ea(vuT?>q|w)fuyI3NEpH*LiU z)}6WprZk8leFr_wSoeTu?dd}fO<hWa&8F+0;Vg-uK6N>R8pee#8~>S#b!VGE6;(>T z_6mG$G3Y|=N`q-A^HgiBkmgVO2_uc4^bwQ{3k8UGbw3Pur?Bw`zyz75zD8EJPmnZy za<;ttg|bb%AoI%AOM9Mp-QaAOa`&wI@FqDG0(3CMlZ#A7hKD0teUpx!w`#!G4_8H~ zfmL4(I0B<L9s3Cag>sM}oY}F-;sdIdI+VtYozdkvw<5mwm-OC@CoM2}q^fJnk3Q)i zyq(IvmxE@RYOmE2@x?hiA_WE-l1!toV}vvjdn0Kl?>Ymr=oZXcFyhK1f!t(ZP7}xp z$|XYK*9*U6fKED3lvX5@*WXC+CU_zKGn1E`oEvKh%J{K&OSw`%bV#MqKc)rrYQO;y zvvyxh56UI^ZbkwhhnV&RXRK#6Wz8>WKyQbxKK7NpOJ()?JjJW5h5CmV4I+LJk!rEo z91JDW0+u|lh6@1+RBuPK=e=<hAX(}QV>P5eZyIM;5fh~FKJZPjnQY#Xo{Kr(gp+v7 z_=m6IJSXsR+OMiAI#BuOAZ`MbF*xoT4L_xY;M2@ruNbXTl~)kuB<Yx_X*6D7sS%FB z5GC9uCdf^uXNgUEyIDR{Dv2w4J0EE+*GD&ect*swv@ZkO^nBbD)KUqyV4Ftl0{>)a z6JjLT87zh=sj3KRO}T=>TF&;D-M+YKu<Sfez{&m^V>6FaoXYK1_qOKlI2!yRAv`FQ z4$Kg7Q1o^t@mcEnh`QIhO&Edz_5lY_tr51~Mm34<<ZUfW1ui0+T59Kh7}<o<r&{+6 ziD#}Y#ZZICQY<S{s33F6{R*%@U-IlOZ=W2435ba6Z9v`LgZes&duESTbmq^t0>czo zOB<W$$>-O-F*UJj;Knt<N~gno3oD>ko9A|Ykb3*Mou$eNfxwBqehpP)m-e~M9w=|E zQ?MDhgedhy6RXv{hRnlmKwU<7N<f}>FF<pGmf8&IBdsA`3hTOWT4j#gYlrL5@y71R zHhT?DeWQz3C-%Z0LWk;IewUH3xu?83iDi`*?d(nAo@~AF0TM7>?CN^W8cuBAUZe5? z&2KG9Tu@RjNUc%Qj)B1ir=KlkGJw&q?7zcI5L15Gi4y!3#Yb3cUmqL|5aR)@ZEVwO zSMMR>g(ipDmRLJDBI1RjgQC9MW?xO^m8k^wW8f?B%NxE6+WYI*2Wqr1V>mRKv)9VX zDq>*NM;IGO*IJ<ZQI#|sGjU*jjjLa7G1$8GIW}VhDiVYZuC?ahGAuvFL_lZ{n4!u! zKugRv@3w-rS2j?c^up@O?x@y2&`n5o{WxIEH_rZ)^w+;C0qoSGCcRgIl#jZk5`C8* z{Rnt7fYQwCHZ?a;LekCS<p?S9|LHryX53)wCT7maFfXaC5zeVV8yDPNK^_x1t%-eC zy!-MY?#ENIpKB9qd8J&+9OVvtF{6nNUxsWrsBZE4dIdTs{nS;^6v*|1OvG;@!-Wj~ z>H2RtZf`Qdzp<bg1r)r2Neu^^Kx#z*9hiFWn~6LobBy3QX9Wu#2t@NS4C?)iH4xtU zol>N()K||GaF4NFOu><_xW(1}nyt!ovHw@@jLpf>aHgFJ(n{WLzuVN>kjcc2^%zsK zvaIHU_fW#Yp28P1{WS{QT{{%sC#H1PQkqjxzg<*Jr>t(vik(uLWW`LISammp4>Lrj zYBj>X_Q~}lg*<^QScDXITMgpZ|CB7tR!kb2FtYfKL{s8+$B^UoyW`9oB>`*Bs2V@# zB{K7*?Q2es+Bf@Y4C3C;+v(auB))c&x!-H|wouk)0u!uwekcT?<H%k<$U1}gg1KWI zy>Wcj4nQE)sQqdr^?yK_3?qBrZx{Qto`sDMz1RWOV1g|yvji?_mGoOwjQ@Il<{Kxy zxK(qgHcfbZ+j6@#bc6#wb!Jzqn)ov?q#319F0enz;eH9)Rr3(Ziv}unf0gb}j~ccF z3rM8$b}wcsZ95Ua5zCGiG6q|9nhI%VhgDP*segvV41F1z_55XO3s0LY&;+~s(esku z{~9ER4bC@r22N6a=0#Km;o}bQYuJr`CjmCnd*6BWIXewRnDxY_CrXe4(2>8NHIYpJ z6oVne&56`d_1}~_7og4$^m#La=uvWz!ir_fk^$ahu8a(<)PT!ELfYFnQ*+d)Cu%gx zX0F#zC^5uKfJ33BGib8Hhm^N7u-=UwVw=@Mw4%5*D?YLus`o7ooVcO0F{PDVpBu-- zALx4fzkS`MA@|(<Jv$m=zy;nY{%N3s<WgyEZe_8xMwx7Rhz2p#5w1e8c5r99$!f^^ zvb3QhZwq@Z<BWP<sIGwJ_OPi<bcX*--#Ssy*K|i}cWE)aMKa?d>II7-(y=OyrMBiG zH7}>0+G?+{yrKHvrt-&kpMZk>!eGiS7H?dDe(c`#*wQB8VSwLr=yMv2msb;afTm&H z$JDVLp>WahUEdr9n1OJr|5X+}ISA;H#Zfm1D3ku7q?RLkH@~xmww+_sZnH5&4Qd$P z+yM7Mec2btoeKwzjXKvQo3+D(MTfx}Si6Ps@n84dsyChkudskdY=ZoEr01lQs!RvD z8OE%E@fTeVdtLmK_N&=5tHk)!I#x-X=T`Q&*;grBq+FYT4XuEd&h4!AbnMd8o#la% z4u#29pn3_gbbE5GrW1>t@PDVYg&#sA^G^=Kfbmvfm?3At8ZKN?TomYUHZ>%Rlsn5% zR}*g#-deLhwXEg(l*RmGLFbITW7HFNq+pwFNDNr!_#)Vi#U{W@tahab%QL#d9dsE! zDL2wVmkQR==Zvanca(ot&iJ1@)xB&Js~-W{I%!~_^1@Y=U{VWoZ^kTMZ2>Pc&Bhcy zXQ-px&*#|P)beL<lMsITB}MXUz#$9fiQF(xcQaQ8W4Xyqaw}zAJc2Tw2fw_NMzj0@ zpC1hp3R?P*XBf_>z!m!`GL<)W7Qf%iDHZ33()5qI1FWGLIpQY{pDRKxPffM+s}HBz zeZMgSXwzpRZ191mh8ufF(G^dg4qNAogfP(pNpwimg}%x+H!8a|ICjSpa@HGn*Wud4 z7HrJ!TB3D3{d|<DfyO1?{f+n<^N&w2oQ+q}35G#do>v1?0~;1@H3@$!OzEs$3KEye zO$@=rSWgXM650K^B$J4m6XafHFxe|@4s<5h6gN;Z6;@us0a};Co`&p&o$ra(KVl&h z^=*HAp@`P*-E4FCJt<F(cm-M>jXMnBPhZJw|6XHo57Fod6iA98BOI+ohrY$VLL0XX zBS(V7_lDjidIWLJhZ#~W?Om8ew?tH%ULcJIA5#0+jURd2Ust6t+aSJz)=+z4j+!b= z?JN-ntV`@yriB}#HA*MMM%F+#7IHpTC_H`>>oa)lzq^#b{9HBD;;6IXJq+v{@P?J# zty|-J2L|RPEPMeC{C&$~>%F~znRSRI!&vq`vGMj4!jo3db>j9LIx;=%(>ZH0lbdj* z3Ani>=ub}4R$1pHcKJ6veV`u`dkjEWP$jRzq$uRP{i>2&UT;|Wj=J2n{jntZ%Le@? zZ+Ui<0q+9>gn9w0h;O>vx4k1vk8xwc0AuE?o99Beg;>4Ug	DgGOk<`ziTLg#!xm zy4h;$?(nKMC`FhnBqan|Ob!i%-w6wo)#l8vRp>*@uoY)y00rj2#VEneTDI&hsnqj? z+GBWptCgpe!Hw6A`>Nmy@39UBN|`<@yrXSyz`Jh1JAyi&3pQb+VE`v|GQaHjk(nV? z&3Et`k|P$UexY2^Ew;-Zd+PI=#qB`IT@HMPiMTKrMihZ>*fbvA-QZq^Z~ZQrTpKE? zm!$`|X&^Xjo;;Atd3$i*hD0M+SGz*XX0sMBwl+Km3$>}Rc<+0zv8Z^oaCth@zna?p z(1_k=xi|l#YYUWWM%3j<vf-dL@8#018GV7l53!@1pZZng*uJCmnSs2=bp{AMlcThe zb>UHJx=%~rmZ5HlX5p4rg~Ddce%bizB4B2aj#z{6RLGa2qLzD@G~i8y&7+@dQQnW< zJ~1pMoP56^aqjZo{v0Mo@SCQ4gCb{={#LLc6G6f~yX%RbEQbGRLmxT34Kn-;lh23w zmvThC_G*DW5^G|EPrO_Inz8N<guab<LylN~4j|dgJs1nFn-|w@h<G5@G&^fvy%FU$ z)s)jTJmaEy4-cf1WNG6L<4kYQx_iKEi9Cg*8Y{Fs=5VecGE6o)ouPh#w;LueN0vtk zD5)1q;&zr5#!1*^bLF)&HerJFw!{^=QR_}IE;_`S^y@!xOg(*_zv~)K7I<G$1Sr#$ z;0a#8jhK1%S_-;{8IrE{IX<X)GLsg>#gM00?5d#vv(`;Ep*zJ^BFj1hHu`+FMX>Ck z<*(TEQFLuAvZ1CX_6r!%y#z*3*l?4gu9*L}c@X>I_%zrXOSX9ryhLF#_d#xCTMG<y zkAW$y+0KD-U^sx)jC=>2AJ(c6v?E^9Vh5tUS^o+r=2W9Axj3T8Imhy*eb3F4HN*LU z&NkC1m_tD`_Mg8Mm%S|viH%IqxwNlWtU49glnB7!`EMtcmAy!2Qb=topQqY9yB8}I zbt7^G8we1}OOEc}>APQP3m$&Pee_+2GzZVLOL1zg2^Ochjx$;$9GO4L{PL%s1=bk6 z=~^`E_wm}dKru~y>{YHJ&u){;pMCP*+)_KVZS?s_>zjz=m|(SkK3r6Lep*NN!w>s~ z#I`m_KP|e3rm&StYP<aG%1Yby47uhHzLJpNr1^>gbANKDK?N0kkzs63Z?W-Pr}8II zpik)AWG35mZmzKK{JuUuhL;6G3>Vn9=)u9KB#&Qw&3^m;`Vo0LyjIOrW0P*FA=EUi z;!krjH0(K3@MPToGrf~*Hkn2lKlAqqSqV|wt8PahsoyrH>9DERZhBYE=ZaLIbMIye zS?j5DJ8cJWy%7@JSbev6=l|N_?}nT*S@+cC9-^h?+CpLQQL)+FTJCsPj}w38Id8%= zvXj9O#@car+4sbf4_RGeXX@DY^dD2sf=8r=`yHHfTAH<tnPKT7|F8J$x3vxfD-XnW zlDY?bzimgU_*bCvH{J!Px+zYZCs@AW7(XdHBL2&pQR?5LKhsI|xnP8^6uPl{BuvAd z&{8ZAFk8>PWQwGl<A=~uF_Pm?t;#|dBQr*K|ET=my4pKQcG7XJ9w}b&sfC`Y+$oXo z(ry-n=BBCz=h*d?8+5Lv)Biq#U?e@&uB~LaN|}*A`p?s<SGz;C++VS!T7@uyTbEHz zBjfSV_KzymT9N<Xjj$UGM}{9FNV9bJ_Ex)hj?@hG_Qs30c|GGI-qYf>q&<cot^QXH zF?Jf&dPj;AG{0o>DlDJW3GT?%O%24w`M410{_e1{M!onr{r>;&I-Y%dbn7(8$oQg= zeuVjtN8de599>=S+`k{Owz|sarS954XBPkOQ?2fbTiRPmdBym?5Lysi*rb9s%Z20S zAz1!UH)5QKxrhb+U&}yUzDBNiPx0@Dx&?RlXBC`b6ZJ>M{NLN-IX@b+(=t3z|2*Pi zYz*j}o(QSpzRcOu9u14u3=F-%bNg~#;ms(&&qciULenpw+T2lE<A0%TYJKr#S+_mo zl8#pc1JREDfDpYu3sAeeX%+e<3JK~FXbf`+gu6xWc1^3uma*VSCTf}&3R)SbxztTR zi*}wEk<H@E>qw2PL*U*Sij1Z9<lWKe;yrZ#?88K{xRxegQSTFNO;^wP$u;lTM<j|v zT)BM1Cg$;9n^iZWZqDhgVgV9|__`79dN)k%(Bc)Ntq)t4PnomUZl3Ps3L8{lczyM_ zM%D%<D_1{7$&dZ&l0o|uC=4bn`1bfK*$LyUYIof>83~%w(MPMdKYp}b`*z}Swe7Lx zkK?b!h?L4V*EQxFjqqL<kFZyjxDMP{aehAd*qJtLdGooMa7t!Ag+f-i_&R=Dk+A|C zdExaCYka?VFS`(`HDBMO@QupjLf>y*uRo9YK1PzA8vm>be1q}TyIH%<(ps!xQ}aP& zY{7WEnW3~B45jvx-HC2jF=b`YVLb2kCS6ZN%&pDh=KSVaji7*UC;b*hvgARRXPiGo zHbjD+)cE;7RyMl84zgZaV3FGXWhDRn>FWzY8Bw9PPjSfCNa$DVkACzz<r;jvvj4`X zoFZnSR|Bljv4jRPyK(%x%-k$qr8VTG2CdAcF{Se<8fCYHo*WKCb&mLNzH2@Fh*wVU zOp}tX3S-ZeCJ&0^*W9sqvq{l2>KhZXsi>tRCt{GkkEPP}j+`+gw4XkE6K$0xFPspe zv(@kM;7=3&6;$i;rsYjG9W}wUnA1y2S*y2|XPB4mrf|x^sXyL?b3PwF%`BUlj0`GF zB)O}8#4!%il9aW!Yu5U`r+H72k24tc3pBp0RQ{=<?_bJ~XZ5;}M{yp7?!?6itqCeJ z#7B&U9a{N`b6@yzeI9=#FT)5C=b)#a8IJmzXS?&o(<8jpSJYGM^39p^I#+qYB+R=$ z7mf2n1DaCpcW#z0-dqtpZ*d{ZbKUC*iw67+3Q=4v$p?1%wXgtw{p3Yd5i4;K8n83f zy~!l1MO%+tTVzAPe?);=Qi(Qg&S%f_K}c=Qz)QK|L#N`SM;4vj5uLAeTVsZ+rW$6k z0o<z4A3`%<limS<*Y*LrR!}-GTNe22%=eGUYno1Sp@%t2fY8C)3|_f9G}i75>bcxD z{{2SS?T21GMqFgF%I6`%=MC$ooshIav(b|r^^g*|aoa5p9rm&O2J*C{Q>eIx&N`Fi z-MsGN)$a4Q*kCDzbBE!FM{V8()hadqIUQ=SKJ;b6@>7iT4S3;INwXWw1>x6qMO!RL z59%8!_C8ym&Pcm1%S%|x-!Vw+nfh&YF=JPyM`>lM=ktr~%yV^k&Mx+tRQj!v+?pe) z7SED?q@ZH-Qx|SEXZhc{addO%;$e6v3(p~;!GW%i{=7qFK^7{rtd&`_w!G<|of#3U zL%!$mMO8YL(WneopR7~#UcQXSZ<$HDE!%gAOa6HeS{AR#Ge&TC)K&kUJpDG@a;*L4 z5f6?s@rip}lbc7aW>0nnh{voqoVb|XJ8XXQ&B^1$+sEETK`f7d><4ijUw+|=v%7C! zQ)>h{7hUVg?o7LRSljPp;8a#whS}Qa?^)@_^)pxOHX=Q%=@T=LZ#c`Il}degnK>8N zyDZD_s+w+f^t?i8E6J-CCUwDHU*>W3;3T71mYa!C<A98t;16Hg8`BrlTmxv&SFaAa zFXkGA)mYu(#orz0dv54Y`)=yQx)@MadH!0O%3$S|Gz_*nCbyLmTs-nU`A+7pkR>Dg zTQznT$zmb9!=QfM$#W-J$`p51mORhTj9YB=HhMf(_2%(p&`nX`a!8dwF*$k0z2nvS z)}wVF@=RO5iJkd^b!B!oA|ux#28jyqB@CokPF?!royTTWC-4&z8ee}z=3*9Mw@vv- zf~tUXghLi}XzIGM(npiQ3#tzmS%;c=PISp53m9PY%3rRf)vQx1>8;|WYYE4WABpbc zTXM;FvvE}wUN)@RCa1K+PaCxD-1!z1K?UWgv0Nex*i<fQtX^H}Ka*!$e|J*ewVyLJ z;McR%TmG_B9qCS^A3}vXLJM&j+E~Ls!|$eKe{E0)oi5nRg$M5NCmtfa-qdL(&9t!c zD^?d26_LYr2AUKjuaqfTVu?%9_0qe+Pjq`D7bs84gjzD}I%K4ZD0#b&SxVIsWB#yl zng&9}B(c**921eZqhFo8^*V+FDx{zJB_ZhLP?RO5x9O6BeedTrBTjvaMYWN0xqO=| zr!dp;(vpvNycgXx?`yMJ7r4Iu{Imga3>r2z6ByMcyfJ7dA-e8$qM%FMuk}&PLsMeT z{PI|{s2$R^^n}x07U=flRbN3*{lF8a{hiMLez(@Uc*BEF^22p5HzkjgXVZ)j%<tRk ze|*Ks>}H=3GI(FL<{Op3_^F+7(Mi}~J=mD5g1C4xD|V9~RUP|B&gOh{^4;e~C_-<X z&(+*;(*mcIRV1E9{E^5uhV>R;P&90M{A+ak+Irdfl`c5kX(X2veu!NukHPl4e6{z& z4NK1{iS7D-en0l>aN(e)BSF_$R*t_)ZPyky3nsFv`W(I@(RKNC{PO0QSh$kX2P2)t z)|SAW%DZr@-@yr;H5}q^@4np?b!*1XwCvC(7k?kNa%d~Ay9{`npj3L4x0J$(6$ic8 z*E)}0mYgl|_((r|<jDkthK2pp{Z?F-Mu$VTs$Qv6x8FT$i5;~1A$jtJD_M(Le1%}{ ze-7_0_Y_|b(|ahzpYg0wMlnqObLYS-U+aIY*sq*tB5ogMOV(@7)~6tA^zJ~|r5r~M zH5J)YW%3T?JrD?8(JNMK>V3CfV<;}|b?<zKg{<i-jp4#d_7*PG?=bVtpI>}t{hml2 z61%@nlAWG7axvRy<;*Sr=UioH{8jafY8|w<B^84MZ6vJ+`uOUoiL(W1578twCE&Un zBLHB`Y2g3-#hE8H`km_X`J+LzG83Q^VzAwhV>^q&8<I2Ux?m!d5!!oHPucwIA3j_8 z*WHKqOndE_gpvb7LlaYpPq<{xk?a-|KF%<~*xm#_wYjMO7<va@%?#bjs;D>>%FAoq zAWe+a=zT5okCMR9C`JB~;#(RM%gSv9bW3PcI3FCL&{F-aIiuE2rtXl{?YBKE@t-qY z`fQ|{xVW#yd?s8u!v~o2ExnG>xZW$ypCtQ1UaXfQ_&)I&j?}hXO1OQBGE{t4rPuFB zr&0gMLgDB<Yq#4EP1#_5H-%BTq57wlHhj?kA75Yn)>hkeixZ$gkU(*7kpcyZ7Ykmz zxND2MySqbMC={nS1d2;=Z?Pi5-QAsV^1SbJemK|ledjMo_TDr1tTk)R+_@6(ceo4> zBidt^38VQg13!w2h^lp=rHJiXJpwxhA!93CSB(#ev5>ZdKx&iD?COjs5l#aEB8AW2 zHmHgfds4!AoR<Y_^ZR||uXq__9t~oZFT5XHEE0_8@>5@QAgddP31w$Gxc=VijAw2f z>TRgMF+1vqxi9_3tTtOP%B^j5G9P|f4c3fD(NE=a^w;0gutsw#gZY;YU0GhV(Oec6 zX9eN6UuYP3z=zVsY*WzGOvM+sKYpz7%Ns=Fp9RpFTUHJ(@O4x@on+tR8D1Px8#H=g zwqy#$<CAZiXvKyR`{qFem@fo%9w0Tw<x#>S#J6oR>N{Gi=8l=+iH}3zHv6>~$zNXj zOkE3nl*Bm<ULC);M$Uy6jR+qF?x8us)r5T$nebtBdy}?SIi%u>5*xpT5jpr3_jakO z=XSytb9`xWZYA;e@qMsp46GJA<cCX@1?4G`X|`uYD#y1ob7wUbc9`1$vmaDMJY!l< z)O3<(%OUkzIHv1JooHY!rFpXY@C%uM=?60S>R~hDA-T6lSV@zCdG`8L<?G+gd}!tB zGH$xlMfE-rfn_f4DJ%bY7%Eej5rkDs-=Ai)RjbE*o1wOwZ#OocpN`|@<TrV$3Jq@# zspv5uEp~%5ee@0=4@kVE%gp<OIGW?&l0pq^O)$*8kYXW}7K0y|nU-Ufo#7Y78+G4P z&$3;2O!iWAKaR^Yxdf()id#s(dlv#J*mQzYLg>reHQbPM8yiV6@u~kJppD~3uiz&M zVy7m0L)W)j`H;x%8wz+wV0vI@HD_vpx1UbM;Mq>P>mLQ%$2~C;RK!VR@e);vmH^G+ z`TVDVaKV)TT^OZ`!PEDZdu<WS5s+C-j#JDh>o~KxjBlOOyzzR7g$72pRs*h%l>IG| zRD+Ff{Ri$^$Ob}kD$HUwc|FWznO52JI@=h|#vjsTKMg=vWNX{^Okl_-4@@bpyT0#} z&OA$Qq(9d<%B;E29H{vmuJARYr2WZ>a8(v2Ak7x0uzZuwk?g~Lt{SDbopNaU7M&jX zx9iZ^iwK6TrV>p%GloBl(dDq2-O#a<uBWdLzd)Y}FGkri&h_8R$loH{Y0QKr*y%@z zoZ;Jj0(CUeqcN@o%q(IXJYyDbsEmoBzaC?4ESh(mqh4^%6|V~gf<L&Mil0|U%xxO9 zmMRB6YT#;V!a(=hr}Kq3#g{Chr%a!a9#(P!x9{fAsp#J{?-8BdHRi;1_&$G6=Px&) z?~}1TH2m%6eh@3fWJo>A9KWzoa>7#am%4&J2W_HA^xYES0&z|`z^KapuPi?_;n};n zi+RJR4;qe{)Q0-ydyR(Aa-oo|6|2XPkPemwjUT;v8p^_gtOU8L*Gh}8VEJSmjqnW_ zP9feww8g_n^sT<rUI@`Ym3#F@IWyRmL}Rs$$+eB_JHM7L<3~tDVD2dE;e^QRLdL~0 zxw{#qeO3D!2ioMnP(A%kn(QV0m7<QN`JmUvRRj1&f<fbB#VFw@Xjn{7IwQiP(XW(w zEQvmEzD?kLmY1u!$49;UA)9Fo3tsQMeSo?jyBWBgYZ$b7;f)$|Q@C0xk(}*V2YY>3 z`#zdaeZQerIJIJ3G&-vMj#8k6JYrb{=%{4jU)2Njt`_%Pb$5A}h#w0Qgj2dEcw5Jd z`45-{p|^y+C`eYgVa#}oH}ZUK$?fg}Yz%lEmbBrRyNGS;s%@nE6XwFMAwgRtJ-J=^ zaMd^e>QH1hxY$T6&hnaHqV;@RM6J)U&c&CaeUC8>RwTlvrlqQwk#~&LG41OU+LU9~ z+_jzdps<eHAkLuf&id7GGVX?IY3tzO=J?{|jObpOYgFMB(~LStfchkppNce_3+F`i zfwApjQIM=fa^Dcg6rN296VM@C>hb^S*wr54@zlS6)MS2Ov?`|}v*z1^)R@?8_%=<% zH#AOg8g`Qw@T&A$8*Op`8U19(pk<ZO?>v!Y^?VEGu&yp#uMB_^Jq6O7>k0;Ple8@~ zZQYjD^WLvTvJvokT0BH!eN};|OKRavb(K-#^~3RtRMqZPz3alQ(l~xZt2|AhJofeB zFeNpql?m6SF#r8Zi9V&U%b{H!VT(8VQ^?(m|D&ruKK06Fi|Ez4M8#|i{;p7nh3}CD zU4n1N2b%UIp8%Dl^Ju>-E0#Fzcf9z7(qG%S<OBI?AgJ~%eT#35#cE$R(x5NZtv5S% zEd7u#mwfOBKJdKOQ0$G|9_u{G5ke*9_#R$MGMa>7>cy<~=RqxZ%yna7U&2VqIlYv3 z^;aR^Ic~nmx+}$28FUccKz)FaBgbpIxX%mHDyIC&9YjON<EdAa_rMndGmo$73Wfva z?y!c$T~<*=zOS&EFVpsnX^DSU>@Ox6>HVazy_%So?Kc$1^2ruQsJY3(UGMS319ytF zRwO=uKw0z8yGS#YM!c!NW7^}Ot|XF!U*eu`qcbLiMc-&`-n#w~-2TZ6zodypCfOx) zp(K2#R{e54Wm2Vk<N4Q*J#Da@T6(dL^H81T;qIZtC#3>Wb#J6hPn!O*8@{~a=2}N| zrZbJM{DBm)g0a+{?;eEyjnY>%_-&BM@I18xzP9Fu(kGVvUA6WONc?^UglA<kF~mtr zVf0UaYH$jJ=?8DgkC|sEip)K-h-Z<u9O?h`d)xfFqBMo5zF9IlwypH9Oaxg$5{}A! zC+nnmb?GmOj$b|$)GO|9ThsXv6R@s%knXGu+GsO&d6K{MJu*}yk2n0Q2ETVYg{^2= zHj+L`+OK_OYZy|>3=4#sAj6Nx#*$dn`z4bwlN6>8odO8K9~PT6yY><Bm4@#q>*;D4 z+$vZCsYfX1=}#RR&gmW77I#6Xcon7f4-!BS#cwS2>U)37RnBi6(kKV1neG$bUNV~e z&bje%W;BD$r_B%a{<ohU{WGiP+DP$5Z!oAUMW$re@~<$#@h3ms=)CCzK0@q0`WJUO z6VCjrLS}*T;bPm~@}IfLv7fHOggCg(w&Emf{Ffls`acBf>~Qw;QRX#@aW4rnE&bZP zuHPAW4ZkpO+gAKhdn(mtKjBtf{u}RI*p~=Q8{2CoKMvKXFu-(FEm}UJi)Q4%*(}mz zzJSQVlg@VQb*>IC{v-3xm9@JAGFNmF<2m>WgI3oxzh*w0IIWZW-?i_%i^$W!Wqpi3 zL;D}IEk{Z_2bM)?o)1FQPrpsF<%gzq?hY=-M}<_C<ySd$czAj)1Toi95H9av3ELP{ zj$<fue0~1~6J0k~_>^8S<9|egnd5b|aVf2xl_w%N{C=AT+a_3a414nV^-#<OPrkjP z;iuWQgSP?g9U#MaD)ew;f093V#C|u;EbluXrtDuv&QUn%4lD0f=+&*Ug)8smezmF9 z80QWMD7xSttl2xbLM=Ox`KvyGS?j##SYipHE9z%az+zq^eB(cX24H=)fwME(Bg>%| zRZH>*D7VbYQF|NuqIECkE3*BzyTTUo(|TFjX&9S~JX+=+t{dcb<~d!fX^{0Z`S|sx zx>U-ze5J07-9U5pa`CPw_SF831{~704E#6WN>kAQ!-on6zdgYK79~DM2<+MQ=0vr= zgQ>^!14}#!arba1I&P>=4o1UsXx)YXU4d>E(?5S`tsVbIC>sZ#&3+y$3Nu)r5d~SH z^FufK$EXZcXK&CZQk~o7YIHp0z;Nuad!runBc{(^^vLYQ740@YRe}wZoJmniW-^oZ zq#F6aNO!tuKO56Un<tO7)|b1Y%7gJYrlgbX>ks-k_v%0X#H?us%WpW{b$`DNRkt)L zJ<{sQ3`&~F%sD-Z;nMEMTu@smxp64z8p-rTH5924xw!BwHCPA=LHCcQ9aIyj`hIZz zA1<NwO!u*CpfkJ~)gxSi%HqIQ`Rc|sDPv$cwJXlW?`+Zgb|vr^&{6-bp#`zqcY$q` zrFLv5CZTBN=z*5j)(NN8-0SO03&-0RKsnq6p-z+~iAuo&_x}lUS(LQwef&{l(t<`0 zs3)cWB!is54hN8_GrACzGAaWe3<{O?X7BhucA_JJW<?gH8f9g#MrA7Jr=xH+uXJu? zcs!=~Ys1OBi4t_rsgt7x4Qee!MZK0;bOO4Dva2ATu6LEfP!xq4{u+9Gi3IE%MyAbg zLd>i4ZC$f1P~4+?7#pA2Q<Y>K!Q&kk647w=ewpX$c`RvDT*LRT87g(ci39p`W@$j~ zbGD!lzY=Ch7|W~<c>qWwl8i{SR<<YoD~mPq+S)VmcLXnrRJ!|B-t_!+wTy-gmng>$ zsfWDr%f{(^i|H>jI|S?dSfAFb{nxE^phz+(rne@$xT3?`HxzzYs^=G2Ufe4SAghNz zNEeUw$}YQe!=28ey%zGn(;F2Hq#qfH4+Hg_1<qPs3jMtwic}?igZS3YWcfb5E4?J( z{+KSQQY8k>648oMgI+Bv^=&s$SNMA*2Ec2myz1M-4|wPbSFXgGInCSC-}w{5w;m_Y zl4D6tmk);svnb9R6PBox8e1emF+ln*=jh`IDGB~^IsRBgUvLV>Z{^s2qx59`W}K>7 z3;|OZ{QL#sO#J^~mq0Fvu7%S-y^Q3wzvw(?vmFMEsuBS4Br%6BBDzAWAA+=oUa^IL z^Y&T_08&T4T_^NW%TG&;kRg!5>Yu+Pa_00RM;za6z_V~WlOH>=Ijd+BlG+^&EXqy7 z0YxfZ&;AeZ{cc5Yoci;Lr2Ih1;%!Rc+-d>FJN6+RCVW~_P_<Ql?XNwZnTd(m)&R9i z7{t5TaXPjp#(1-ej$|w=VH#!-R7;|f{)?8tH;RF}sSwC%NlRy8@f52H3MMXF$}lsW z4UtZ*HE8wDF}hEU7uU}2+38nBqY?F`cDOrO8DOb>6>Hr=PV=Zhd0uegzQ~y<tY}>o zDO|B#&d4D2=T!rWiXlNZE47Yxxv}56W?M@KOMo+g`tp^9#=}Xe*Jp50Imt*r=p-W% zXY_llckQc8@+B$USW*SwrFR;=etT5cS}!T+2BW@uiGNE%hN{=Mmj({LI@WOfyuKXa z0kxmz^RvwKbc(pc0uR!z8zc4>pz^|lGl6OBKf)8ACs6!$^TW@;$9=sX6OlH6WCOd} zw~v^ok!|Aq3L>Ne*Xss5e7FmrEP{`N8t<&AX-L>y9tF24FaDATwix#z;kaRul~PdX zTxsvD#cbg)X}JEHIHB&nWTyKWS2Xnj+jF4ch(!BKuCggH7Lz;@pJ(zwk$vPP|JN%o zJ6Y738A`bZ&Un!?lF5=!jQ0*W(sKRxU#&_pEgInOeU;JSXZXqk)1;g!)>|9vj~T3B zKuF0#`aG_r171q^19RRFw$A<|%q#qp`Kanr2F<wc>)11c7xpeR$=CzW(9_D>#p#{F zFXv|y+t6E9if&Z1u%z|VM8msKDe2fDB*7`*Q5GHi+P7o+tEM}Pv1bJY+34!1(E0Z4 zVXS{(<(W_3VHJDPG+p4vq~leOkEg6&^YPmv6mf`P5L!(DcfK<6b_%PWu+Q0(vBp8X z3KZjLU%p{R>0vW0X@U$%e#QHHpKI}&q~)Lf$dy_oOZIfSsvt3r33jV^Wa9U>F9LS$ zl9_W&f0)yUU5bb;?Pb&v)?;7u)$MguRrO|NdXiP5N}sRd!YsjZIW-j6=DHGVEmbnW zjc+*01I5dM5sFzt)F}1XD-xF<)eG5@HtL$+3?SzHa>mS!4YMNd-jX3fOHJ&W0#sf+ z2)ww!e|h}LP2>L|4Ns8&kcPN)knCG1<=sh}F}U|AMFR!<B?3^t39=ud@QDe3g=tP~ zXWpusgp)ArTkgTP-(QC6m0w1EQ;b7wK(8|`r*bb*g9MmN<Ox<xn34GHbXX8CefGn@ zuU<i=r~Y~6yMXQ53ofv+mOPA&G49J^6FlC1<7GL6P^{%mMTh%|2Xt+sY*S=+zOzQ4 zk0SNbiy4TfBVfx)-M;Pj#^{}rqN&zmQ7UT;!Xb>6%&-D;Bt2w1?r6KH&VI@=X0Y2= zoUi19<R)~lb0BHI$&Sr=>_JBmAKgdrPT<6eP&<Dk_LPUR3oQSXu$Q#vCzMnS{;A%m z1Fl)nkGZllu_?iHFCG@>@W74|R@9-_o#V*~us0k=#J~fS>lvwnO5gd<3r4LKWtujm z+`J*KfvvEbGU~;HCLoYI*Kr>&%@?b@<=*27HmzS{c5y7)OF(?6ECV1D2&i?|EvXU9 zC4)#l&L1qhlZ*Op2?~7jXqFOG1JHVxj9f*VAogFFa*pHn03U8(ww|7zWmqejHCu>N zvh;sHB|lBeu0*qa<4lo4&xZKP09ZsGL%0JCQ!U)>!O}0p74-RM?B)x`H27CBAyWm7 z&1}nU&aoE3DW&RP6-$5JcHm6A4yg%#_FtS#anJER!2+dmyvL$>?ooH{J8zUbzb0Ma ztA@~s_ow)~Q5g3#Mp!u<bfFtB<W9Sfpsoa(FGVzu`0e?QG(ST|d$ve9fv_T;kC(#z ze*AP{FQOCQkW*2ra(!qS{kYWOQEcQt<|;1+>l-s~2hd9fPl#&qxuY1}Uxp(>!i{T- zzDV_*ma`JbH^r2$Zi(^7ezrXF_r*kT{5*)bl1k)ug41~BfWM8raVViGS*p@*Lt*S8 zCrORQ*mgd9p{K(CZacp-?5xRVLecLu>-7e7C+Cg&@Bjl4ebL!5)6&BpvZ1LC)tbG0 z#v-#i!m}H2M<1V=iRXOWIdSXTUK+Y%arPv?sDCRa0U+~wQfX9YpDo^dFxgr`G~@jC z%9zsmeaphgam1OfqarR~G%@t~B}+#Au>a5{gvBv3Tue8ir8^2y&TcRflspW=Inc4$ zkLb{!ac=X*zQ98eCGKBnldtn`gabe0^A_m^5`jOEr@2Onwz%UfoAO8QXUO=wO&;71 zDLfz`U?1D|6`y56q7h0z%O**kJlK@Wp=B^F2|0_0_!ZV9>mNdtL1a@-AmhR-Oi-%R z3g&1Rh%}4i^G1HPJuO*g7&+J=(~_ALfsRx3`H>7oSWs<_Oc)ynYhq_GtZYQ@v3xEb z-FLDQP7GV8_CGg2^6URVG~1@QFleznXYP8CPVrY33O(Q7wA47~dA<ye{F4H26F&SR z)JC7$Z+ZoC9KcNDB$f)--4?;-&B7h5US8>+{;EMSPus3o=4JB4@pL-YNVjsxCe@0X zwk&ZRrbluT2>#F$(2B>izUBJYo`W0P{m{3{f5-av;%D({%BPFI=?1C3@Tjp+ij|e` zB;R%j|DK%3>sa3}+&D}g<oJPh56{*eE^`Lf?-c=L<CxX9-arcgun^6N@Ihkx0FhJJ z?Qs5+6a;(z9x61z(joc=y(M9Elw*qjT?vkszh|EScbA$bS&g{oCLD=mH{tYZ>o#ri zA1({;Yx|ts)rIIe%e=k)b#qbHVHES5(}?!0U$Koq9+6Y|i=jk1r_@A92Yg2pk=YBe zG;JRf5hdnln+Yi87q%TypUo37JEPG~x&2(c@fHa#Ss23!Y0%A1!Os)T#yJ3OIv>^z z9OCM<)rZr|QtT4zRI#F8lX9@{&g-)!qJOwSM_Z(+zYb?pRiivW-L;>8a3v}gWbGuY zWvjmXO=@0hNBe)h07FwO8w}`TU;vrK1x>kkxot<KmBW#d*HPBkv4O5;+7cFuNiaPI z7v6QVKBs;hMU@dDO;X5ZGv|khb9jSj)iwC%3p4$(Rt5F?i)#3V2<Pg=d}uhu1$yM0 z$;frDXCm%>ZSg&ZhHGpmLUh6X`flZgnCOku8-?w4b5bb!4!fwlL0-o^Y41vR+0n!! z(O*d5{b2*f)2+x@flZ+6HHzW*P#gjsZd&;v<*xMUs7LgzV7fSWA&$@)-{p`o1OF;4 z!GusSoQrh#x;VSl(Kw5GPn7VPfPUMJAq=~v;1J&=_!wYp{QnBY|FlvW9UU&#hHJN1 z+bNy}hW7y_v~qH#8#|O4daa~YD{a0zp<~mgpGG8d%lQl3S-7$7c}p`6Iyj!1eUsHK z_J03yif0PdZN;8a;F)J7U5s32ffv4~b^)b2KVy#eM}Fg6U+15(FHoWvYif|;?C_0+ zvHq>~MsJu<htQEx1eb<VEnisvDee3QF?gf?>Z`<TJEGCFZX2Y@qFzwAFh3KI)7~Ia ze$C6|ztX$*u9`@SwIk^$u+MhupUOuC;{bgPYL48XKmrpqW_U_IANe-!T_tLP?gi1= z9iY5W6HzBGEEX1u<Aw8GZ?T+>%3yJi09jDirHkLi<D}D7U#!#c;ZRL>Ha0j6Ak~Bc z{EKgVH*|47U2J@Hj<*~Z>q5-@r`E;rRoIJH_ewP5dk~`h4hYfQcZ&&!xBlD#4?~}H z8Z54>4~z#@K?FZ>+*?~(symiTcJP)|YsEba|M#5O?^j+PgRH<U1wPFbHch`JDh!J& zNn~okrKPWDKmz2I;=YKE>0Te18fQ%|v6||Cmu#<=TMwm3beJ#b@Cv}!(mJkHQF}^` z%j12ULFf>wMxdeC?<nR?{Vj_}d)>R_dW#Tr)ami`#R{r1nVrh}s-UNzzI;LNu`|@x zbAQWI40h9n%Kc8XWNT4Z{VX%{+waYxPYr#|WT)c^yaygwbdo#fJ9L8*$^3>a1?S`4 zfTo{EfNufrp~tf;Ki)4&E*BoD9N!xGE?YNkv|RMLpExVnzhq&3HBBP_+{Aa@uQ_q+ zm&`tY=C9+~sC{HN#dbU&R@Op-hrsns1)PstbFOE>p4oBu?8eObdG*r41V2$}=VO7N zoPF&`&1JO|%rj@S8}Yy~?%2e=-9{-ArZ_X9CFN@g88T0+_<VUbVlXSPTur~HT2j{g zI@HzQr0pP>akEsB5*ZCb4M7EmW30PZsWqWK*&OAUUQspm#Jq4PNPft}#l)jLwmM1Y zsyjdcYuWw(Ut%D40|98|&-?E)8I{m=5HcB^M(U67>x_o|hH9-mz8!)_0&HZod;sXP zxt5Z`vRA4wlGMcFOlbYs@jnMzC<5_D5hqRQFX|L3d<Zy_Wc7aOh?KE|mi9(~;Q8!k z#~gm>G88F33i>*mxP4?q`i7zv4YeMffq|x{h0Q{fX0iT-J@s{7z3|n!Z#LWIoj;Qy zckcyPFPZD-)w@iNZ|6fBNSl>WzN1>UTfwwZFaa>Yo9B9kWG4gFF_`yAewtQ0bYaE^ zZ70wks&(X;w?wnAIje5aa@;m~3OyJlC0((~&r~V2q%?lbeR^9aQn+U(>s$~e)pd~= zc=jvcJTI*Tt_Tne5bcPCyh`X{Kk;T0{pCluou$EnyuRM6^HKvDx1i_U9%`z?(%VQP zlmt$e^PjqTtP{v5I)2N-)Fex=kZD`n%VAAU6hje8F|gbj<R}|@K|`U<g{9(eMuv!0 z1;RU*@(h#nfb8nHZDf|%n_i6jGf6cm;!;;H8qbpe|3P)6|1YN{c#+#?wpdOw*5{w| zB#BIv85Y-;7!Ed-m8Qn76(orAX~~jD#wgA>Fd_igT+c!8YhQb=FYo&>&R5H>bh1Rb z#50&%;VO;^8Iz5ThA(jF#|6Sq1=qJtG~Vu(-Zs&D74)ZV%qF0q9(X!l>p~l3AZ@-1 zIqc2W43RF!ceZLsR@6JARh>M>x*U_k1G2bv{$CZq0Kpk_@grn@*TGl#Rvdb8Ljo&b zU;c0Y?oh26-q-k7<8b^gl*8|?6oCf5%X>{5G^3thn~EfZo4_AEM|RDr;uDG3o6BZ) zqEo+**o)jgfHJ2jXD)vjEhC2bOfQ~!)>$6T7%a#7#0)(!zGVxm=L)Kq*y5*4`X4R6 zrxgU8BcYtMv74iPe6+2NwU5s+mnL46VC>*iB8K_j=t3{<42`P3Ny-6OuHC7_ZQJT? zgN7;*gSAYAQMa;h?O|`iX)n)@&h#<$)*=-pU}*<O`}^JSdkm_5Y<fhEU!*}aiU``< zDW6j){*jkE(qV771$1&12BY-OZ~L>~;obM({}Se>ljh<9nW^CRG{8gAfS{(SD*5$o zf->49B-5Al05oMoi^*$@r<2#V2oYD*YKMRpU>06j7h?5ADjFn(#iIKcZjj%XyTp7( z7~32p@3ozQ;{;DhWmMbEHTqr!n^7n^)!N)7un7_m8lRu)WZenaJ>F5rOn>abvEzEX zDQZ=R(U+6M<x9>NxM%jA&;17!&kR)GYwIBkpmXFnclUKP)0{Fdpg|dwKz{Q)tY_G9 zP_3rt8Q?014x_v3N;0rLxnC8$-NYQ__N|zpBd?KW_eLwl)lZ=kYmp$?%p07`cWwL= zQBr0-!4^=BrFq3}^umfQ(hC7WBPOpOA`Q9M&%$eq*E7?yqkpGyUJg4bB|8A>YxEbD zB<=rDvz-upY{Rpf!csyngC^xx<la`)S5lmG99jGO!1BPx2!mFPi~orvGM(h=>OXCp zPRnPx;n#^gX96Z0M@Xz%yfkL`r#E0GeiOK(9LQ~HM>c`73;uMaF|HIpfpD~}8AZxo z-B#-)Z;Wy6q^Hf?P6o1K{PUIMmKTQ}n)izooM*bpP_*_4KfcKRrukxMVH1sB+8}lC zR1bMh3+jGVdB1XC<GfL12*?yN_0UI_<KW;POn;C|+jh-j_}PAaXWWFM_`EzO#}TmC z-MC&(6Bt<{bVc1;HXZIWQ)qP-tEG7JOB-P|sc@`{q~41^L6xs3&mF!6j!NjiIKkc| zjFb(s9TUb~X?6I{+{=tRr^pw(f+##|`j&U?9M89jY<ve)nYKsYsfGeLy)WQtrBxp) ze{Snl-0ylft*?g{)ig&zrTCWfo@jcHs89&KvSST}kBaWLE3aDY`XIqo%TsHLWfuhC zgbg9eyGPS6JLelGi*@o%S4+hkM1cX{6tfJz)jc1NBNvWk(1K&GX7CBX@50bNE&ILg zv#zvX@*2?Q-?hCODSgPYeMeU~xFLMBQE(Juc3t@A-cXGTtK+U%tamQ<bClY+CK`uL zO?$A~Un+wDf4Te4`-F(7bO@Q>|8?<7ifd{v0IqPp0_Ye*HE|V5cgkM&CCSN-Z{uh| z7JiZjdRLA<?>u)|!ZaA{j^ADAEDo7x&VsJm#SRS`!&@_a5|UDK%>5Tn_vjT{IhG$U z%LN{46ZgyO*|+D$OZHmwvsEK+#NU&Z+2-(2v|RsgNHF^0txzVwZ_m6(fqTa5WKM2D zG6<RdMX}Q2*ot9>y;^V;HyI1$Mng0QYg79g={pmt1Nw+}y4j*sdm{mZHAG$*D_AcV z%qrQmp;2Y?uSl<EpL;1)3lT3HYJaSY1<EHc9c3dfpE;iTwBkd!dsuHXek_6v(*h4V z>-nZ)p3_R088&piJ0GEH3Q*!@6}_kqIA}kbUz~|ol@!<_*7O7z9yKQ>Z79e{-%`-Z z5$|LO3q)==IQ-a&am`vOHKGndWB{xM)H~-KFh<=Q9b%K)+>EN=;7yn))~cdp#T?Dy zzFlofU6nc<l()t8e9yvAUUp5Bh4WwI^dNAfv9|GS>iAx(;MIU3Ianrryg>qomQ~HU z$_w3`^TclI;CQysWkm8Hwotux)zbigsk|u^Qvs3QmNC7jRP0|Q-}T311byU*MFwd; z=sWfE!#0BJd1E^5fEavCFTHqA3)3M`<I~cn$C+YK7IetBNAtAIr=1W-D$?#)8g=i> zl8C$K!%2i}d9}5EX#a89$F>xp%O4D8jRLK29=<tCKH?DXRp|qK%u=22*MV}UIN47q zRy*&h_PPXDyfN61mXd9%V*OEsbWrgjnyFKri@)-V6gr<f+O;4p56wCwtf&3UOS1;X zSad!1&xWuU#-^N8vn1%H23nT*4qkQGlaN524qxM+4UL|evl4$yf45;H?6+?drDeL% zs-crdW#!4(Zis#cqB4aZmpGoE|I!^obO2doF1D%K&YqEn{EL_eI69N5ANQzKHoDw- z5nH3!{(?Zvi^$!<wib!a;`~cReg5o(r|bVldIWVEEeIL7?&<jM;S(VOGl2`h-aPz0 z%z11&&?>Dl_+f$1j5f_c%t&ic74=2YTgf%94?$L@3EIH&Z%sMUU*))8y-MfDe;io! zbCwoFzZh&^ljE#vd(btwfhv)gq<_gPW4~WRBS#;_|MTkm`ofJpY`~N1Pf5kM7gv}h zn7DI@WpGX-0vh>eDVN75BB9&Y%U*ZuytHAIu~%xm;qM81!wC@r$vvJ(U>}b>4RX}9 z5g9H1()j`2V5b-}C8>C%64h;Qj1ue2O-x^`7cvI5vHJL%B)LoPs}}O7@jwUp<sO8} z-XDO_{69S}wd^-`cwqh^isbufD`Uwi3N6A`7kjFPFZh3*pK&-h7UZ%O>Otiue<faF zOS7_!_@rJpBM0u0>ZA2XOGK4R%`!yb7=QmnJOdk3hiT5)@P1=VWRB-C_J7`1mi;@u zJ5viDcOa%yL`BSu_Fr~3wgY{MwBnF|t@w^Yr>Cealb@Ta3KseqDXGB;?g4j#0Mea@ zqnoLRH#r%u`6yB8El60^&*H5Ccdy6F{r2gg=VJT_Ua9cQL>20o;cg>X`KWnH9=&km z0#B{^g;BH<O`<q@xPy#@tYtSB-xvVrvOn3ax%!dvCM<GVF1me`)NPEu$17SBdDA@f zkRyz|FC$)`;_{wXQ=a0xHHAd0Kq0BjeYUxSZY_5I{B&$bhk1e0ERGao%NOf2F=o5u z_jF;G(pFlZ-S0o4BqPy4U5N-k>_6R4Sy=f&;?jEppe?`f#JmynCjbKbR+mR2(VsSl z3nfo_gbJl5)AQs7KiK?l+b&%JbbW-rwlWn-0Y}M3exH><MgH5S(4*zb`Q>HQ62{R& zOSs9EeTfeVZvrkB*>aoI^0wE8epMxuBGBzZsItOVxoQB&INyJI%@{`faDP1Guo3{O zIGSnyx$L>Mlv!hAA20ON`D^EoB?7XkyD&PoaZoa|ysDN~1mdExn@<zo6aO7Mp>yOu zl|z>;OGnaQ?5qt6qr7+|+$?CQ;HU&L65AT4!GMCjnN<#B<Vbvul`u9(Z@nGkXMjV% zx#p@I{?2PUhWJM1_J$5J9tS@S&qKS9sbjw-`|NL-K<=8MA;-EFIvlEnQ5A#8Ky!6o ztvqYngMON4D|MI2H0<a;*QYj|nqMt=o=+~3_tNeY<Ohv|pz1z$It!$m_m-IhQEJSH zmDK(x9)`xgN!J}EGmfi7i5h0c{;g+~XhECa&oc11E9VOER{>KW-&t;rzR&~P%d+Qr z6s>E7(TGEF_pl#Plgx*&o(me6TSurjCuc?J9r2G?G$bFIWcc1`TwzCxbG>(=oH?Nt z4Jz}F0>JNzId^BC*eNN&gXueEz74Bg^}MWV{6N>+w^JL1xd(*t0o?(Ad!rjq|Nc8e z6hSH9aO$90|C;!FF5_mpnJ-dxxasGBX4$L{k-haMgiR`co{7DzmXxy|RqzjfEx^p( zrvp-*fyiKoUxXjgVlDIK_*ec$^Em1zmSx4Wrts`DFTa<a8k!?MO)+ig2=Fhaa;$l% zF7sv%(mz=!g0dT)#s<p~j6h22se)9UM<5La^_9XOCsZ|=L&C;YXSFefz<{%n*m`zW zWTU0&GMJd2Zf<~z%>KO`C6W8}Y6gv6gRK`NzWk+0%+6udHUSklM7*yq)c=!qt&#IH zP7y$aRea-=;2)#is=Ji4t+Xtu=#37j|9OM+s>{6|dt`yq(?m#30txGokOpNQM-7(D zfbSWgzK4{wu@=<wn7rw<FkE@x!(N~5_yJ*0<Zll~Nn5#~Ec4*AvExMVqMg~HV;Of3 zZ!W80?VKuAcQ|~$(aJvkcLa#iABkAI8VTtYhJ=Bv9Kidc25O&E9B}adCQf};W5H)> zwC7uc!(xj|<}fe*9-<eJSXG3l-iDK&g^GNrjEYd+UJK+G(wT^QT&*AK^P61FXUMJd zlub^zEybxtp;302c8JQf8feg^@Z4!4OGyG;N|xtJjD7E?ck53VGXFla;5}<F89gKA z)>7o?)##d=;_wq})bmx%Foh-AfpO`~?zI3xH%}(&Z4epK)+iU^&r5L4BjopWRWh17 zKWvZH;{C~yX+NoIF4XibPTJdx2pk~RdCK}AqwTrj(}l$?*LQ{6k7m#5Abc-GX)93l zH2Ck-`w#ZD<sphclz>ALKmTM$^K&(q?e%wU<-B;lw?EbnH@ld@csk6msZHW}76;_{ z#|b=q!=0TRuL1_|uI?L0zUiq_t{;YvBXZkxy*K)-$Y?)}AW%K%-xyt1d{@}%RW4eT z+f73^@V;2euG{#~sMcDLl`vgk*@1a#x^drqWvOuT`Izo$(fq5pHa;+7XuX5kv@@Bh zP^YMAPD7$%eR3|I?PM+lb7s1vgayDmwu6LgzlYX{6iK!4cdAf<w?&cePtk1gNdVn4 zFt*HKQTk^xdqVRTyN}t-?}xJMwYeiq;<uI7eI(~XBKJY-ps*xlz<b}o14OXQ!?$nc zJxZBFt|&@T-gHGC2NEFOoIy?jFL!(7h*LA)QU9E-$AwQ{^0L?aQp7M93)2Fr+;CB! zZO{CCsK5rBt<%yCpS7)T;tjWNr%DeqrzQ0uU12ig0K0S^q8+O11&^`x`b_|i>X2!@ zJ(0tQUtSka{GCCU6DZkroMn6~g~nr<%`B0`Bi%yQ*Ysue-x)hf!(3!vy#;v;W<4g$ zo9>cR*}<B1;)HwwBRkWer8oY~Me>l=4c)B39tNGWM~BuuAmdk;f+v*z$1vitO%Ix$ zO_;~VX-sQQ-~LrSHWm=9l;=<wF|tPCaU-)H0%8a-X~#x-UtOg|gRmlTR4CJg<vy$X zUHsWFzj?$%SUIrP!A3Ppc3F;y0kbEJ&dz0ol(cBh>3bkJ`!nC_oTwDDC1JHebD`83 zP>@U!9-i#t@UriRF?{br&k$yylU`0K3YLrRMK^7^h+dKCLBn9nUWm8O3D5~V|DDFG z5smGliBb}At>Bw(B#!*v#lXRsV6|)^XD*t<GwPLvryCfcCjatx*%N!ynV6A=w1euw z1(&7M2A^Tdt)8YDqL`Gb7aOF`VXOSmL;5#?UkD*d6jEB&N)z$M5sP8bIcC58XkS-5 zWNX||dL9JdQ#x=vQ%W@L`?l0Tt7tYY+sSq-`6yq=+J}n<jtQmJJzcF|Xgi0Ksv1s~ z1V?FK4mJB4EK<z=C|hd8)nqUYEf3WF?pMQxL3ka+QHHZy6)(4*a#-TnKL&##py>fQ z45ro|0^}B8xR?;;pYH}_Jmnjp^~QQjIbEbe(mjgJDR~&Z#fe#~!du1BW}E7b90TsB zd)K~}eB`hHMhG4(c^8z2A_1(#bzV#oaw^59-0ONx?T3}NSf^F)$=k=&M%eqIWtVrU zDjoi+$N!;h{o1#205crQp%4b--p1l3=<$1QUealG9?Q*7Gv^prBHfOOvhVv$EoRyu z*V>;*k%q1PHPiLq;YEI;Ag`QE{1Xw^Z?7d~0N%A|K#DS3jl$NS`?*FwlX}qA8C)+v z7@f-WAl#U?w0m(1mcr$UFgsNT$PmHUe&DCte^0zLIpc>Fv=pgr#7hRd#8bh47Zm9* zg{h_C9GaKUw3nH>Mnc{4iZgH;f;d|4!sY1RimX)KdNXNM$o#@a!>%tI`e7871Xp|C zZVjn|h<wpdD}LgvlBQLwHVetsKVBKmL#9oUTo<SZ=q>m-ttIC0Vr%TvTwkKdEpH&C zY)7PI|M^bgKgW2tx-%z2VSW4}5soXZN=k=F;wTjGXibLVV8))`--c0rdI~fHy1V<E z50@nYrn{CxbG=lr^E!Wu`I7jO3t{{@#r+Nfjd>?c^)E#8s1ReJi1#jR|Ng++`#S1z z>|eaXNPy;DDZ(~9fZCu-PiIcXE&w=~o@F6qKh~U{A=s)kE9m~9CaF>LNk7!+{%d{9 z<+m#@GZ>vzxGC$<Op9(#ap32BLGU2pC4jhY4J8D;bx>vW=57=+F|&*-)fbuqymvMZ zv#|$|{Ze2w)6a-O%5So{;yVE;H@DF&D9AVkcqf!)I$qaQ|0Ke%s#MeVB`%XG3(@GL z54%Ry4dKf+Y_{9NfrHoThY;g^Paj3UK6wp%gVlWU4P{NqlHFjow=?LS)t)M$KAL%G zv{rGobXh`sq5#WbRpDp+a@Do<@9#K(X_yY}%vfnEnIF>00omeS8z4U;ldHPCv#skl ziiS=iuG(;h8)n+6Rb7aX)e(Z_T;lOlBQIKg&gOESI6$a<2hJsQCg@}lSy&qb<}>m< z(!61_si0^KqXwWhttze(0R&BTxbVL-&EUUXiIA7CJDYKobE7EfoLZzZW_J=lzzRa4 zF~Fi*g<P2lxkX>}F$dvX(v>=iw54`rl|!MIW5Q*OKyHi~ZS_JLYKMWpnJ~7b#4jIH zQ09ts#E@pUok}VZ*HZ(05z?QuHvWyaf>{8I==tv>fE3auft-o(_*O}-0zj!l1l3Yg zCo8=~Q}Y=i=uT9Zid^r2v}!O70%ehn4WPV)vKk|q=?Y6myE;ysAhXysNl;Y8Y#Y?5 z<9f>W(h-0Fi>wD3PS@HwogI+H{d*k>-<Wa4p^Fp9c+R4uD38%kna!0oA$d@q{&0|a z1Ko5#L(Zpv=i2>+;%yiZ#j)~A%JQUqK5~HnNG<gQCpWw6#o<B10^UNQeCpea-tTHt z)&X>B_Tz|U>WtMAtW5X+#vx07nCjz+;m#jIwc}%8enZG8=&vA?%vFqsG$<Irn1e|R zIC}5np%48h3VphcD5?Ws60K`v=|7Tc>f1kP+^R!6$c%5#VvRhM5nN<KRQnPVvypD} z#-76Aq5xY0(5ET3;(*IP@cD9#Q$j`kwHBm&S~XNI3h)-)D=ewT?y=HJNO8f$UGpJB z*4Gywew}=Dj1CVWm?QbP_+HHy@IXF)RAdzdq@%TYEaq~0lCr-`FR5h1KfRk?SZ~9l zLu7oYo2K7(jm?|8#e(|}N(JB`@sJV$Snq}@adNqJY+oJ&>LxW3Zsjj1k%eks|1j$P zm8Fec$lQ`bN|Y^GJ0k96s%DOB3>(hFtyGlh)qKqrG!tDh{P(9=(giQ17%mS=_qxdf zH48G>2tkMcl59Ed*$FF2ON4!}$Or~HBIJ%BU<TtV;ZPad&zEh1O{QEy;vASrC1T@M zumH!@?7)ZAfAUvFnn#Y6p&F2##8ut?YUhDJI{=jExM=>xjqa_r6mPVQ_J`rAB~>yf zG(vD(5jC}ewk?P#{JK%&RT>h_-JO=JTz{tH56Q4`csZn~Y}8`&v>?)W=2WhI^{OUN z89{QZPWX>kFbYy2G7?lM&S$!%kbvd9i8fZmIE^|CM*ZPF3vp!sGIv#}ud@ln8ExC+ zdb~{&Uf)$UG)Rs$2%&W$0ql*54AIp&ms$_zTG^j;g?rk^g=%yNXhYpI8%gQHw5Dcz zRf&A3gXry!JCAN0)TNhw4S;%BaT_0V%gJ-rSvWZd{-l1+IGt=*RZH(SC?KG_R*A{^ z7m6eaz@znjj6C|~`I@kr#pI(hdLZ<{@`dvT5{$j*1qOvEbq($tH0_P@J4>g4V?Ve% zTTZS#Xr%4~3SD90QDlxl9TCmR)7<An!SSEt<L_8Jt|gRMto2mGDRBhL^Vx3aH#mJg z(oo;u@1!+HAZW&HTV<F2*DgGlFd*W$IBonL!t;L?V8X=iGD<V#Xr@ej*VOu`^gTA> z@A))U@<u63C{eLnf&|4`V}1at?xjC15=7s;MX+T@@q)1p%B9ydUdVyozbEJa&f7~X z_o=VIX8Q@bJD)(azS1bEfcrHDh?R;u=DK9Jk+VZfCMsQ+Q#@aUhWY_-5CvabOhdxk zeFHN0i4+74W4k6L;Cd}t{3UIpmq_JH$xH1J0Wub6Qx2jp|JGF$FzFSV*UB$-V3asP zbtoy>Madj;`~`}QhP&oEptZgdbEU;IQ~BXfkI%pbWFV$FNkDzIoSr#-^|i&JPI7lh zbQSgENQ{yyR)tq$@e324xDTjY7CnjLs?b`s#+k<c#EYQbUD<Wp$1G!Loa#l;m7!oD zfb5{bI8W=l(Yrc@iq*)D5-qoD9U75(ttPMv2Yx{Wjo2?#Gn~p1QEP`d12Jin2h{h~ z4Kf$(Sw@-KRe@o^zm9fRPhkSGmTh4O`K{!3=XrvCft*<Dag^!@E^lF=IL2PcwTyQb z^vd3+=bq}C8t0*%jwQAPu~UW?NnT1qquGrJ+$1_s<E7z^!`Y8KJ{>PiQ#FHx9R*HG zH0v@c3^+mHwbjB@<rG>{V&<(6bzE})_F`C2h}bp}KH@m^$&J5~TDvJ+3F5TDvmXu8 zD1qV^NW}ORmDB&=Mn@fWbhj%cQ<?Q;7B>(vijyA}i#_T(_7y?n?k~QzXv4^}Nn?$S zj{#iv&5F9{u%$eyJm66uRmVI5O*YUnY>2s|$wN6@N4K8F9XAV`3)4#Kf|3T@|I6En zn~zoXz$tRKkCgu?28L8zm!UO^+bkM~{lM9&&3}TySU23fHmke9o1g%J_wjjd=<&*7 zq$A#%r(gC}ZexJkmC4)@#c7Z6;oIcak|Qr7r^CTqK;av`vW|8e;qmE%?3!@P(#N;1 zJz>BU;$P8-W?oIA_j>;o1Q~eoWgFP-_D8U)ysk*^>`R(T|DvEPW7_XIV|79br2obg zFy#g7I@0c_!t&>@59`H<kA2Z&cb^e$_JxNylNJA9eN3cCd$AUM_gMaVTHf*Uq0dC^ zoOctAp>Q*~kXvP{d)$Ir?5v#1%2pVqlaWZ;aNtdNb*GutBLzX72XlLee~u>0w?Z>Q zvgyg+#GRNytXfs&HJDb!)f5F`NnAG674i54p49<PO9%6li+k?P<2r&cV<MEQj)ERI z>h2+8_@GsjF%sC7UOu+e29>xNF}xNXooGay^Ig4>9DI>JHO-`rY^RO*&@lX!^SXwH ztJ%RUjBk{EB1N4DC+HLW+tTuek(kHGskK)u0l2^ANRf1}h0>>tVF^KA_8V4F*h*au zaNL+AL7t0E&H~<WKQev?gQCf#fIo*+*arwy`p=7Ek$x0^b>Mn)6~=AgKY`+jHqjnN z@ujeLBQTRu({rVGzd-{jnbKg>*fUoh(!OQwe^Ys&289g0GJa|h_Hen=JkB_KS<)#X zw?~m4mk8f66uDgtY|E9oQmRlI4kcujeD{a~AhzXeH`U9Kwc+ii<M@6D;+*Gqn72nS z?;B+R56;F1ZfK?1JUw;5x30mjSKhP@@n-m16wn35f~#^w)rrbqd1J;8psc`i(x83` zBn~DBAT*Rf_ehyllwId>2_F_RaJulRoS!S<;Liq#VUPO#4W<>h(uX{c#H{qb?)Uq; z=;jdh&(@MlM;hK{ndjdd!bs&m$~{;(V+{ESx*qQ?EbcG&(h6~0&{682vC!znOJc+k zLi&G_O>PgJe`W~3jUN0gl^+p=1k2{3nJiL_$|>liB*U4FS0p0U-}-PeN?M+~usjpL zpye=~+VS}E7_#WNEE~=a9^|STTM2aFFSE_mWYGU2Su%{*Cuy;a+!gp<-JIt1kyc26 z$t4-F><S@$sUkc*E#6W9vYy|zZo5B8QM$ez;m*%3VqFt(RD!6HW~QjYhW@SPUt?@c zKiosKSL5$JpdDo#<_wv52!ucxikh7Js|w3<r3E>&aoTp%FiH?ml5a%n5dOD=_O120 zrLoQUYY*P;Z0eD=M#R%mZr$5WpRgTd{KMW<d9!v^rO;c-V)j5FTg$NwCJBzHFRmc$ zWLnlK^dI>`+L-^9J3ioPJ0Vz4&f1YuzvYV#uW7-W_4M9h*RU_wmrm&VW+yi~KFoD} z2M0Mz#UNuZMX}Z*^4-G(BGfRTiz0>`5-#Fe<!25xRWrQtNXi^@DdfXSN0_WFejhs% zGV7nODS<ehCy&);BjpAKSaiVFh!3g}s-T<qy0#l8<j*O(Yf!$emB6O?na<r=ofW3U zfgFF-?>N*a&Il>I|CVxSlr2j{#{&UFoD3^7K4knLRn8EQN*8;5wiNX2(=rpQu3p22 z$TI#KQ3kD!$kpZ7wuG3V*dmpmQQ}f>z0WQFWD0A)ibJgSNyn9o2f2;pn2BP%SpDz8 z%hCnFNbc78MVcl!;(z2_Y<gVbLNLUnK+Lix`+-uum3scz14Vj~#MfA|)d*2MTOJ=M z5aVmJ@^nM|M2JvepAf956bu?!pm^sNX^n(N=wuhs*$wf&j-P!dP}Qv>CUwr-!3YvI zo;N41*lj1|Zcqx<mjqcko^-|Rc=&R>$M1{_SQ%0;#F1QVK^Q*G;ucp0{SNqB&6rp` z0hwJa2-{{C`Nk8@Mkr0%vmFooxHU8XErVM|iw#^&A`KAKa<2t7|Lt%>(8|YyFM(Kt z1AM;ad)EsyUc|&giW+)G@4ITvFy>49ZHl<yh#Q)3mW*TOkG`a8?r!+sk1rR!)~MkU z&Uze-wQ&le@r_KE^y66Oq7v+vN|fVnD2}kv0Fa6!V<BlSHn@~$pKlG+w3OjRhm|cn z7NRiFZR$A3RslqxJGIbMt!SgJ#D{9;5Em<rokaW7;FiA8{v}$)KC{2yzdanvx`@PN z5eI=_)8YfFT?{L6U9z5bkkkL3<sqSk92enfba==Gd*#%A@h-?SEWhC&s3{Q+V@IZv zLwM^_cxAA^-k^5jXZun;UoOSZFM6OM_cC9{4rTGcX;oJb${T(Pk$%XVMZlJ%0;%^4 z<g|AC;+jgeEh2~cQKyEcRXRIe{y#*a`JYFB%%%L^O8@feKV`+@4LX;yAj}_##M*S= zZ)rOJ<!l?66H!#pw@S6cQ0S%>rs@g7srEiVetM#S?OM{5V+i>smwX}0!~&|I2Lr(g zrq&)6EA9ZzdL=F2$m>tc2<X{AS&zA~Zjg@pvdAe`aN=*eq!|um2^E=oxh@u#mc->q zjwX($y4u=Nxz^P}7{9)*q}K&iIr6w_VH(>&+`)+}L9aFa{=^lL07XBgq1_*BO(d0= zZ~SkXmzq|$ap(Uo+pjB-LTk4_|C#)|9538B?R}HfD06X58<u2lT)@;&$_6_@Lqbbh z*BHP0F5pbRJ(kHfS)>f@7m?{e{AWb$Cw;^-=`P%G<gXpg)(=+kTYZD2sibX>Rgs&M zaT*~KB45fN2tdoSU%LIPk`23XG)^Qv(0gBR%^wLQbuYzw)|He62zpQu2fFM)j3NY| z#-1|sR%?`e-+fF?MLI*qv78zz$$39xe8n%?QB#lSW{gF)k;fUgVq~~bg3v?%syGFG zSVMX6#zk83+QZFUXMRFAK?sQ>C$p4^3#dgQ9Eiir+>5Tp&^-r}k85{py8IyH>^Ku< z>$*VDdOn!0>h$`l*2cdwznouGd{aB+4F1ov>*OR0r32odeh9tOh$)m!h)TZr8aJ%3 zDGfvuSPLWb9LeI59UksK%l|JK;(mof#!2_ino`T(h6U|a6jpCZR7?v;G&bl}l3cV3 z4mzK`?KqjSPJywnPjU0zB&+@eMs+VmH&&l0!Y)O0J0#7lWfwqIc_gwNfhS0kUEv^J zSe^Fi_t0*R__}}H{-CMrYmX_uGi)O6{wLokldXsh0pPVhZYrS;%DXj%D?U$C*^xXh z(+BMt%6B(4!hXbZE{cec(>7G!N7Se)U%G%E?ely1X+-C~9`|0xKayNs@!71xb!1-q zV>2ZrB@T|Lft31(q;lZ3fB`s3U4y42abH0$o4)`me1qtfV&|i`>!<!pvRDkF6B0kp z2O4vPQS~2~ATxYMvzp_Z9O$DTOw-}WHL9mW$0t|44E2r{r=>qes1Fjk*~7uCKpQJD z&5~_~={Fbk`9Gl)#&?M;d+3dh;)oGT52Ok?2PE0C+RlHx01-IZ{sgPb2)PDGog`Q` zaRFb!EoRlSTS)u0WD+~{u@%`*(;~U#_P%l9px}X4Bo*9vrVL<NyPf^>=-Ac-d-?eG zjj91tfygu65Cr*s?NhG(yX-`v*cP3)2`I8ECKNW5JuNG(h%Vd2T&Prlti(<P5F8Pf zdvZ&_Jc!)>tAniA-x{~f27h2rZiInv5q*M{CHmz%ZxKmNyXBc&Q+3(vr)~um0G%Wd zsl|QH!3U?>`T;rI>Wp|7uPH(&+>oH_au39Nu``m2wei}bm65Ek9VHk{P^OnmhY|E& z2pSjXYP@=Q^AKX2mL1b^SIZ;CI8ejD1S)Q&=LaFYN%`1n!E&PwZ6s0H4R&I=|A(e; z46Li`x;?RN+iGmvHk+i4%{EqJog__TG-=ehv7I!wZL6{F&hviv|2}80z1GB-V`9;* zG|F^5&Xk2shyKL_QoiO58m_CQ_jjh}e`sSpt(||FLZlR<4<rmQ)hS0&2@l;+yzn!` z_L%}>^S35TzZ$kM)vJs<Mwd}KM}>qYV4}vtXbTc?udl>4CgfbV_p;VFh&y(m;=H|P z7#tJq{4Q2obBEK2Gzy$_ew9BZ!-)Waq0q^gA7X_AfkU^nl!*Ta;eUG6x47<$sm&dJ zS{+Gjw3!gAgH=iQbNNB7Lk3w4pAiyc<;4;uJRI0tw-*>h0aKAW2T>3K2~4y9))K=} z9GNI7aF1*vmI|MEFgczBY%%4veTmNq&iS|GNt*vz)ScjD0DB(IbQIzL@gC#yeX%&l z{)pzF0ok~~GlQNV7^O}arG2fmL0T#w+fe7Vttjee^3G~Kd`A`SRIaDgR6&y%tRnjG z#O_$Azd8|>>P7nNhM?fs!XQ3<<#Xoo$Y$CpieDKCdw_m0FC=JGmS_`A>kLW?V=36U z&aRnZK|@NgEHnXZY<eD0)8F5ltw}cZn)>}E)!P^kKvM*x4y)??$#P@AAqIUeO)l4= zXsNmH%2{T)eg2es+jvn`3Ib`O%n%HZlZYq}7$6t(-Pa8Y$exu(m8DJ=JIXwBN5>p> za&k#)%0OfM;=?P|tM()NZ^zi%<1u~C>_QiwWvFuTfjv{<=RLlRvYGx6uqKqoWurkk zb~7vZJpR)`we;YBCP;%>UGXCm4aA3!#5{fv<|XuGR?Ak?0dzl!su482oM%dQVJo0l znVMH?UIKM|{bT)459jU8&gID>cvbVA#*}>}2Av5%cwLFg6<-R~d^s<+={CZCjUy@V zETJ#nsy=!wsA+auZ{jy#L=~HwPw8Z8$F*Ns$_>&SYnV6c%kTo^%ESc5)W^lip4t8q z8gdh&Rl^-hh@g-q1x}0N*7@5dnq_kNTi&<NIob{`sq~O7cg-JFIV*v|a4`$%RADZK zEK{>oZ9qQEqqxFG3vUT7fxcYs?kAToDv?Qg1v5`-tF3Wtep&c7Fp#kaZ<7wqN&*D! zoqwBKJ@nJxPhDDHAGOwM9Ngr#C#S#2*K$^jM{OIl5xR{3KWPe$QOX3XO(}bf_4m3I zw_d8MiF_fR$+|CkQjzg_wheLiP%m59axar(Knzv$-K85poLc4~w?F%HP2<R~tG1K$ zLkq|Y7{MY}IB46aV&7Nd-A=qByWUd@o-LlE2gBK+Vn0g$^HG?-yK#cwUzez^uA#`b zs30lXgWy(p3Qd^W1t2+!p@63JGgv5DR$+ih?hk*tWU-8oPJVZ>(TedW?0bkHXn5{W z1v9ifLS?f$#;$k!`r%ftl4^_O_3)^#>FpL-K)}agO#SB_Jk%t(@pTVmy+)eLJ~kjZ ze*P(y6mat@d8S&$M1+FRGJY*_OOVF%h^!hoYJI(tSnL67MkU3?js3a<C{l>1nT*Ml z*#F-eagxC?h-q-EfRqM54#b{!ZNYH%)|rCe2G&{z4vn?%UUTYl(uP(zQjPY$%S%8K z4#KF?P#5FuFdF2wOHCY=)GaAUJD3(}SCxyFOpziPENkS3)n`xtbin!7I%cD4C?<uG zg5HTp9STZAXi6B_;YhWl9U2kxd3jy%3Fvrw5=ydE`pj`Hbp55nWV1<S@Z{X<ylrmD z&QC{9hrA#(F$TRNwz-*a{yD57r1`NH?T}2g-Ql?j{O3E{55Y7x42eN47ISsilJ(l0 zRlz`EVM(JvTFY0xw;!L49Zt_Qg#~cS54k-5UT+Ot7k8e8ZHRjPYsx3V5X&kKl^gR& zk&N4xl_R*mND|bPrTC4ZG{z!HS7io;-sfeq7EgRN#wsWEovU;-^MN<Wmed>>T19#O z#TM7F`7xQq1Tct%)drab8Ha;3gJ{G+57m7IsQ?%F8%fwh#wT|ykh4f3B)*U@^7>M1 zxbauu@xOi@^v<ku&D$r3{6g0_?%XwyTl<&}q+>QX#f&lRKjv3_O=V?Uv~+cSh<ayp zOJQ&P9fkgPQc5{Vn2X!hHmsmhrs~~0wt?gCqi!aO8aCG8UR((UUr4@>h%N}cb4-V8 zcWj0pvn1;S--V%UxLVbO%Rcb4>KIwV3Q}0wrdH5*{#cz3c=kmbu!8K_pYsdD2<on@ zRq1CPT8u<w@7ENjEL0W>%Qw$(vR}?=r-;fFm6A^WBMr}>`g)jVY;*OwRb=9hg_DWg z0t19@zsMQb)$;{^{Ztc1B(ndLtPKM`ggIEq2+K%=9iNb}5Cu@#>1GkxODUFrhntw* z5caEX@OE$aPhamZ<d!Bw5Hde)dP35wOX1S<*e?|g=_3KSlHuP=?|F|4y4vM7-tFi! z^lE}PQFhLO;H6htY3an;94!(ab3#-U@zvZTF4N`2L?`+GyoSMqOZIq4@AnM0zNk;5 ztSl6N79c_D`1o-|3@&d*NHYo8l06pp6Q}XVvFi^6=vvr45N$`7Sbrp*nsNuF?!KdQ z?Aqxqq}IxZh^}-)uSPBkAI0^9B~_zyPEXj>bXoL9n(9-BRw8fR15P=4E~?e-SLce- zQ15IZ;D5)tJi{|skgodY>T&BrM0|vlZaR4ji=0n?bRy!pv$dAYDh~mJ`8tww5n)ED zk45JF5)e!Pv$FaMr<Pk#X0uh1xN|e?^LV*dDO6E$wyptcGg=v!%3d!#cpdI1k((g~ zxEZCax75XGN%nTL8C#o7=V55#ri-lZ^SSx?pKg<sHul!uVpJ)J;*bAPf*SR(W_eaB zgULkalVl73)M#~r-SpuOUl^lGzuC6lFDkm6Esl28sJ?dZaG!tFkT|Z=lpUdSvi_HL zQ&h=je>}Z6{u=JT9VWckv+OO=w<wU7znsv^L}&7ZKw-&os>pr#>kRGT?8_I^tERXX zQkNiwK6UOS*X!*pKmDfz?*KW1k(}at*k9HG0Uw{lBgPk8yYFGqJ9C2pjVn=ovv!MV zkrHYBnELtjDR{p?=nk^rb$L6(=lPW4%$_q;nA+5pmXfRSSCpjW&(<|yr?7CX61Vuw z?}ZquK%{3Pff;AM5|RyU_i=1%-u#KRs-IoqCAcu68-1opJrCcd$kZ1};G?w9!Ck}c z2r2@j1u`!4j{r$opOzg)#$f%#FVyc+!$1e6#x2^8AvdV?6Bq(SyPVGJM)V7zfyt1l z`b~A6q0(?}1lvgC>aGJ;)(AqJwdpd+Cbz=*pVQm9j`2<3Ii;v`XqP&W`&&qjz!nSA zgP1`@ws1bMPA_0u^v<a1hCM_mt_`?4>fg2Ufwd{Z0(Fkp-xW#oc72bFUV^8fIioHx zCWq)Wh$eGd8_rAH6>6^~GrwLFikN>gvRPRyRTuYoe1>me1y&02CURW#Hp(e@krMD# zM^cIN_Yosx+2pu$EL-G(Bzo*%nVF()&ej2aB?%xZ50J!>hx8nfI^pECMY6w3&BrqN z^;VkX($mu`u-W~IsgISeM*gcVp@|o(`#`0kx2rTZbE>=J-N+Lc!FU~#lz+byrda)O z+c3P+jJUK_z<d^faO6$7MuvC(qlJ_;{F|&x&#CB4yx+b)FWJoJ&}6{E$zYzJrooJt zyJR$wY2bv3wdn;aN-5w-Hi?4*!@_`C_iC4Ef3H1xs0jFrZIYL>*NbcE&~_q<PqmM9 z!saV$#ibwmHw+E$+yX!I$9tTH5QfP4^T-!ZVpiq!4g_djPnbPHEVS0f-;z;;j(ER` zd_5x*y`G5n-bg$vUYdKjr^Vh>$i5ubs21<@aA1dg9!L^Qj4E^vpbbqZK><mP|D?Gq zY0q0s$|Yh<(#9E8R*rXPJxbtrEB)wa$6trrFV}Bn>6`f;-WEo&)7C+A+FEfr4-(`a zkoQ|+dA;nfKTile&lb%g^{!V6byCm-oEv&oFm}!A?34$n!Wh<*%<PGJtC1}{8#L1r z_2BM>CZwtQdKXP*Y$0NroCtsxE?h`Uzu@UwK-xA-i&2=9AN>pWx<z$SlQS0;T53a+ zL6(Bn`6<N`hYD;7oY)F~3gAJwg3EoL_&?OHwPUs}%%0n&Ux|F)YOazST2PIez!Zk3 zB*7=mdja|iXsZ0JvL6>-Q10I7>fP_kFp9FvL_V{ji@BYs7$fe%v_jUvO9gejEuICd zzMGTP+tNOta_tyoVum;9)o#Y=jTs#+t=yk&%1g@zG`i{#Nt_jKdIkBz&!G31FZmb5 zj&eJHKTNMQheUIz(#^~M@X=2`Q|w)+s?s(Lww13qj*aGD(!Zz`jL6C%U}Cz>HfM6d zxVEGJ6I@^ZRn~rCybwf{81={W$CqQEQ}%O~<Xru~aF5leZ_k=8^2K09WK~v|yu>i& z;8>Z!{d%&UPIS>&BlGFAYzi1`S~*Na!$C|9QX;WpO%%k%V7!Jq1}`~CP)75U-vR5s zPX&mu89gQN<BxBCS8KRhdg^DUfZ3RS`I=&XB0}9yOwxDM;Y}P8GGHX^h&?wS^N%%c z61KRxjN98An(c(dIdydEnHrFjb&H?Z?artN<0HxsZ)Y}!DVGM_fJ?Semu=zV;aY>w zm6J|=mym*g$mCWdMorcxF6OK#B(Ah)9a43Rl!;C{sg@T_(c@jJB3@~k4XyIfM~?EB zwh}^J6f|+A63=a<xTawn4d?z6>rWlow-Bd#dEHh;c0bsF)h6LJ<<lV$dHxfZ@-5pA zE|73MH{lY73+g<=2X%eRdLbs;st$zrydjk_$55OQ-a=rc*sUcfxPFiYU|=vb1W0J! z@53cck1!^-jpAWD?hZJ$lvx6(drLcAUjFR>c87BFNhIM5KJIvIWaQHD4tL6zg!Ak- zHK}72f$HnWyR|tO!}Q_-Od|&l(gk1TPazaeqJDDf!?<}&87Z?EaW}VVzi3<!Iqgr{ ze?(nEC;=NPcW4l#{oq?q;!*`dNHaKIeo+V6f-}asW;cdZJ5U<@{z0Z0o@?D;Z`r$t z+3hOI5v;r(EzgxQ!iL9voE?4p<t182g_HPQOIZM0iw}7q9-ZU5;r=qJ1KRs=Q12>l zczkvSzVPAjG+zi5_5-n)k@Sm0;I;(1GU2ngrc+lkh8H=&0yw;Niej8o!3PE`H<SII zAXhW%sqps-kkbOI+d_tkWLuPnNvO%gcuT;iZQe$nw^}<`R#|@z_}cgc5_zl3DJ4(c z@seP9dD3WXRnHr@$hiG{qG2KiJZ<py)>vs3672X9e0m9Xl!n$$NzwaLEV(zHLsvmU z#!LU7YLvpz^L-u}ij|b0T?MH+c7;}&_>n%o?$|atD@Uj5T>fPg7viEnyM(3rRQ(8< zA6#zyvUKnB_RH`qs@49tZn~{vq=@hW<6$f%i9zJ`b)<%)Du0Fx+ws8h*-^od&vNpa z1cVn^kgkyi&0>KTKW*kAB%mY$9iGsNJRCu}h#0sR=o&{v#ig`Zf+z9uXCz|jrxKs9 zAKwPEU;nLWOiPSuxS-K+yMs{+zYIeI-X!hvwXM{yDNBE%76v!qxkvZnBB@2o7qU_g z^)F0&C~NJ;A&H;5P`U;1byki!v8FBePST4{4f2XVPPQZ4mlq}in{IAuoYwtG2uW3D z*5ZpEP3}czHvzMP&Qb1}b55K<4`%eGrN&_%ltMm05WsT<k3$$$`$D`P>8?k(jXU19 zedT`YNVpH`64oH}uZww-T7_tV{|))JKk3+ZM#e+==bNIV3(F6CLcxPfC?LqxgN}d7 zb_y$@72Z}HQQc%kqb@y!+@Q<&`hsMd+a(<6rWoh|_ieR{w|D<kekhV2Qvz|n!H(_s z)_y&s=M5@TTwKk!Fh0=>YtqUa)Z_f`0`f*ubsrKRSC!T}joQ9bhZ({K)-(bFtuQ>m z_D2?zNc!@&(xLZkS9xhtgDq@RElg%W1ycQu^kvzGE|h?D#Xs<tmLfFMrr@H<C&UD^ zUw4taKezBx-k*j#dFhJovS+)!C)S5TK7!PtrgyB7=GZe{YOd1%0pr3wRcS@6{}N?I z?@$@ZpSBoMTX*Z#)G$087#J41WAq7wh=Hg>;2ivUrp<yIr!NdLr`0D!aV%Cl5637F zf#Oq#MEjp|)!0UFeGPgUzpUT<g{+I8t*xo+ej>|8@L6o-RlJBttuNw178{_VQ53dI zMv0mAAhou(#YbXNUwy!-JS7W83BpR&SdF8O+;`-4i-%ol0Zf|xZHdLt`#PWOe_^4Z zgmB87W_A<${xI>hOhHa_G(;$~?Q3Dgo6=kJ=w?!YeMpOvZnRcc$>tEp>nm-h1k(em zs%3GxrD9`i+dPFo<V(6#2feRJ{q&zpwKT9Nf|r60N5mlrqZ702=2fqUkyR6oG|;!o zjHX9>c1z6+=@Jb{H41p(z}U&1_~S+wYpH>{R<~#7@O8twx4b1BEq)`*^gjFbreAmU ztKmX@Cc#l?0>}Qwgta*<K8BO3^SSB>lS^qaqM7Dh*CkT+;O~YmIJ9_3^qt-kb%IiK zOpUE;0e2pbp+%qtoOq`(!EzNYa3E(H3F|9TNtkWq?-#;9AZqo<Zy?#;iFN=*f@S@D zvAheOK<&@v%7`eN%1I{{m<)S0LSDamNkK?`duRS$iCU}Nn*C((6gx5Z-UIxmR-tS^ z@L|FW!{l4u5eD<wN%GN=ZA9aENWP=oN*xb}SYs0gpjVbl$V66e+C)k17{4W!=y$Z7 z7+LP~mx=#>Er9z6F8nc2;PCg+f#?R4FgE{xkR|2i^o?Y*IGvZTR5YSknO<3({rj0s z8IN_@6n@hV@kasf=Wu4L)CeM<KIQ`icrpV&R@7Y9s7=bARZT##CO)R_VSEskg-z9W zA83SIZtRTuo2LG%0XtrxAa_xol@eXs_dMmLPlP9}9F;a#Y<;4bX$u4Nq41{&eKi49 zMS^ya>4|;59}w1ks+JAwTiMzR2!P0FdDKc!l*o>xl~oHYa^OtLRD5>#A@eoYB=p$; zdUz?U{3UOmwtuTm%qCe*_2=mR4`kr7>XG;Vpl0VCRo;k`dCw@MnH@Dj2Qt>#m#L^^ zp;tvF$%5y_v-E@balAJq@wR+S8;wjlTIG#qTQ%Woszl88QK`N#fx$VrHuLHcqfqGf zhey-WIRWq)cgXimn2hEQ1p*FV-moM-cM&o~u&9cYj))+JB!-mIA~uUIOs3*GJ4eV( z<#n6gAK+)g=Cz2@ODN0n^UbAGZ$bs1pNSkK(eMeh3a{j#v^-L@H}XS&{3C@Nsul_j z>PLbZsVpma--p7u!~>zuQ)RpJXAD%7SU!vv>L6Zj>txJw&QD(7f;OI79w~8Tk#Hjb zt|IN`8gYEy$}iYau2eb2X+U=h<-CmX==iwW(xqr5OYjZ?!}I8!wHj37bVkPRq!^;$ zhu0{KqDtfIqK)fKO`3<yk;=V)UN(vE677(wXz@*J{Ppc@c<a=99;}=Bl@&xjUQJVY zu2%-MAWL6#-Zgv7=7=B?6O1zMNq~OPUq+4E!Bgxy3hH&BHcLt3h$UD=msmf+|BaM^ zu0)B?mGg{1r_WyUoM2$-Y5d2mLLu?j98b+7!{TjX(3QB*R0;fvOsy{-4VA{O{i~0H zLbsSG(bNt3rIlCVPkhdX`!nOHv2ui*s-cU9_yChf)!H8dv9|(_7o8U&^m$AOI zR(X9W&E-KB0X{NqNid`m&T?#?iBEv_(6d!)RS!c~DyqG~?Dd)G$kuLhUNjeID-B}b zax>-nqVk@0aNS#VO2t<v!KA^2k(G+H2+cg81>b*T{QCNB4)*!l$vD(4l^da#X|JTL zhX-E4RD`&wTQDv;?feH6_WgRi=P}CLh1LuyGq(8PJ%Y_YG{BZR2;#>`M-tdxqbEWA zuBsAVg2P4(+S<+TvWLK?Fd4PJk5F9G(T+frI_SXAIC_QZ^-5MZbDQsSkjEe^;<@}b zofz~}t&uX@j4-+Xifl~tdXQlIZ8hpTmHWB|D6oq>SFXw<`XSB?abHN*9%DDhHW#fk zilv<-j0C?A`s4B|tB99mq5#U=_Q#{8tqD0`RhwD<-R~bKUy7&u5|!=$<tu^<8)_+y zN>3+r|I;uO40GN0!w8&d$MW;|KewU+CF^q2#IlVa=-xgAJ^3FAvTkx`dQmI5MzPQ8 zq>|)j%qHXYgW9GdznP5>249=rl~`BfajXt9r}-Gc@BHm6<MOY5{%HNe!%JcyXU?GM zI@xR$6LiyO9+ObmpA2m%m+0Uo<Lz_*aGfLgG~M)5Yl5bLcqQC2AF0aY3G@O5zQOXF zFH3EKL&WtHyl!B7JI5KKI4q?O?r&BADvZ%Jrd}gqVhUgtiO;n*cspK^rCeW`J8|+P zLhas=yBMqd&NmO5!_LyXcZ>iklj`Y!Z+u^iL!9?AL=xv3x`Rlxl#!5#u&Vf{@zL>- zS-IkraNNLASs^#Kb=>*tRrfm_-$`aSk>}+$=c9$TxwW4Z{)l7($E|kvdj8uus=c!P z_+-7&Q(6O_O`hlMzRzLJRt43@8ws3t&MUiEZ*ZcCbk%rRf%0{JTCgUvDGbR$jafJ5 z$qPe5jvtH{H2WtY_2UA2t!U#nsHoVCuiUi`&hg}t>A!%RHe_ZP=m-OGxhM+HObga( zwEMd95@%F59#!)*EX}OBG}L5muoo0v1VJ!WuKI4`VLI4OnBHH^fE9BtiBC#|)A%`E zulcWBs*X45GO9(4LyTS{+rpYjU9QBnL)vi}iJk#$u&YcksQL|Rqx4or<}cj<oClSG zx_Z#u9IlO%T}qTuAD>8RnUcEQG_UH8rRHYb`+gLeKb6$J%3#r;I$=!R(GJvdO16~l zBuvmM<S`j$R9$kWZn24cN#vT<c6Ygu(^o~2OV+i6pud`vfFLF%?AvX46?=O;)J>F= z4)2lH#?`}=_}m16xT9qpr03nkbi&!Z+fU`b^LNQK)bfkFs_BeJFjhnY_>OI+?4zU^ z$oH);`!}2T=e8H@Eze~iRKa*Ic&L<46wKE`l~^`+B(<4Y?O&#HOFsuLtkVI=<@1KQ zay5Z_az>ybw-zST=MnSK-Tm_d9+B6-B9b+ZA#*M<fOa~XGgVGqZ2X{$1FOJhebvv; z&1-9CH#s@UIy$PX3mI4^0wPQHirw5~0ZfI&uNd@^@nt=lx?HX3k<Y{2K1|g6^gP=0 z+EBpA7r*&7h>SDuaHGa%Y4X6`7s<c=p4L-|%6(14{rJQpLc!7P_YopXZERVxgwni{ zok{2tpDz(@L#{+NqNdvt^Mvw;7Y<&+<8XXCt0@v={h86!Gk)M@3Wp}&kKl%Rv)JQw z)l*qyu29=S-7l<G_(`sf&P;KlQHxw*M}SgUGDQ9Dbjf|3l>yMjb;kzd|B_7y-jdMH zV7|0$K2_bA3<<A!Vygt`(9Ap(j(b7c>(}POQKgBjWMx*3PWUl5)>KJ1&1tG=fu+Lw zdfKGUvN?&Eq0-OqCm*WB;nrV^L_k4NU6VyAfS*{f-2<mnXEC4C3f1xDv<XtX^1kO; zl7r}TxRiplW1En#HT1EQkCy2I=f-}d@}9yKJ(&16&`5D&BnD$H=@KGAjaUAgi@X~Z z3Wldc;0LYMBoAHJPQ+3u8tQ&DvlqaA`K*gKDzVg`k;rL}{9q8r48ZjEc%#sprzWPy zxZ}w5Y5u+kUYuvu7eJF=VQ|mhbO5rbyW1V0`?K2@@100vM2Hx8>@WBNA2=x=Kk#@n zuexEiB#{^ZT0J5SNm<Pdaa78bmMh30Nkp@cOS?Lj#tC=o;80`sDl`;UV07sa`<vwM z{Qb<~(~!UanYo_G!M5=GAVZ_f?A}jrn{IoVwBCaK<~`gu#onQSKI0EY&HSS)pZ1f7 zpBEd%=6-W*_;&Bp{OMfGeZzX{)(nLHEFhDMKvBEW&UbgRHzA0~7^r<5O~@w{sm$7G zz4nU;#eoTP9d?d}!{Jn*SS@3WLPE|))!Bn4u;uGFE*rMrD^T#QrQlkO`V+Emof1IL zNjkW(#jik4=__xUPe9+6Oo8h~)F1lH1`)t%#-ja<DtmhnW%u^(J%{6u8%73jc3XPM zKl$5_!`BkPM;*1Xk3GehcXU+wl47~jdHf!buR_5oKtVy#tFf#eDX$EmU4%z!uUtX@ zF94G--m5OIBaPHjw5@V>w*Dg%gpZe*$d7Y>HOs{AzR!L2>l#lWRh$vj_}A-B&M;*p zxK2|kpRua2%vAU7@b2;?y9=@p0=u$IDI4I~JY#aJD=-5EaJWG-zTzPh-vSE|PoZRG zYcmkGgQ$srJZ?3y<A^B<gacqms0)kix$Z^Mv7PBhu3XevJfe$TfH{wRJM>A0*{D=p z&0W#@^SAncr)nF2pR&;<{#w0VHL-e{;orRuM;}f?SQJc;ZCn&b_fSi-gK1+YJKh<Y zzHjCc7Y96p(nxk`xjsvKvf}7%7j@osMi@ctut>NgrpuFStSQ<l=oqDY?>SLR+XUj6 zz1qLn>CfR4QOenVW}k>m+D=dJ|5g6Rxcu9Eq^-R2AdjlUBIpd(=N7K_ygB|W>WBT+ z9h-n5*D{vH$Pi^8jv{oph%wiMTlP9qAeV!v$AQE|`M#RuW%6_WiYPoLH&vt0&csE8 z*J|>0cmmjq1&l0hzb=@m|JwAL^aow*f^78(qZvH{zj*9<+weH4>h}^Co8q+^C>n20 zURu(let}y(es2`egTmAHd*Q!B?b~|;CYOxOCeMLNOroovoyJr|b&=b*K*^z%b$sY~ zJwsZZ*Y4Gq6$(`!dn8Qzp5x0IXUTj=Wo7Q~%qGmr%CWrZSTu(k;=qW0!1_lhR*m2Q z14P*(bgfHlO1nbH0+3!W_o6?!*ky_N?Nh14Q{(Vrbapm|NbkWV)ZAs^0BUg9<n;{V z<N02{jeVb6n}aWoBB2@fjz~r`r{^}7h>^^+{p=KPBy5eSAiUH{Ah{4$#M8P<=J5&j zxWt~@HVm^w=U3sxNu77yfPg(`ZFA^$t!I#LHgkiz9WHnx%YeG{h?AHKwiFkZRy!oz z<;@+!|N5p}UBmGi>3R>CV~+_8hO0Az<`ak#ea;cp#{D>gj7mn}k(&2m4t;Co-KIPG zAn!*cs(P6iQfZ07tTJ4eQSI{!u_^Uty=Tv?_9;s$Dm-&+#O(x2kKbisN6P^N#FWa* ze~6;tkEh%JMPzM1!jPblXD_Gi#pvYWTz7bR-s_tjp;qsJJ+yRF<H#t@?jDWZqY>5m zLzu%$^HJP6l&lPgtxTF{X0>^R)EEz-5`;v(xQmp-Wo2OLDJi?3QJS+fhx!ZF3!;I4 zX8AW)F_uZ3>%URf0CY&<v5z+@2|?kqSbv8whhm$Hag2iH1F!k>qMI-3QFg~u_t-YR z)XEy*2X=U?qzG0c@mFqUJWr1J3&iiK^pESzYAu2f3Kr3Lda<4Z4c8T3N=W=B{mb-y zLLOuRuB8qe`=dl4aGeMFU+7hvqWpYFl2eDNr723<{W7KapMMoY!rtWp>uP+KA$M+8 z`xD7!f|~f>P0AKTYdfSEf92TM1&j-xy%b>F`W?x6_xbBzqJnDHeWZsgIYOr;p@Hwo zcQfKEpXcaeA9zmKJZ~O$RwggAY@01Y(OL6Fs;m<dmvlEy!aSVQsPk^=IApwEp^Cpk z5cT!=JpQz_LPfnyQbbhxg0r3%dk4t6a(Y3{N2`vU9o)ryagJ!G_>t?P>|=GL;}-lB zf8V|QSr!g|j)dJ?ARH`g52CSBDT(MxJzGDKgh7-eMf3oMAV6bYDWPW-Y&O__l*%2H zl+HuPC$l~f5cu9p(YOgXErQ!~a9pO%@ALBgI#52~F%gOx0gzDTK7?uG=-AG#Glhep zm*Y**-z(Z1L<NY{;QejRaU@>J6%}Ig#4{7r_GFnSBl<~?b1oaEvD=#z#EjPFW`;io z+UnOP_djz8QXeG;Wst#=l08o$$q$dkfyI#dRfIG7ZVM~3MNCd_BF^qy>8e8o+nYdz z12vLO;zvk$=do5o>`!U%c;lAI)GY8_)xJ9XaobWH*NPWMK@@!4wv|y*@C>^o<d>q< zY2*D*XUw^@i7dGwS6YpN(Uj-PSvAwh<8eF1*(c290qUq|VA%>^-oQ$bQ^Mn|QL8>^ z4CMH=uv=&h%pi4$gr5PNz%c(>yp0nW^~==G*i%KHN6Z#V23V9=+JPK&iLpU}Q&MA> zvy5>k4?AAj&$J7y;O8{n%7^x`zAO%_F=DYy4T*cDpD3C!o3KCwI8b<`k0%nY`Jt$K zi6}?}Q{_63nAOR4qfEvjs=uQ#r)7s2*?%|7b+=g>^QyMIfgKneU_F8TNt&C%>9?+< z+Bq^4wqeVo`^~8dKd*W?w3(zA7DN$XVWqGmtLW!4+sLB~ZCnq2{Uz=Hh=eiJB(<6k z#o_oNQ&Y~5N4wS83_fon4pK8T`SIWP-lF@nwIE1t64LR+K@D`i>TFlU)shWfRzW&O z%6NaywKpKx*s}AT;il__$8LNH8Vzh-Q470vQrelG=twI7LDf9j>Qt>s4K>0*jUkD_ zQ)m)^1}kdK%?Rx#o2qokfyD1&gYgtpbOJSdQ7K|pw18#T^B42hzWg~#ow?orZAa2# zpxOp_?{QGI=v0j~^w@ee=$o7l&7#|`{`F;dx$b5(S)172obHpS23Sk4<r*XML_xXq zHv+@*BGpAHWUvr6ph$;J4Wfv|L=4&H{FO&Nj%Gkl1Fg0coKtmdljTPTS```*0{JZo zxTSp+X<kxI-1Ve;*vnPs8A|nOoG~(qznwmJb}xz5N<`Mp>jeqQ%TJr>TB*a(YDU!+ zlCCJTlYZk{EI=rSwl1v!k!bDLaeSy--QqP^*cm}hrcb7t8^B4hU3n-eN2D>&;t0Tv z#oxxx%Rr`plMn=7?M6oTb{~aHH-^Y~pz?OZAXgJ>3f%Q<eh8+~&^0{9c54H(BF?zK zgAIwA*QV}XhcKE)$-nUH`Sk2aFG)uVLKkItTbpb~totl>xR+yrcDXj3cacvFso(7g z$f;`0gF+37V7yCOOm){@p*9wND4LA_P7=>DnDYDy7`5YhRRkHSU$Hc1F1Px?WG1Sd zh;(_S^j)X}`<hIm6g`KCZAtK>AaAAZ<{nyK3IapY3+J}gfIM^PUAXB}8%x#sM0GxA z&(!Nnrov3>dJS_Og*12zh-@inPCB3s`$JjTX&J<tw++X;#K^_Fw4r6Xzu@o&POqEv z;rxpbOANm`C(x7QdqY4J!8GO?t_D04ClM0J|BHjw6)u*$RTRl~)>(J2p#}2Nl0jix zxppZd6IP*ds4Vb?&;*GVN`V8@jspH=j+8yg2mIUZ;tD_CRSn|Dqn4dEU1q#ax*Y|+ z>*^05N>nOz*F4Y`bpYY6T>k`t^G;x;n103P6G+d}m7fPU3KOACAW%?SNJe?r5nCCW z_|8da;X{$L(Bln}?1x)bpTcewI>2!$k8Ry2T<$MM<cPL%!ZW0PDfixLTGPVSUd#`X zx(jEQmzGKCFf~$%WkJJ|gYLMjaHFZFXzBvOTLR{@^wWRD=A|N}&ikB#Rd(wM&29*~ zze`I8nY1lw?Vf4aX<X5Z<NNT5i3y>4KhF?hl^FLx61<1$A|~$H-hGdrK?V^V;$GiQ z3)`m(H!gIw)ipIkq@x82nwkz}w8QWvasDe5Ctj~W7dL@Xu1kq%^$^(DwcLObY0;^w zse>RAdEr^Pj*Kp7ub49Z9E9P-S=t>Tk1ZjM<OH{gBJp`(DS{X_T(;_wjTBC%f2!wF z%0>uLtKW`}a{<_!8anPe$(b!Mjj}v@2otTUhZ{kQf`c25nHgV>w&u<QwRknc>p>Sq zYIYwW?)pkjVRq*yn7W;;vIQHo^3jJZt<CmLTw*sBo_@wOBGr!ao~A!R7yvB4g(UNu zjT8hw><2uS?{5}ZQh&+WoRuehp+AEhlEe%%-&m{&2~7W;Ljar2Z4LzKw2+`ku{pYV zRv7Aib6>!c5HzOc%MtMU2bj2B`zfX}e?K}p`VAHDVqP!L&FEzSNQ<Q>0S+s~bcDI% z3$YWr!Pj*f_m?Tz(RN+y9bMh6^9n(-45to*xk?)xkG3QvsWWN|Qw2T>`Bwvi{QwoY zNS`i3_i!!+R83@JQhonRJTmR&0BVJVsgo7POsh*W3HZD`a2;OnMtRv%D`N+CKoWb& zNwJNHygluX_w-*>VhGBNEOd>>>1B9M%0U<3`Gd_x5<hX#275=mFwKXj6O?_Z*%bA8 zLY9aC93^64y`1ZRCr><Ke^7t>dN*CUHL;1Ihq8|&UJwT{H^f0^1X=;vew@`u#|c|! zh_Q3K2V!<xD3IJsmL2QKze^XWG61B2o4>!R{ro?mQsbPr6C;o5O!H!Xw9y|Am=pLk zkMA3$G_ma(!&MUXT5_f1+$A;9W#b{6ckSAzeE(*>hGZ*@DI$f7TRSbktLBVI?9Yb# zwt8P&(64ze|6I;q<wP&hA)(_3lC*M@h{s!s_13FKO}`_1I4Q7H^Jw?MZec^IfRV|l zpCIuGuNk`kCk($a>)K{o+8MWrp=(*L!P5}&Hd|F(sPg(eHBX_*UeVPrrK4}aa!L&t z)Q5YB3*NV@d_ws?3?n+5xG~EgXmdzcdiUn|81UGBvNC*Pz@PiAsV)`P{zB9>o;ftp zL!ttN0lebgw#(t=DEysSpE(u<1uf?8OP*^5ZidYJS2HMDK&ZJO;%M^^;T}(b=pmkj zzoR3-=$05;5!zksoErx_t@&2Z%<iE#B-ZB=5~ZD<Rpy}OqZjKQyPTWcr3`S(k15af z=)r)Ir~%TzI!t;>hF#m!aB(j1_WRdgYMIbwXPwN&a5PWoIH3U892tVjU#NB})@zCx z7EM&kJw^073X&4nO<;R4RrQ1TTCDgu$jwAOua~s;q@u#8{5Py2Hh2&i5s@$zOD5)W zZBa>G-acD-*^L+@k8d1?0i_L8l68vZRx#cW#X+E=11v-iRI+`DSL>;Vh?i!j8B`~* z1<qzjCIhDsvFtxY1J+PTNJuoet>Rkd!VsGi8Qk;d|Jw*WG-Ir~*t)WP#nOHSs9Y}O z&Wm138zdS~DRTScnD*e?Ze7jUGmlF+ag&m)7!}v~kUib`eu(KsZ{gwVSeEJm)#_92 zwGtv`L9rM>uh7-2{_%eCy*oDi*yx+RB6L?OPK)m#Z;prp%*J4FS`lCQAwv+^eUB{u zRaB~eZnB_NOC1$OjT_uoS882c)*bLXj|5tvR~M!~AmoMbjs!YncB|VEoGr1}AJ%x3 zaokH1L?Scn|9on0(}5nW?grrY=T5@%`;AXlG%$>%7GnC|-n)(+_gUQ3M*@cdERQNc z#3q2}A$Q%nN3;#SR>kSY^xjDFIR$1@n+igjRk<KnTuneP7L_g#t-^j_O!Nz#|Gr<D z)OG=C<%j(A@m5;PTd<^apw_CueMw99j9|_hMtRVym{2W!%`9*mozldJl6oKau>e1< zC|V*Iav7KcK4`E11oHt_{_>B43ojan;yDWTGR#o9`r}=AWV28tJTta##d!i+#aWDh zz>tWQQ8W;l_nhDOER%^m*9ewqcvxv$VxrSuovGs_v<j+de0uM$P&&UtroV_p8kdl@ zYfJs47NG@VRGMHxA)+lyXM({gaJf2b-P?Qm&U}{K+}u0^g0y%AzH{(*Erg#BAB1z? z6^xBqD4ZCLD@2x*aYY_1S^#hd=;NqU;@EcscJw=S*X;e#FGF9{1x-vjmb2*Y%r*^v z3118{eZA9M#z43uUpB}z!335u!XsXgc|1S5#Q58=EkWB1Ycbnb;(NN$rSqgORcJzu zr>YjVxx=5FM^Pmy>Y=Wz(feP!)1Vb8$A<3v^`o<lIV9V%=X0mpRR`)LYH2_>+<E!V z?;KAFI=?%>&7L~MkSKi*VgO%Lv4C9L`Qtab+CqSaSNJp_H%I@v;kW;^h22?7Jpcy2 z9R`b5VNiRP5@uDxwTbv09F&(UyW-$P+H*)9OuxsYwOy~%=tG|3rw`mICBYRO@EU~p zz7I#*d>4gfyMLnvq=EEQSQO`3d8y(I40yji5hFZq#Pv-#4-^A`_GXg0c5!2c4i^^P z_UUUsU}s!@H_&9YT?&>78s)=`4ksCUZW*L^R5=9X|4LZc1%}?jGZ?la#SfS+!L9F6 zF=7|Islf5zLyS@Q{qZrKLXa8m6jO^lwtPXt;hNL^*rV(eiRpUX*Di2M1^m(lihlL@ z^>N+wiiYTqAMK}r*mCHhsGH3}e7Fc86nA-RISj6ySkqvt0>-gy!8GLxePeDrW`M*P zqCUi>z4$hMd}RBc*#gRDgw*ai|I=<KABx5U#?EG%QQ~CGt<q0ORolZIp{gALu_NVW zp``*pja@7L8uihAX*7#Lp!0wIipA0LVj9F)Rad6Ees@y@A`0$EWJ{*Uk}e8!2j*Gs z^cM4SQHIst88?qCW=cR==C{mrZB~yQ-veDra!ssn!6KtRZ<2`3J_(EdPL0_!n<$z( zdqILpS~>2&)lI&V9*;RCcKDnVJ+s->xKWP0Pt+)E#{l(jRP1|gPh8-;Y12;oPZVrL zyEp)6F7A8lSGJniHUz<FqNkWUgTT1!r>k=B@6FY3))oA~>+Z=4UP@1QxjRT|d)I0? zn@vIb`xVZ<sqagJdK>qd{Pve!hF1pBm9ic%q^*Z6-Umpj!&`G-gZS#WFX6B-{l&J1 z(_Y9fuE2{`-8QXDVR{9>SS%Vm?|^V2fXqYzuZl+l15K2$ZX)Ila2xzhc?h|sO|VV| zt4CkCU0yOjz^2zBbiIU!K9T!S$!!);g(h>=4NAAeFRVsL^#@@uz-s)#N<ORH^AVQ+ zI9@~y-6>lstSjQuWo}6uF7uQhbDfEB2E<Sjud!@W`~p#MyeArSw<@TI6-RG!*i`%Y zfHA>l>rTIs&ll~e^<=<pn2Y>Y$S?2>oAF?b6u`lgYiqOsCzon8M$IdJvWIuJjEwP~ z?Jhjdg@QZ|AqV)cA~NR?QK-;fq$K5Mtb$W!Bubhbzh!>>=WDy2(_=vb35uQ2X{J-; ztzP0;!Cuzg!-)y_HJ@|XjRWiEJp#>K1*!LRPpncvzUMd&Q)^^WQLrdQ(xwP@rcRNA zB7YY=!{OnnU+Sb<XU0j<H~HpJdguM3HRe=iLwpZAF+yIXRVSr?Mk&?GfQ+YsAi-Nn zl`qaj$#7apBCRFXFc#|omiz3BPtb8+-;8N`f5RIkQ4@8^lQZ)XfVuT2lO}%U)zugP zo=XJm+6Za+rXWn^dnlv<p3AdKAs^%KxOm2ukCAdbx9Yr*aN+oaEp&;{qMKC*%5ZAK zG=03`{kzi47)L^Zb>SDQ+k@lr8m-N{3Ek=8^{i&PAgHJ2H&_>sF41u*82tZh0ciW$ z#cfsF@1{OU8(4=XXx^=ZA9l%Lz+9{3p~)AwhYdrvF<ub^!pZ33q;FS;4S%ER`+u*d zJ!7Q$Qdet`55xk5L06mnn4Hw*#x2ysv|z!=coy=NJbzKxC1z|eUCyyKZXl4MP8R&I z#ydG^s=o3xrfvPZGPH9Z54J(tb;yMVh<id%u(5wV|73?PFK3yWoTR`>Nx8(s%8>s* z&s{fanroZa9+qF+%{5EDcrcV49{@&X(HCT5U$bMpEH^cd4u3sx)&FuU6x0|cz&L^7 z>blNL57pRebV(u(lhf!H;_vkoG?N#(pTlnS1{|`xu31OBzw4<6*Nm>X18Lw;DI~gt z%EzzrI@0rSkJ`zo#6V5mjn59g{agt~p#HsO{ZHpr=e;>?^X>A~;i&p=7vkcREfC$r zj9SR=MQv0)a5n7H2Fd@<i9Ca}ag&0EN_nCn=W<xo1Az_y<rxrS8qgEeZeUbrPa$$U zT&c>4pk3~E_tMl6YNQ-zmL}L(8j0!XjeP!I=W+<{n-Z#gka-Im5eD1_&=ARujzbBH zi7C>z@hGjlvO8WJboNuNG|h7Ybn%3j6Y?thMAHOZqLhz`SaS8sB$P|FLrtpUnvkW$ zO;37n(y(?tQsy$k`_P;U-2M&}aTm3{HisKlnC?Qw@QckbWME0C*nRzUir3e_e^*jG z5l&Um%f1!2@hx%Kb1CmwH9|8w{5X7CO*g1WG@!|ME4VOmwWQCDMt)@X@}0EwCL5@{ zJ!{%x5<U7QHe`94OS$NI2>Zd-#sZ+t(hQ@rIy5xHDp&uk-P~*4+}y!-;*&#)ula~5 zp#3^IN2u(FEkJD6aCV+rnQ>p&S4>q<_Tav=2Q<5YSPg<Jr(P9Q<tfiOt3S4I-&1C` ztI5r*ojJV}5u4M5{q{nICugxroZ3>h6<y@ImTeUpm5}tMEh-ajkMTF8s!)Tf(|vfX zevuvq&91`j2cTSNuw;=J-S?`yP;Z7uSBe?hv2FKCVbCUnx8!BZ4<U^97L}r4=1x`G z53E%@*;@3b`uXXfbNH-GCZx8pAI{n1Y4ncf@pqbftE1tkeJ~TNJ)oZ)*C%9=z9gWk zsB&Sbg=L=~sAJRu;E!xD&=!;{WC#>H$Q51aT`#<?7^g^O(z#V47<lN#TAhp_?m&8M z0Kx0K7)DT+Hf`6DU}I=$?Mwi9M<5Gj?n>+1+4asOD$FsDK%nc@1u~AA&Sfq{?<nQU z8K7wEZk$)V!L<4g%(`wK;UZW$pT$s|qiq-uBMo0*Q_y7@u!i@MY@D777dW*aU(yq- zJ+bG%wgv0d0Dq}6+Xy|gRm=PPGDv2-TP6|{M6vU4Pw#}fnDf&C5xNHH6CDVLj0|1! zEi}RM*sbqK2SQFH4b#itwQc3i?l^%#Lw=^HNgSv{7($OihY574pLp{z#~b)G)j$8( zHWTaiDPIRD(6O|gGcK@-v%S2mQ*?RxG~D|GQ4B^V<VTo9uKbD6@At$bcU*-fX}qk1 z1Im~|vld|nAz7d+-1}r31-ETgvKV|ldRBv3N)`Ro9=HA&cXeO$RSjhS8^VVJZYC-2 z^U7%59!#LKah{h6njfDO(EO>PLIBbL6*C)Al|ra7J1-O@`I2Y36&92OX+MEt=Axc` z)-NQub#sv@jGz4-w0HRULY1Q4&`0otlxN}($bouCx8>4}&C{n^+r``f3ArC|XA2y7 z&_#JVE-$;oJ7J<<1pywc9iI1<;w%<8{GSL%`<IWWr`c?8mVyITn71lnkmkARa9U;` zvAVtha;(|d@xVEN<DlHQP344*N9nbnWSd!9p?L(>vWJJ9tj-Y?_Y#89dEv+8Pm#~z ze9OiJJpQ%Q!NEZS|Lkm<9o@=2-~|#iF2*^D>cu8LG$5uZa}#Ig3=g7i7cb6h+zYcj zrd=-){g;gN@-uG(5D#Q7I{OesOU#{UL83H#P1>I$V#C-qym?9)i07`i`x3`PVdw?l zTiJmppw!6H{1%P!2@Yhodd$zi^8CuZ<pT{;(=&CK!upmVpB|7n+TAS-q|_XVBA+oC zvd=?DZuv3uE%R8VpJ~0<u4oURrUZ9hn3l6Nw2ekEF+2Y8u?wbk0#KGhQ_?6#3q8Z{ z%Q(pM7MTV|(H2KXvVkjI4r^VcFFw`#ZIXQaYyohKOYQQBIp`gz4;9=v3-@ovv^RAr zuYWXZOk>@+B&wsda?QJ+iW#M#DZxVVZ{3NB7(gw-<HF?6fin_*Pvij^84gh-kVjqJ zhyL8==Eqxr4;i1Eo5N;k#(iC-du&KxXk5=fHq_LN9g`;E`0ybR3hqg(JdCCFwyOg1 zPWFT-L<aj^k;~Q5af+>{SZ>-#Q116%sfg1NP)&bL3A(}O+8`~NVT7e}Yd7AJFkM#L z>3Z84C7oMizPE#;m8p=-k8-<AtAey$5I$}N*9Y8H8vd&Q?pr|(m!B=>8wPyN4EjB; zar<{sn~q(RfG0mEDL;oo)l6p@FhdmNJCFfhFJGM7-j4X@ex0#PrFu45_BtT5F-Whm zXspa+0Om9KIO3RjXWa}~)jwAk{l@nPEjpkobc<(pC2?0Qevu(^eLBSLA^qWMKw746 z#kcC_AZ<Yi@sL`&=GUW6l07R5so{CJkVu0=f+Na$;=I(3-}ZxgBqbM`+)_QA0<`Z= zmjli>Hpt^h1$oZK(NNH~CpLQ)8Uo%}T0GC^@EY0+1ij9tLj3&5h)76;ZMGbq--<BL zvCj@+wwD(cB50xo3+pR*gqhhId1K!QV2m&;1Kyiq2Dwgl^IUZ{mgw*QZV&6!<G_^+ z-9yAt7w6#1*)aXR5W<&y9S_&3x7c7hPmX`NLact3&`a5|+cW^|)JATU)HLIHpWF2Z z_{iqY>5SXM*mZwa0n2IkY#{F8=iUkq|A!(LST<%5cxP0vB&C5McEgisK*$Tc`P~4a z(@VKF`uY_SKh}B;?X&V1@h$R1uJ=VYCL&wNnM9@h26Rh_$TZ+{s%b5X*0tl14iU@A zjubT&HKe+S#lf8tD$o;>Sr3KzfZG3rV>9A=&62v=x;qLP@Os|7pKi$_f`O$lLBhs< zw@_`d&}7$ew)T>aih^d<&S?TJXDMEQA8M5B={Y!E^>Wg^^IWZVOGQOSrOY9FBlB;i z{>UMp@g-T!@JE3mP<V4&&tv1{loS<(m{XfS^s}4fm!aJ%m3G{_`rB}m!i;5Wtdpr= zdk-JYaaAX03UyP^+IAJd<P^yV{VKs#UGYVD-P~(Xko3dJ<zcUh1?dc6wkU*cs}2s) z<_hX+MmV_>tRO;s;1Y_u@p^$Dg0oHg0i=PGYMy0;>ABhIgZNYKTQcT~f}5+x>al~A zlm9lNzQ-*<s=P{F^4KxAy#mwp`G9D*&#<x^XBaos_CEjomy00wz(3$2B|)IGrYDce zV$e>`{wn_RQ8`X=<zTYSwMhM^IbdV~C4ZG=UJDy}*lq~$U>P%9qsH9Y+dR>L36|HG zU{U%*j8EJ<X58Z8?alY_>^<~@0)zLtdXAJg$jjRszs0NLSEc>&RCcxrK<|t`3va&| z4qC35ZZl!w#nqMO*Vp4l3*yPUxn0MGMK<c-@LSYGjlYXPT6UYUn@vzMJ^7bbfBjlH z4;nb@e2h3be$+Y0e#_V^{*=b;qw9o@YeM~wW@X=TD_sV<LsM#SNKj1+hyp7!kfPqY z$8D4*+;M*WQnGJyk}HwfGREaA0BR3EQdfv7%nY{s^$=Ax7MlFNp-oIbK>F?i%vpX{ zXYEah^(;itl`|xCFwSuL?xx{7t*Y;yM&|m`MmxTM34}Aurw9Q{3hlANLm(Z-X&w}? zwb+&(J+6ko@zNwGkffMCUE5-n@I(yk?l&~Bu`>jH`%4~@%PNjl(Te~VTG>$KUg+F< zPD_lrnHfk}xXqy0wG0LUZkxuhl+m@xXws|a4sy<b_~f{UX}Q^be63ADKp_2D_;2sG zp^lFHYBDy4h6E$l@GsZt=f_4X40YVx(xODjkR}Z8szZ3^3DFyh>j+66o(bZuaNGxF zA(xG9%oTHIvx}|KLcE}5&VQSKy|?w<gW8X_6+xi-#0j(NrVcVUixHF~56xV8Q=W0l zixk-2e|s%@1mXi2TfVTUcQRHb&Fl$i1B<T|L^^MJW)1@N^9jm=yWxW%QceDE?|zj? zP<+S_)Geq{(*smkuj7|=cH4HA>sw`c50F$YsuucT@6GC{nGs3#e#*Ge_wz+wP^IlO zjZEDWknH@fD<o6r4lZZO=JV|zQGpuL%)P7h!_GXAZRtffSsTfDlkXQWbO|Iqa_<w9 zXRtJ_sBZ9C=LY%LuXl%$nD(l_+==Lpvz<+EMc3Cw109T4AD6P*(#Q9sUqvllvsSl( zd1e)tnWc=(1~U}pEG*`}kO{$z1MlW8riy&FAyO5*3?h$jsI=X^$efWt1rz#j%+Q`^ z{4x-FI8?lhHDvu>A2vINpGwSen(JqtCy{F#q-G843A7n^E9%KXhS=r3ZhSNTx{PKT zM~u_hM1VPzs|62C5}7ve;r^-64x~340`6lmF^PTuph1Rx<L3RNy7LHVGq3_$0*s*I z=*p%Y7CgESTg+2tc_smi9A6INSySjl+!#a}n|ofW7^>7c$8B2Qok@PDX~zr_PLLd` zZS1(H`d*rn<^4>K*aKhOBV>xNS~7sfTm@7j1V`{d+&JEs-+>m-8rp`=sOacuM&#bG zeg{$+S{*39P3YBkXVTIjYcX)(jXEtwQijz=Mi&iq<iNsSTrn+2VR{Vh2(%PkwLLxx zFdNtC?Tuv(i@&>w&;1ps5uK&VS92>##B25K*Y<Jaz2TF>gt^U-Uac=eJ8xHn`VGJO z_EGkH!MSA#!@Z)|fqN8#G^;RDEDIKa30T__)p^L;A7{5NfSCSLl(#u_r7BzB!%Z{5 zasE4SD2<+~)GRuhkthu&6mG|5;2)NQQ+4uBX38Tp2LI<OuArcCap&j`_lzi0c@<#- zi>cY66N%?4P3YGfAI!g;0({bV+YPaq$|pkWh!9j@*}w4Aci`eS>au%SsRrc;KW_*K z|399tGAzny>kc3-QbTt)NOwvjDcz-XcQ;5kqI5_~OUKZuAV_yQGz>`B_u{?x`|<wr z86HpVv-aL=trG%6M^>lD{s=b{^{i(lO``pM+0i5mKvsR9hkB$>xa*A_FW|iv^So-5 z9ebrpaD@g)$;bv)J4KlT%|6)}uHW6=!A6_dS0GQ_52ZZWh|!R39w*fxaYBn<i}h;H z1zs7Mfot22jl0a2P_F0YRw1J?W~W}%&f2eR({ADiv*bi{dNtYiXqY;W37iO8AXDfr zB&;+W#j8Gz5=TG5M<3!d-P<8z<#lJx^O}!Z1oM6;`itFA81^biq>$JHZt_R%had?v zhu!*QXn)R*yl%p@l#D55%kkw9SWZskikCLZ#<Ptp7}#vMdX^SNGO<U6`-=9RI~oA+ zd>fmTKYoVYP3xH$=cN5#T*K5<=~Ac6gt8R<r0Tskw9;$gXV<xWIf*WP;+N=u)w~)` zqTTfVXoEH~f8eq%4mTeQWL|`c25<HmQk3tn{QB`J42g%zl5cD2rQ`fGiAShq;Ba{J zkhM6cc?xU{kVsP*QYLHqf!U&k0;4dPY9FYcHKw&2=by%w7Ztr`F<}Ou?&?tmK?-U9 z<_AvdfanUovZAomEAP+w&341yTYEh0?Q@^QCCJmQPLs#p`g%d$9kfR|P@_ifUH~92 zWH-7;|FCoHTFE>-dLO{$<Q;cXC-tq76kruoS;kyDIqBunYta8m%6UK1O69UpGV7)G z=WmI^dkc)*`ycPG2Y))HUq&=io4+}<)-LLrNegF83itY5=dqGrh$baI$ZS*SnEj4v z@QyHL3xpdqM5wEEf5V?QC+GRsXTUJwB@n!Br}p{Rl0N1eM~i5es}BsWbrAv@V%o0o z!6!z7XVx!JCeqh!Y}qWNJNr3d%o^qeF#zt0#%qAv%hO~^TRBTeUUZB-Qbb$~P!yV6 zWMS$7k}v_zmvHEDK(q5(6ud~AO`<rz+Po!3Nie{nNO~vDt5E-Q{(=gQvT32ut8bwQ zKJ#7lU62FW<NiCRl*q-=;ar_e1%Z5?J;?9ol2{xDnHPP1a<6%Kc-{<hWr>JzafKSS zdmU5?d+rYp54WrdPx@J&RV!^ga0fkhOt9-MGx5&M>;+I9GS@T}R;c*UwLw!RK8pao zmGHMjCmm(K^}evPxMp0^&+>3<Y5@8bHKS+_hy|YPafkM7)#nopbs7KHxwJPwzC<B? zHI)BzPmPUniQ0TDyuXN90bhuvC4q?Z`0@2q%Jsq?>6R7W)&7ZC3!<8V7}_*&IXlGK z)eBnj9}J`1Uq;QE9ql8+Ll|PWDc3g$pAQxAl;_Ki+iG~XgFow{I@xS%*FOeacXPeQ z-T;I*F_#SuP2L%A62Ydd<Uw?Vf_ZUv?^ry~KCfOq_w0LvviY%dTc9~I<h6R2RUKCQ zIgALD|8G)%FIcQcFn<#_Nc%n(A?+F9J<%d+En`5_^!WI`<?)Oz<tOwfP0eb#fHE`A zS|KGT|F8BMuR(7#>J)|V7&TFmk+oHo2GE~bQHbYIg#uT*`@7`wPCl50j0_?^+kR3( zff=xgO*r|GNUHNt;^g&{_ETLGOUs_`g`|<90JADUDpw#j)rtAJ%Qm7esh;2T{^aFB znt>K9M9ZONtIuw7RfECyoV`c$z8i(I!7*u&g72!I?rn^?Lv6veB3)|#!JwLXALl6g zR4*j`mmku!xie#;Nyo{^_ZY2oG@usGMMUCVNShQ8_!Pz7?^mr$UKn<aJl#u;oWb}n z8YF4-_0lWq>|6LUhu*dcw(J+GwAuzRJfg)AwBKC-vb)pajDYJuO~wFwL-<ExyHiAA zfV$<P9i5pJdUx@FGfKo@1X8Q)8Ze**vi#bIK5vJ$TF<8GXzV#NpAM1dtkcqbNs08F zZ_+I<sdDv0qWb#SiEi|BE5I_<dFDi0kkHzhQ6)BJGpL3(5g{y$kcfy)Lm(a^oHLSE zw^>oKx!x1DdvY?@1km8^?OAWxQ{7AV$v^$L#_y`Gtdvn!E(HKpI|LH6eoGC(3%*z* zz}B_%sd}DbrY6;(gDR_y<mv}?zbNalTsGQ@Y$Pp=nd^<AS&N5#e1dv{2ui5=F_pL% zPTa{EA-}=|n2SFyL|@sT)M{K%P7cR!BHmA^37?w29{n>&85Gi^?DeE8hnx_%rR(PZ zoJL+cS?<@TV6?U2U<O%=RvR|Uhl0D1wEQ@+X8!X2+qzVAp)k&J#yG8MX>@7<C!f^p z_6{P7&P&64?qGtZi@iV9Vj`F39OMfNi9o@sTr_?+iaSU>4FrOFJKi`ZllDSwxf^(< z>I1{1@Aco3&fO0C)`RZ^(?dkTfFp)0Gx(T_7;gx*L-&(%m-|3H;`JD&QE>Vgu|HaH z%d5PKy>o@-ROW=c6YYTz1Y}+j@l~%6)4G+t`mrlDN0UI}{cCoSy0Niwb%@x6D)Vg$ znbzwPn4MMxK)L-h0WmvXZrwfFn<*Mf==n&iXa{TDxOg5^i9d8Ooq!GdX11Y1PA*y9 zNnZ2)*owRk2&t^PpA1m=P27*(z^hvqqOd3|31WxLa7r)}lE9}FJ0}1AP$#CRBW<=} z523x8W%xsk3I(?o_o0{?o?<wQ55dvnds}ZgJ`DZzE5uLvqGbm3S6qEbT6O3?eNnV; z+tJ8w|E2);0S%&}N%y>MR)Y5Mr9KA;s^YX?zZSK#$yk`xwyB&~>Zc0*Lv{&+(aJzj zHm4-FPyCy0EE#>?Gb`~ESGy(0Vu!2z;S@)^eO~RD*H5UM_G`N7!{QTgv$y$#9lko( z*)FeukYSXc{DM4pZ-1zr1HAwZaV!kT{j&MY>qlA@ngyPWJ?Oe_R{7Thbl3?ZibFMf zjQNkPq~8VgRM4*os-$nx@4mvM=-J&ZyK7c0(m0lWT#Ha_13CZQRksiFh~nerD{O3( z0TP2h!f)Y45t?QMP@CNV?~{dAc_d`yx~FbQUilffEjxvOdwIDC?nhNsH<Vonz4>AN zD-R`Wa<cxaEE;8KqDc!F67*op>R9gO0@!(BzKpK;-EunEo{aV*W%Bd7C~Y(|yQ#lx zb%fU3{+pbQBQ%`U@c^-ol4x2^kOHo^VEv2k<A6857jt~z;l<hqn&&Z&wC&^1r5|B< zUwf^E$~a)aGlB&_Dr>>j*Ks#xK7&M{*Yn{qMm!rCbg-o<xUH4^&SgVwZBYAb?*QN& zJK~eNAlCraZ7$K8t+G*$y@h-ED&G8{3E_76GVqXsc%YBtG9NxPs{KlCKZy@V=CsNs zgvSgZb9}J#@8w8a^YNi@43pr+q!FwJs(Ml?PC=*&EnF%~=<3TZ7tG7o)pKLZt!_95 z;x`+VYF`V`qiFx!S#D>N^GkY}no7LkvO^giO0<f>eSn}nv26u32bqGRUQx_OpyMwK zI2oS@yd4+io;#FQY@rSv9Fzq_c{;wneje7=gtPjk-y`>wQJ!m_AEE;GaTvuftMOWn z>OM7GmS;e6+ynh+9{+?9tSj5;OXF^sUL>l}u_uzcI`1*#ymXUE=@xE}7d@FPQ!>>) zNO$9ns#*zXtGs%hdve@28_+i&V2UM|)Q5Q+X^NZx0x^@=IgfM*k%p~T<-~g%*<on2 z8hnh^=GZ>P@!!p52r2ThOzY$x=N$qXu_{g!1pc-wdM!tN5K4>-tr2(@(Db#{WZ*X` zM3Vm?j<%*6J7qi2PlS{=DuprY+iorcyIXkZ3|4nv$|-UUbVAT4oKn%}zQchWlV{Y{ zl+ged$9bndQ+LA(vdiu%imdeM{H*ad-n@@H*x>Tz=`An?{Gpa?;JoZH!WYjVr1=3o z&2<F{0n}o1gmb@v0WB(O9M}76Hlc8a+qtVL@G;Kzz%r$6EIun=SV$<QU}M82)x=6; zb6fg}?Z%(n&(HUGC1}07^SL;nto$?l(UJZvw~&pu$Ax<^zq3j?fmAT`Urm8Tcw>#A zI=V4q4sh>7`5gYx*6>xuQNLaK#K$&@Ke#uj7#tWv`#P7N0Qvpwb?5F}d3E>N<CN|F zU?a=sAGeW)>5gG4f@Y75>#-fvuolU>ifF0Ya~-KHNPi4cQkYgv76WXe?JC#5ONYX* zi(qYSF$}p`?&v|K+j{LaIT0a}=Bf8w*I%I-&E2~Uj{XZff{nJZiHu$YPP_-DC*<R` zWM&B#!fuvygI|qbUXH9D(_h~`U8Mk0B8o{wwk{7K+n6PGa+$SHrs7sPljsTDJu3EF zyE8cjN|nRjb`{co6|{7U%Q`?j0oupqi@)mPv&I6|t_26{>b6QOs1YfYdaefOGH<R{ z{R3k`-4S;BDS0hlcPTQXW=MT6G4_sEsQ?|a!K;`dzKh&b9lz@Va^p236><sV7g`l% zSnElMfm1;*JWajf1GAkP3<(d$?+qn!6b~5^pxlELT!XSDsm`x<CcODX)+!0AY?8N@ zzd!Hz<fGhU+`2uS1^KO<CkBo}gn*~np*i*eiq%@ASp9?IZUy<RwFnn?roULOsb>dt zsBLvZ$Ig<jjw2_qM=uf*k~ctA&B5AQ!oV(8Q(GH9p!8Jmv#+hKt@Es&($0EMS0b5! z_vvbW2?;|)CE$itJ4<a9=T!P^W|{PR2XpNTY59CQ!9LWEiE!7p^HwIUn8aW^C4KRJ zd-3aaDkemo_>VTM@Xm!RCEh1`d+LRbjH|Pm=|g*HNMDin^~lQYd<OaQ!?NT0t}f4` zP#x_D8k<<iyps@Dq?5yH81Nx1KYd$u84<j$^2%el;Ke(BVh@(piZRDCH^k!jPHcuV z`D3V}9ntWt{Z{YGP;P+S1^=T5?lTi2A?kz0$74~9EN@BEdVypw04H|2ZOQ01b}SI| zv{-`P-1z=GhEgRxUC5Mzgm8-n`^6q+RR=2j;_c4L2dF{!zjgaKS)=Vp4f!ud$oG2} z#Ckm6%>}>0BzyC8N|<|a+?UB5_;*Uoos4K8qZ45q`djxx@R35E7?<PiUl}tTCHcr7 z?U_PUzZJe|IKIeg$J{I|%LE7z!>r9YTutbOa&a`~1q%~+5*~DpkiVq<_g~!JI~r-p zUfT#M;JCk$s`!{6WLo>Jo&p`$36o4Hd}G55&{N$10JNra30GvUNYG4*^XKZ5owapK zO=+oIRAdzQ92IRMiA7TBGZzTU^~<FL@!^qmd9vy^g9<P4R?)0w&MgdgIMarGkiwXd zvRJ$8g8%(a)ZAuA!<X<W5D~hdTfuL9e|-GS+&f{Jf%RmJ_P<Xejks6#z8C^rk@B}Z z5AF1}dF3AvdSvhtKnV$(e~_Ek|4?*%GwJ;6aeZ`EgI#p`RE^~~%ZNPENDIdML-^DA zrC|!YsaeNko#HEst~*pyT0n~&o)m4rqOj=@GA#no>f5U-HYci$Bc3iFXAnJD1!=k3 ze*D*Wa{J}dl}i+h&JR-kJ!X*GlmI=(_2+m3qF<W_^qX#uM^6*0?NLyVbgR{?hNf}o z`ACYx0>b#`sccex6+!NZ@vC%N2|wl1ch*yU-7_JmU)j<MzP<$S`hOMVVfvNfiAME$ zF0D@@HA&(#6{kY5g8#?VYpkJY2Qt=?6jp<&_S}=i#>-W^ldE(GbG;1X6^J3s@7FAg zO;zKSFJZ>_mj7`9W*bgC#Jdqm3{siR=Nyg0evB(2=B|pC+(nkcwsSc}+OA$d4)rMP z&bwD{8c5jNVsrfEfvj?~a}M1dZrkI=jpd1m=Nb~&bOThjYzoCJ$yO9WH??t>tL5Ae z_j|lG{WXT2Ju5v4%8~*89!=29n0u1*^K*f~dvBkMJg2{E;RcLgpf>Ffo4;<U-aAMI zibOGP6SKrT*5@%XD0Z`dN0Mn$3CW4n4+dKJuy$hPsptP`+Q%~eI#q2+*B>|H3558k zx6WCPITR4Oy44BLrnR<M_#a6fJ6v;g33cbEIWuV4OV}w`u%wOu?$f5CncCXE3ObK3 zy=bC1ju7QaU24r-YRvT77oL&Po{y&<FcINPybAC`7P|_<+zo(u5REVWqK<)op`K!| zEnZR%F%~3L*Y%)w{y4A}_@EbHI>C6t1{8)B-cX!qJ0+)u{z#LE7-^w55}l8R++XAk z`Gm2hkmos8Cl>;u6(IVdP$`8hu~M}9zdwA$o2yOv9tzeg&y4e{-hS&mGu|g3aYr25 znDb$vA&akRv;>2##nUaQp6UGShQ;l4HTJ#f((6ZPL*KloGqn*;WC;q)Zswc(T;_LT zbSf)0NV3??C3;k<2-3h-I9C0Bk)`FaAcI?&W##_hZy9AeN6{dR)$>2f^WO{TT8-?h zA~<p03R(pPmdg{svtz~PD2*xHdsBNYx3&r%20Z#y)zrv6eGvl;A9YW4UFiu5zwDKk zl*sb%Opk5!S(p%!P(UUL5$qg3018haP1#ZDP$@E->HR2a;?;S7Lt;`+aeaB2Uhp%C zGK&aZcFVE|Ma<*jrsd{mO<Ktya~V9n%OV~)|D(2FT&X<i`BWC@97_{~b+{~AlK1fE z)$&b0de7C1V|4v}1Uf8*JRX6G4EjmKn`G|-u>0@JPlGOxdCQ44_jgJck(K=NhoFKK z_F<mt7KxC_`a$YLnx3vO?%Q!EheQIze2F+LDg0cB5lCl$bKh&VUsGq3#mSG?vBkCX z`WI$l%rEOzeJ_()fKm2ug~C~>sMUR)c*<Yl4IRY&(s?{%)6I+iWPH~w4VM|StS)9i z0_CTxn-A`7<J{=N4lrt*T580fGvW+Rlzh!88g)mpQnR+^g5o7|f%BUCQ<W}#YXqHB zL+XxOA*gmfz?zE_)9gbgmXx+z@Jmo@y!4>u77?P_y9fi0!#+rRF@=u9G48v<TU$dW zzWADnN2C@sN|uD|T(Jt6-%j&<a^aA4rif^K&V)#1P7av`+0l{1AYqLAgw$HNgJYbe zoZOxA#f1kUG5O@ef}Rlcd2wR#*9YCI3-d#lR$U7G9~n6I$KT+NJzXWv(3!nvkFi4* zhBZUli2_zG;LGL$Vw8e!PpQo9p-~dVeyxYjh~#TR#X;_Csotg&^6PO2OM29_sD`kM z%P9$VXG?*db&mFVMSPvQYaxck3%WL^+o++__NA!5msgIScXX+1CREzo^w^d@IKp}) z;t8uBb4A@hz8!2kF9YQPCTvKAo6~EZ!RXO_MgKqXHQi2~?^AjBH0hiD2An=bufS{0 z1fT~q=FSmO|EIQC|D7t3U6tt5Cf;i?j;tL6L!Y<c;ES=AVXc-1P~5~+g@;rMEw6sC zgz1cgX(+Sx@wtBm7+%KB0nxF=Rt@;Dn%}rQ6>;p(Q3SzxiFkDHEKA)P|5+V&rD8R! zj<NDg+yl-X&f0HaGt?_GL{U>vcp$0s&a_;F8sCrZAb9t^w|jv_i(`nWIZdP~f$e1P zdK-K#cDAqv(!pj2Y2tBnb4P>fNe7aAN@uT6zRyZYzZMah5)u<D5M5cBnx2+VKGxgM zN&-w6z8MHp0!}n5B79<j{CCfCOFhy}BHlB&V;!efQi8xUv-SC9wCjO)oY6MreKZgc zLH5pCrQS?x1>0Ce+RzJBN3$VhRm4P5;6a%C83tHRXVK%&>?{Y34->sdhJO`|IFCEk zrg5Qus`Xu?_vHIkAlwkA^`z{-Zu+bH;|#e`53GMxIHr`d-Ie!WzRkG06~gxk+8`0W z2<a>;H_cjkCQo>?{cNQyAE^3NH8d2o1^rrHF#0oIl1MAwY1>w0M#)ulJnQ6nivcGm zgSzC(r^%2taP&&z^BcX@Yc%IC-e8n`b;{-R{*9kr{{Hy{)+As})B7f+Pf&J=ffiMz zikyfnPV`_|AkIMy8(JxvS)75j*(G@Nz&u_F1R3x6+1?mPjqhGy_H@GWvtPYZ-oguG zi*7{#z}$?0xO}ZoQSe1))%8)HK^VWuY~ne8(~IO(`27_Zx|Oc&UY69=!3;`{ga(ry z?yY=bVc}S*g7qApm){z92r&I7U0S;9W~n`YAO-_5ucI~y^6Y>aq?{+ME}eXgbEP~l z2eYuV8xsXIu~#n><94T~c}Rd*f+CnhIQL1xle0of)4695|7KKKyp%rxR`>pK>~6iI z2`A`W3A$zEw2<aoa|=;wTp!ax0gtD5Z%33?wm!kx``F5hpEWYLJmpRvcFW^5_PBvm zva?<|!YI*hx4|U*kB9xJ3$(H2+YJrKr9-!Q=X0tenCE%|3`Q=!c7M`!6n~wdT`Q|h zZ04*j$NXr^<VOMG?>4S?t-3-5VqV9Y;r(Lz!Q|Y^E;<q;CBDWep2W1t2fEg6uC-@& z835+=P>uqK$~0et%Je^G7q%1hUB6ENUpQr+Yl8g;>aRU&Wy9d{U(2S}l<O06+I(&4 zR_0gEDG7CgRixSRV-E9X-N8N=*gTX*U9N{E9){#(nq4I|`1^WCNz2q*crWF08aDf2 zECFeiHYdRa&!%$C;b1z{Ya<4|{cBwT&PKrQcgA4wK%WW$)=j+9u_*>Ms}T~CF%j}g z5jVHaP|es+L4Iy1R4J16^h!llb!#tY!dgcMs_SQ9U;xJBh{1Oa_<DZ4ccEO~gbVPe zH1nHF<w{CQIk`j%-OkVHmhLnc^8x^BXSkc=W9#~0CI4_9rt%(gR|A5i_G>)T$oI7x zdiHf&w%47Gn{1vRFcKrYp&vK%h5Sf^zbN|eUy!(rL4;L_?GWI~@$)ycQ8q0-PjxaL zm+@kJ+l95z5w;XPKc<$`N9(US?;T6b#ob{lAFz3e#yFi2F*zE9zaLjoJNveMCm!1; zXFTs$I5FN{*|v579JnD8^1~^TnpMg@^|+&q3CalE(3^ToZQiY5=L51t=7gVCQLhGC z!;|pH40mcmU>`DG2Tt)EGvRIZPn<V3ZCp$;18!r>9!K=c*O5K(KjXF98z55EmY*!Q zs75*_d;n_+V9-eoo&NIFKGE~9EAyL`E*iJz+y&j<qav={@O}kDWme99??hvOJB=<} zmxS5-9Zp)Xt^&Lg9~Z^NBU)jfBhH`DakRx~w%x~3^R7<c>_-P!jI?|W3`>&9c1^MC z@H%FY4viM)ksDo`Q-w!MYk8s=L?1tDvi2W|7N@bT7{CBt2=&fKtbx=be=?r;*sO%G zp6YTnDH?es`+4$}%P(r-H8i+kI`iOj17Q)c@6CLMevy&4DWMr^hkB!k8LaFW7Z+t! z<;l^}H2jI=V*Xx?hw)^|RgE&$9SgW=&t6I4X`2rxEfSXrDhD}<Cu4})bbnORaeCU? zBn){x^e_fmzo6&iv3v8=f5Li+pI{!mkLG^{+$|>^JES(&Wuf^XO0*yRG~bY74QJr{ zrK|T5{mT>j6MIe&!4hi0^yt(B(|<|DZoV>HScuPS6=M36)DR-S`}DSDFE-IkNj1#a zQ_{+?-7@5{)Z;8Ae!`Tt4eb!V5+K?z5H<i7qM!a!G*b*?+Vdl&69q~QqjiBk;Dj5; zRo0)%mfrsbL#$}CcK=3CkW8HPIdz)RRCoEu%cs2gX(jkCRR>1*?Sr&Ypm9L%Dy0Xs z6ILPFx=|tNf7IT7arETIf`-ej$KU20V31Y`ZA)cEk|dvBTOt(mUB={0;FMB1`HPkk z|G6Rp48?g7sW+^xmTp=<k>yT=07mN~W}dnmDYzDHZT^H#ejl(jhv^AWmxR8Z*mv7; z?Dn>Xu}#gZ9i1)u<VX^wqPWYv7)l`93jUF(%5j*Tmp62NcWDz4K!$XCM;B9=vblVJ zl``-}t{&bR^sx}d!J+DEntytY8#sk>Rv%*eC(%*Mo(EL_TK46!_r!<fiI`Q`^(v3< zRpGFvW@Wjsp{xXs?CDK6g&@=@FAh78KJD;0h%xw!t^fWr4uHH*o#xjR#3+H+#)u2S zy;9unw9t9uA7jsi87@13rhLnEHdBb!0zH`6V_RE9BF$rA3r!$+$3nyPmLL?w{#5xC z4^w@@`9e~W>=HBFzx!2FZ96Vb6;iA7;;05b8BHQ2x(MItc1pEAOu*&K_e0>hC}5>Z zert}D%Wc`2N4Jz08zlREv#%a7G3i8|vnTJCu*%sEl71w5j-k&7Z6;xCBUZm`;x0x} z!$uk0vN4Lm<+UT^e^C%{dl|HfChWqa+ZS0v@`YXSe8w2XNACq*l)uz=h-i^xTqu%v zc=qLumS&w=GE1F|HuqOUXA9)zII2(LzZSbq$JT;o50l;~(^c=;NLd--u^TVNH0E6B z&aDKyAsH0cb)jK7wS3(VD(0V$liA)l(Hh()b+-~EREnRFI205O01M}?mgkU>?H(R7 zGEIN=J0{AMRm|A%)YQ>3`}swTh$3(PHE{OW?Hr~a>tY?RMUGi4UJkSY1CvMn1_b?< zht8}W3{20xcoY90s=f3WqcWk=itOI6RyNLJd(?^n2Wnq+<8dE$;KVZ+bAL2gJwvl8 ztGQGdxVDbKJ|TjRY0E!ykMaq`=dX(D_A1LOoH3t0lzH19Bz2ur1cf>vCte%H)jLOL zrKg!X2jv@p$A4^koh%nVJzSZvXyehd-)Mtlx%o^gW;%OoqWvpL6!5I`o^D??;&Sf^ zQWztI)19GEvD}{NP?r-Pm%xzw`MH%)eL9yMr!~UF{bxX{kC7JwP8M0Z9%2OhPHAW_ zlHkF~UaVHHV*afiFwWZXa49Uwnby^EW@$wH@`ZHC@Mhyy<3Wy-K4@3#yR|EbXK^TL z{9GLz7@9IbUIr7u?MdF-vbHb#(17LI7EZ!KxiA{h@l@Z&Ijr3k&%Y|aYNqG%(^U8c zQVjg!fvwA)1TGrZcV6wS-X3i*t8-7}2VjPr@f^9CoRs;D%F3QdU+9nGTsiAVeoRJj zPb3r0z-Af5=(E#d-i}-9BMeKPRF6}AYpv>aHJFj{XXS=(D?XWfjsm^W2{2DR22wF1 zA~I1CPM2cdHLn87Il@%ze-CTYew-NS_AMB~&~ZvSBGJF7@^b1)K-jYR^~!Qg%d)>& z5)~>Pp2ZQ59W+^z;QELVc+p{ee|vxgkc<$_XL`MpoxbgypD7Xa)0|{L(7<h>mYfJQ z<!-gTZ0_Jp5uqsY>)ynRgrQtj{C6_%M^iMGLb%Tqb@P?D)Kcp%RhKZ=S5#je;1PJB z$tYS08b={wA(}V%Fcj*T9^|?NJb8J74aAx6VzD&%2zn@APA>c5&`N~q4nw?*RdEAP z2>90<p&lFA@m25;CR8*+rt8j^>cn^50{pb;o21PDJ9%0iJX#;|LFLZypYur@VLQb+ z>_ffX`2_{UPkToMBg#(8We^`|QA^N-d=s&8i8=YXw<Ra+ivF89G#9mVJ5&YE?Jm5- zUmA{Z*>_JL7(IXfdd*t$+KnpeI&&iCi!v-z?GVMr%&2Y&=NlQL=q(l3E8`q>ZOI%P z?ZFms-G`d>w_iJGY9uH(kM#|lzNeQD9`GXVky9$4JTd5<oY7(Ll8cMAQ~l-?;f`IT z#`hWQ9lyEpIShgg7;SBB?H(UzEG~Yb<~OPzK3DkFbu(A@&e2Lv&cNag!YeZ3sn(mD zw@(oPqmR$y#YYP?A5t1>CHZ1`$51^4g#df=BHp39t`+BNbrRBo*}@0Pl`5i)2A!v6 z1|<Fqo-OgGUSGqY0nlyx{t9vhy}99)lQs&gm~f`!zL)UXsA%Y1v9iWSVhruiyBnv& zX|Dh`5@&yQhPIzo)yvunPmI;!BZ_L*;qQGyU3_Pt<O7osf2A|>t<DC#8o6LweV7V0 zfE%T~pVq`Ta<UQlkLMk^`~f!z?QO)@{5m^ZR0mKt8i^jM#eJACiLlFsk5SA1S)h&W zw^8L8Gz18?98K9|;e^gfoRbH+Eb~0_f1)Xt)N(JEF-=SeW4?ZH1e~d9N|E7+5G)IN z*LJXNBIZjcc6E{Cd*0mi#_B_|`hGPy47t8TA&%@Dzh`YQ_Mxcz3jl5mTvBa+ALsBg zGMUqkQsUSJV;}I}K+n>`!>=+6qI<%<FTRZ_A*h>+Y(%M1{y;3uH?1ZyjAn8YxxD{* z&_bQve^rcF_b^>Sl%a4L=;(ONLK=)7UYnAE9yids;g|aEU1s)|se}YicP|fxdk@zS zca{ZWIM~y(v*r)C9$Z4c*SNTH3HOi7%Z6v7X5!CzQSr3&0kv!8{*;HgsTqu7?Ow4J z79ZB~H2H8_aOY(X?V*u;SrZI<ufcWvZ5Y+#o%&8=7+K54%tK4yIS8q3Kc|UrS#2vU zP%A>+MY5|n7AYcv5{>6eB@H*DZGnrqR=;2d^Xc^^_Cq`*h;#{)jA^A@=4&%=K$US> zC5xp$;0SyWp2LmH-2w&jIv^$KH@dXK_FDOfXt7VQiQRS9?dJQGn{1lBW0Vsy5+F4^ zO3%oe)b$BT3VPYNJ{t0&<1t&M<4>>gx4r65EyZ&kG8(H&smk2yX9awol=55!A*I2# zzFX=44XVQxLxO91gq#W<ERx%2BWleH-1y73h0xIE;qLZT*95~LJ&5t$+9SUwX{Lnv z_nvJsy>D=6#TKK&EXQO*ZN&RDIIe#tI4*pdu_^JPXdD|aq9-$us+*|s3)N=@*M?Ba zT{6(Y%e?ye8=XEEE)n>YAD15_J!aOHCzvJry{VkQ*D&O><$jIk4y)j4NiWY!^Mt`v z!?943VILiB?4IFa#=*hC#^z?|m)VRA<OOr9P2aj&T>bK^rKKgY`RVEF9)MAi^Cee> zG%23bJ^ERBr@{l3GTr3DbtW;D4k?LL?6}y+IGe3RcCp?qdpt;uI_)ESbG^6A(*@u< zqjjQdjUT}_)qOKn9s;GEub@?SeU<#*+j6o_3k^QuOJ{;#M)=VOa^Pmg5>yw%B#)Oy zo1OZL4`>kSOQEN7L3g;F4=`xoD|a$VdPWM3`l2vIo#Rft*NR4^S=(2T9fKv<NsV#h z{^I@*B=&mu7NbT)Lg_&D>dfrifu&<V96j~w?SA{WIM`C!0tzpS=BHOeW0ww2-Rult zx9III3pYkM8MiUGU+NwLB2cCosOWN+?xPeBU$683>CY?JTvH8tefQ7I9~k&Y?hdT2 zxg7QS689VPXuC#lK}WbyG~JdoF?%@em$&UCmP-sZeR5(?77xFJ0`Of1gwZ@k_Aq}f z+nEHwh9?D4&Pl>q7j5W?%;*9f<lCqiJR2hjmgwnkMnr`#hLEy+u-bF|+}>#sDzMSL zQ14h8QgTAv%$ZuL+q)30%Bl<zgrq&ph-2@LkB`%j7lJwPk?S_Lq7#_FX!DS#0p!7< zp~<D+G`zgLpDh@{0;0w$?OK|erU1J6oGTU+hKyO^3J8_~-FBXvlIY+L+r6+Tkn{YW zA#nyim2+sgq?bOkk}I;}adV2HzZzdbdvCP+H2T*Ncl9DO5!#j$0B@Jv1)`B=jkWw0 ze9P=VZK~Dv%Qk@SJ^p68<zwe(!R3pIiT%6PzyjJ{hP-I!_gaKu96twW&Rm)dGJ}pu zR9O;!z8^9#uN(T6oiy;dqp@Eh!>dtzgO?8)TGKj_kZSWqyt@A?g2Y*Ev*8SKH&Xpj z`u7SN_@R8l)l({vK<zXjCCflsW9a7e<ZoV(u_}$PZH3E2iONe)UQ-7hHsb)vM9td? z^<tG4mCUU1jhlHnF1V!au>5tU))u*1v?;)x;2Ea^TUbz(QV;I!t!WJRVHdShy$Bz6 z3R@BL^{y~ShEA2!B+2mu6L13<(OAtcFueXqS!^8~X@ML};QX)~;i8tUG;E{6#Wwnb z3RPBW5T)|kxC4{6p2_wkkR<5m0EU?(@#k#MTbj3*y4ww_trLuH%;t5w_xBxkgeR{R z;r7arTYQpBKLV9^;t8>4C1Ih($(aQvbueClYF9kdx+ucA>aPr-VmV)HrWPqD`%3jK zsSO+5c)ZL$wMM<uzmy0+;A?h}4iAl?N^B&ptlxZ>-`l6(1VM3kR|zdnF*35FWPd2U zE%^gaj-Y*IFkdz0#RQj2je)hj*ZwZn`fFD?WbQ+BmgObsmM&RunFmhjhS(`B*@R5a z-IN@=P*Z(J{L@(LV}ok00gZ+KMr@3@XGpC4h>dE!xe*gp@6V@PNri!5T<btv<E6Ha zse_y-pC_NGk(KByP|Jk0V|V7vz-Q)X6QtA|B@LTk#y{cUZv1cRwN*l?$`=Z|4Qdt{ zmu8#y5cB*AeeLlFvOM2!V6=vVF>A89<Cf+{CPIL;wm7aF3!79tP^49lOej_(-y03~ z=9id@U&Kj#0{P(le9Ps<rK7!#%_<o=NuVq%3Wj*pX2@>_`?2e~%7%uj)>a~9O!6t` zLxkW)e06Y-{#YGg3kO)v5Xn$$f+Jw^w>9wQIZ@T(_ruey$2Ws2oq(BtNXuzv@aA%G zZ$GF1Q33Q~uo6jTh9R{RD}Libqkk=UX8Pua|9Eke>jvL_igG(HFBn#w0xn^t8pTL7 z+RgqUy!t1+a^!rug9eRotG@>4$NL)_4!13K@HzWwJ8g9r`u)$(Cljcy4=2V88c`<J zRdN{M1`xG{^8<@8_8Q2xy0WK|?|W}qVNEGqXO0JsWOh*}$24C1JPWu2J|yCHLWhIW z6B3%0MR#+@162Wxmi{xftmojcTa9_=)`N4PRnnDcRH_qni#+f18tPur^Tn|Bnyyqn z(?nyvptGpf)~vtQ0r+7W86L>Asyz!k20Su>m5<cB+)<{drOpVheHtL}iYFI~>smDi ztg)GHAFp*|+zEuM$C_;3YQ3kMts+Z;!J;vWii+CNLhRgG$KNkK$CmAvvPpDXl9Zkc zZsrt{X();0-tLgDJtc8jv%@k1($Cp%@?i>9Gvpw6ug3$&W#=6LHyM*utTHCQinQvw z8A$Jcw_aBodC?<UWW$$-<yu0}9T>>@Ri;M6ztiw^`K42Jg!!6oE&6qqV*#bMhD$Yk zmM<}<u0e<mA&*2|T@l=Y(7qX784rE~qKqZAA<ukFMkF)X{&X@>ES5S<N|KYCJB-0o zx%j}d5eucC5R8UDlt?j@&1+p<(>p+-54#<^?FY;)u33b<3}EA|#89*jkS^WouaGzd zzkB{z0tO{l1#YYp!eZM1@=_3|I$vq`0icfgPx_mlVU8u??<#r!XJIu#-{+o2XEP;H ztXLRR`2~sX*3U-Q6iWoE5tKJ=*dhV3o6pSI9YsVCsc_)oz8bA<T-G(?wCKPo71p0Y z{$xc|k3@1&;2qkdfAGrFT~S6R?dGwAG7Wz6cWK%?mw9nEwx8`J#Ke}?-ntA74BW?) z|Na|REY;zP)Ed6e=lsb_b$#^+Idsab6~`R@By*S$sqlLB*o>4=s08S3Xn?Rdn+!(( zcs-%i-sH+9dvscc<|c9b!Ta*s!nRX9(&JTSm|VQQIoLki-QO3Y*_01K94g-!IpDDy zEy2S%Pnx3Z6IZ|?vbWbNEniWcBk%}Z$;_ylh$X^Dz}!r{bJQ%)S#*qZn-Rtx?VD`P zOtWjXX;(;+IH%+9oA2_z;xi}X-u*H3eGoP-&T2C2NG<_gueF217<a=c2?|EX$p3$0 zBjBmgw9w_#iow*_({nQ3z|@Xbir*%Qd0A6uS%Gv#W3x#m_rH@uQ#w)ZzZTdW9aLD+ z1AZa$3+iwnTMvY!7`OCs1989XFLn*59>(8<xwvBL>RgVFj#^6^zwSu3?d0Bc2_}Qu z3aO<`0PDQ(-`Bf)!i2=dCuE=Hr^9;DI#?}7Ou-ZWdrX~2eiQKAZZ4p$aE&^H>KFSJ zwJ&Ze9N+5TAJjlv5rWRfm9Xf1IU;_Ic-XXox&tte)%`5#v2GWnTVzoL-!bH2{6U~S zSAZQ@p1GJbpjicA<d@($?K||F`XL|*6FYC1vMlbi)Y-hr;+c^dfVwa~YSF%G+_R^R z#;vOO)D-in%Xdz1vb%sEd?v*;ho_MH^<+?du|g=%B$~{X`^pPvj^c{NfMHq-z59ih zz)E<5C;6ZzJ*4xFYWAr-IS71puDLRi`nOq|tys!5`sooKE7tpeb+)9Pw<$#l_p=7d zv)9zv#QW6u*NHW0ERTPwRy<96tD>vg;6=XjA>iVq5V#}PTv2?HHPI1W0*D&_Cfd!- z&5Pl@z$@gd+Lcwb`n#)*6i(UbEA$BX%ab5j2r%K__72hk$9|wWC+$zrLX!6u#mK-Q z?BZZ{bbkJt;Z<V%gV>Px^Qvd?IHGP24mBt43O_w^ig;LaF$8Kz7}_{q8SjI3rQgNT z83n)czc1z3fRuT?k0YZn<qG9+{jeBlYm4vHe!|c*jL*Srb&lm4nTk8SjGB6AlQ~WU z$N)D-SLqF#%SoO}+FywpVR+9(;+NM{Mn?2{o3WX5%E^>a|Bnk$^(1kTP&?Ad10Ie6 zeOz`^9s?`xUcchVj_`&tbKzmU54qtq8d8ep6~{p~#vrv@Y4+}^CRi83aAwVozdykl zjb`iDyk*X*1L>yT^pWlLH<f$qbV|&7!+m!`I6>J8wC!gC{F(nn@8MC2sxjm;S}oh< zw#BL#nc%@&MUk@&mapfSkg6eugw}Y--vr81spOBs!<_1Q0K1_0tqc6h%}v}`<;QOQ zv01?xLam1P1gh?a#<W7B|KAJU-9JoYjNuwe`5kxSdK6I42Rx(E*?ANOcsf&vcw5T@ z5oT2OpFr_*B3-}_SN}f(Vz8Z~TZT11zO1qsMCm#uM{{(-*xKE<UmP?gH-=vVY=~;8 zgMIq^N(igu?>DekCy}De&xr_UJc6po7*ZML8cafK75cU?7CU{|Il@ox6`4)}C!-=B zzS-_Iqw`P7CxG3X!;Dl)tIX7I0g=*&X7p@{*;eS_l<`51J78ud9Y*4Dob_CBQ$hI_ z8j*2;^CSK1?EMX?Vqtl@X=1EAmj@bJt?jZCv(0-MhS~UgPW|m&k~PK@?><S&;DjY+ z&x!PI?6un_%Shmz)c?$G45jhbZG~>dpws$=lu=8g)0;PVfoFa-eLi{KC<0=b%<dyh z>b9BJSGg2l2H)FL0Y7^$kBGH=_|c*|6-9XjzOG+k(Vi-~?4zlrCD_7ZYjJ7GP1#Oq zEDQ`~-z46A|NT9{KEIv&FFk{NHk9DoCn0{R5YI>6iD$c)xz-2=2^C_Z+bGTZt>p_^ z4|;IKi_l`^z`rTRR}pf_C?u(`shu(2zG&At8^SIw<UxFd`T3o~;+2DC6&hfFjj~}? z@&k_LIIp~Ip5a@kl^`Fg;N(4}Yi}0zXEz28`%j3~4=_}{cOiDZS+Ekfw%VI}N5k4W zW#R*7f|hFqQw{0`N`_|G8^unP9QP1Y8tGfdUH>fp9^OYQ6qP_1v4u7<Jm`m<0PZaA zl*EtO?Q9xrhI*%ohU-^JKQK`rS2urBMrK+64{Cgq;L@_@Di3E=kjZW+&>|1Gvhz4E zrI1a57?+8toP`tVr;reA@;Ql%i~I!q5wJ8eG(p{ypNaTSe4vH^&pDF4O^L{_tWb^7 z^y!g+f{=njPSvX!s2bptxz%TBxUU)+0^Q)rUuqnEeKbNY+bG`}v68n9v4L+y_(CHa zAoK6U0{(YITOCUHgG?2gJZ#ZND^96$9P*3e?wU`1WQor(r`n&8aa*vnTgWDG`RWIj z82Kks%($o#fQZAr>mE-eY&xj&CFnA}3aA`uc9cX&sErRYWE0oFzY85YMbbJ8G*u_j z?;Q-)hEp>NF<F|A=FeV=HxYrL15}ilvWN(82182-Q0DpXtZegqtlTNn(J>BGFZDl; z)Y)tAx(#}O>xxNWN{+%x)sCR4Ocj8pFB>SGL`yT)1^_=xqr(H?6chl@qY;+bQu7rL zJ4bIObq9F3x}v>%_j_@5HQ~5gCAyH&?MJ!)D?O1oPM}Vf0@OL5Td#E%LuOSnV43LG z{Em0mf)fBAmFc`y5_m*O>yz^;-B%P3tr0?XkH}~jR0kK-ACS9Sm4}~Bj>sQA7)dd+ zXDO@D)XGjpPLO4Hqeqo^<hSRpw#LqMRAAMCs3kVWej`+z3kZl*dWk-Yn9eY)^LlK= zsiIvX=*{3tkBjmPlCethFa2-~E%d_+ZO&PXwHrU`wPOc5CM5cF-&eGrYNGl5K2C}K zd!6PVEQyV@Hr3r(^Mi8a(OfxEOx4&2G2t11I9qm6>4!?7C@j0t<ne3&pf+y@CX`8u z*<9W6?e&*eZAyee+oadu8Ucwy&-{Gm<>lq_)a;_~#Kakq`(K0mM*y4-NCZLR;^Wsu z`1m}p{0ov$7Pl-?22c>6&2}CoHQx_7Ho-H=e2Z|EjoRnYHHV8|$4TyPGK#uzxVlGK zdiA!&znCfgJ1qwUm)6C0zTN}nVTA<$8>4FApFu>d8*hSOG-<Fowg3H?xbg}okAO(i z9Nq>YLkHi^iYuID_HSM>mnn<4@7Toty4jt^0@g+qV{;#2{N4R|s(gYJY|_+}*yHU% zamn8}|98s*fMQIV+b^zaEx+bE>&lSI<ZivW(b<w-jO*r$QicJsCYHFfhD9n5BE7fk znpqPd-At-4-n@ow(UD0ojT;q$X3+&LI30{N0lrvm&{M2eVxsEu3XuCZHuBO%<loEz zamh0-v&rRuy?Rm+o?^K~ayFp^cA%wEPyFX(vo$-3hf@A0rWPC_!?+e4ed!0-o?r8R zUf>f^P`)J@-UxM0F`vSjXomv|zhSFb)=PR0h|NGW91VanR{AmkjGn+?j8cD|V$A9j zPfMFgbMG<y2i%~i%szf%)8iLphE*dBL5JGg<5l8sLgT4@Y6!+ErAMN48(*t^gj{lJ z{}<c=lTnz@&ajI%@HH!e<bVa%m&LzzrW(ZIT=(nyBK|-tEzz6PnXm8#>@V&T$Ls!O zEp&Jbx{BNh`R*Xm^KF?X^v0{{X>e}9vEb3}u7s-Br!<_M!J3iJ`gX-fhJdL2kvD(~ z=l}uQA@{&Q@`_P6;AYU?GgOhM{{Wg&+(D{c6}*B01LD0BiRtZ+Q<crY;uwTyb8Tbz zFhvw}zKnGoOi-qt-OkAA0?rJM5lG&MdK`LZW6n#o)Z>QII2nGOg>lM$@G;`}@!{Mz z>(sA?s2{Q-65Ms{i%RAi@3o-CCV?f15YqAS`X?0{UPyj0O7a?`254H1;W-`s7eSI_ zs7C5+;h2+`V!xqrhAOe|reSt^s)=8Q<%0^gD;zkVI@>0fEwX9eW#Ivj^8z=N^du=k zEE-Uhn>4DR<ZF3HPhC69&Ui@#927wQ@apfC)4#+x2y^9b+%!(NcSj(wrmO4K!CY1P z<YZqW1vyE(z#}oxT?bAHKpSQkuu9S*Ut;QT9vwiGOB~-cY8J1!a`Z!umg3arw-qtw zVcL?$rwM*T{VFFbvnTe=@3xZmg!p!p%<dTpN;S6ix+<F6_2cAjxM_x!E$EL9T$~9k z8TQ}MOTMiKNDKL#(PGqNF8$LCJa|96)jazR`?M+^HYiJA%T}nIvd)o!VI2<zJh(%o z`TP9eD}evzWqW7y9Lz2UCo#Q4b^nmO7Bp13y=8D&o|A*A5jv|QKtn1nUx@}^O-%k0 zgq!&MVqEcInLwbw=NqPGRkW9%GSq%q#4#-(7kGQEp>rG(i~17=barYO7`#b7{v3ym z;I*ZpGB8N!?&)a=Fp)kMY+#G}{$(TqOr5mhX0)`>$B8T(kuifS&atnT{=YLIM)9zt z=!<$08;h@tteRbcVQ>{^rtBrU^kH(AeZ1#4-4@OL<XjUzgSLgF88sm|&wj@v<=Z8C z8Xz9NK7D@xvvXPwRt~F5$>oMoC39nPrer(0@D7I(94Y#rOD$Uol{>;wCnqZ0`)Vy) zo#F#h#Q$D0_~=>;EqL8f)<Rki0|OmE3wSgGwBW@R`On^ED@jS|yqEt2aFbD(<e1SS zdVhZHZv|(vdc36me91w!%Phrt@qA2tF7=M~_oa2LN~I^u*PJaV@{B3c3o9zn5FYF- z?fviff!%=#MvF+vbD@UajdTI816khm2{ygFeVzNs;*&ud7Aew6>4&PW!xqL@FO?6R zmKzZ<kI7NHbl_>!(Of4CfBjj~{eAiPIQs@5F^RkR$GS%f$f-b&Z;JXwb(G@lP&pDz zGt$$3zNAWVyB$`>_~I4;J0EEb%W1jsIDkDFx2nheki>3>5d`;p&_iV1PwpO&KH^|^ zz@n6H8P!M5Rm1<~&i|PdR&ulI9@?2uLq6)z^~lQEk#zC-BFrPQ5T!W6*HkJgA%(=t zEDCP+KTMy=bvn$7$eIA-3C$dMnzE=Us<Ec#Dg!8d`>D{Q6*^nPPzQbkN_I>>e%_Iu zH*bUl1zXo$ZroI~xC8pm0UN6f4lS*8^zrg+3mvh-;0pyRNkjZ)yrY;4-NJHf{wnR` zevQ1FDedPfQW!^fY?J?HG^@H?Nup{8pqhAK#1VCfb9#f&LlJbLAU^m8PKav9-+@!F z$HzY)3NomRPM8|wZpVDOF^1$amc?(TtW#CikLSjmqLfkr*N6N+oDrUefR8UreZPP~ zuo<H&`ts9#t>Bzyz3-$wFJJt?Qs~Jc+57YVT%y5K)j43~>U^w0bm3=flPe(0S_$YB z1@^yz1`ilbnu$_h<jlb~PV!&U%d_>XfJ#(M*udQ}0&3*l1zQG89(Pndw6t8=7~T^a z^n8NX0c}FBbTe71<Gdx|ENIhxD+Usq5_W5z`V#BT*QK=)h>wv<gJC~#=Rz=Bp1K7< z=*K-KagB2Ogb(vg>H(%#^6S)!pA0oFSs?3?DHJD#J@Yyo>xhMae3$Q@41=4Ec^T0{ zvPApy#L=+3D<ZmI=K_Me|BPII!L(nZpyj?-r8ThDC}&qAlY$|^n=~A-d;Bg%@{BSQ zV3YUv_a~olP*c(+{b_2{YC*w!dp06>%j^Mr-I8p8sVb}k&il_Twfza;Ao<M%q5>fK z<Jg??)Ol{KeV{v~r>Ci{#pTEh6(qyfgm2bj1A)HT*0&0C1(!(`0IjZpD99;p=lwfO z3ur+!&q(HWDy;_rol<SDB;QCSC}Co2{ggBJdo1{z87-L5|GKNRe!L*gPT@usYwu@R z|AkDF;rhV(mmW|1)}#2$r%IEQX5&W5{7s$?=S0W8sFuxyLM&?`tN#udxEj7WZ?cUR zh9)jMt2@3E$EB>yofqXFuN-*O*Xt1XESDNhin+PD>Ay*p>Pe4k++SJNkki%zvXmE5 zm=v>JtE&dUI8T_+;`Z{}uVdp8$7!@=<oxcGf!Ff@Nk|fT&S#f8t0|KK^kj|dS>VrQ zV9w0&X3LHFY0K3YQ8+t(1ih5v#0RO1)b7v){1z936Xrzd_N8)Ei6cSt9Kmrn`SmDy z=5_K*{jcXtLx4(q004JHZl{x0Ayxv;6NoaqmNRcLiRP?>enKub;X3X<jSmQt=*y@F z&!EUI&uPsFpUCcM=7X>hZ;f-M|F_U6dN*Z*yy2{TCco(B91f?07I;&>=p|{1NhI<5 zsy!vbWS>VaPh<`b=8R;klTyfj3aG8@TCQ(Ivtu&`S|P_k)oj*cC;?A!PXp98A3*h$ zfb#KSbX4)>%fCubUwAdJWf<&(&;T-yrO!J(br*Dlf@}s4?@2uW3s;>?Lpa?NcL84B z*yf-!WZ#t>@nBJ|t@9WpA~PqhIvOmKWV$`bX+%SHe}+R8;S>8J{EO>hojgS{>CXam zm9X1Q{I%;9rP<A|s+~m5kSpGL8;eQ_Ff|f=%N{N8XbHzOo5cE@AIu*CTKgZbif05+ zKgIbP#H#s{vfE*<lk0){cZ0NITv)L=9y0K+NoU2O%4$fQab6SgEABZhxX~apUteO? z6Mt=C;l;_NC7QZ17Q}p|N&W!`Llcvzi-WllfRLV;7@ug8O%RhktOwku!)MR7P`S?B zi2T}V1dc(F+xR6!j*7Fd!!oBgL4o>f7gY}3up4(Tul0%p={B>QbMF+@K#*VqS!R<5 zb+)#MuzNUkk2;4U(TQy8?kX;gaLFA+R|zFP7yeW|6y+#F5wH@U@)phod&nD?ZP}30 z_}c+_(RA6$1RlJ^G=0L+|F13;3%+{4pq_;D&L6n)hf@6<B60m}ZidQ4frxBQK3F;` z8}hUG{;VG)-yhsz*4b;Zg4o6}>+>ox&V1>TObFlxyDgt=^K1>hv+mOvl2#8NA5TyM zvTs1$7Jni>LOOAt{2Z!*4hj*!uW`c|Ye}fvgooCT9G2=3^Sfi0&SRRj8LxmN29@lC z#DuY|cGI_0-K?G)i2hT_BSUoi5-0n_Pbar#6T2_7f;hkEgh1|AtNYD}SG9y3{G~>- zSdf?MPA1mkgx4DMZre!cc#~$QmG!f?qCQ&2iSrnrD6p<#sIten{Xg8-cqM<z0n)mk z;mt}SG{Ab5s8&p}%5S#g^bF$^x%wh{abn(Tlb13#v4L4HpW}4(ir?S)x~<Z`dN4aQ zU#0%UQs?UI-ORQ&p=XM;kx|ZEreXI;AYg{F<61S*Rb5eG`9o6-Ta$V7<?0#EiZ^^D z{B<mc)6DtP*h5Ru$w%~pz7zC_{DRj!9K$={F3Xh|2^KPOF>miLInFT{yG1IxGuvAC zjh`Y*FUE&1sg%o<)D3X!JL<|?L|V1y4=*G`W7{d_<}jN!qMmLryibdC#w2udbR%## zZqI4`gu+Sq>M2NuUZvav4C((aw1(_;h1>r57Iml{he7HW!+x98i2q~itHYvRpSPE8 z>6Vo4P`X)41d(nKM3C<8T)I@GLmH%|I~D=y?vn0a`u%Xe$Mbvl@4dKocqZ?ex#xkg z1f>uA`Q{PuuldYK=;Tzr^LZ=Xd3`JQ&H8h=m^aEMj*hRJgoH=N$JsX#o8lA5A#CeD zPz#$+9u<|@lA)oYE{>MPh4<@x=0LaM*BE{%m{wxnTUpbwKq#>*@Mj?xE_yM<I2)oW zSxc;YZ?Oky-L#{We7{DL7{po>B)w;X(T=(aEudl9?@cTx@*W6h1rwKJBjFHw?+?61 zUX$^w*9C>zC~E$~;or&4(C48QU$s)P9QA3bY9M;NPvUHk*0Qlr!f{!)%38{vmzeAv zf&0H)wOi4tN2}P$<7>d7uE)Gbi|5fLLPtP~i#*zRV{UV}Q@=@Ig!{fX@aP+n$*HNs zLm>o@U$j7J_=Ir&PaNN<!0Jz+&Ai+8YGq|=7tdn0gfQpaCW+4P2VkE&g7*C4qCe%8 zkE)K2&IEC`KoUH#`X=agX6fT2N^X+(0v%3;CLRL<$2jEDf~nCnG3wzBbBf*D$n+%% zIWhGGRqSZWqZGtIaoW30go6&epfiz-O+yW8-3@^ZLxhKE9;+j{OBda(rHan=Bh(-0 zvCcoV-!fK4DxPNam@hd~hKl>9FSxs~4Qcp=ha>GG7bB4XjnMy|8~#rXGP(phFt~n_ z@Nh0ly$Gh*B1<;Ww?UwH&u(}+-;mqPl^6WYVFld(q72s$fqNl1KPAF#3j=9?zV7kR zpy_J+_wUM_b`P2@%?L2DTL502owSeWRJk52u+VYE?yP+JbVR&5kx_*Sxa;YTYj`ah zA+TpY+33!^goDt5pl3Ldf8}EUR7?hvhVtWfF9y=;=~~<dqHl*#W8P4hpQWAekIc|c zkdxMLX%b$EHS^mH!_@oJ)PhU1K7o!+MX&NfcDl<kKAAUW%|{f(uho3Mw8`aG_?Gr2 z5t-+c)8E4XC#@7@AYD6J>D>z^0xcWLnQxQtc~YxhhlMf97l!AiZUO2Y$CGP9GitOX z^QCkI26fBERRA}@Z)Kzk>~#9rI9j3$XL@KpY5L+K{W}8s&IQ##6+r5+W{|GN`zXn$ z7!45FlaP^30TbZ#H=47+P>>_h=J;F+8J|3<b72ICsa+nC$vFE75d4dG?btGyR(VM6 z;%G_Pe-Yw<sh)%U1A88_zguS}@>6G>RTP5M-!~(i0JFTdUfao82JaSzMEHM2kgg+v z7#0E$vOvH=9^p0*LE!vpbfMPjYc6PXccdl0H7M?b%@ZlfzljORT@=11PGF;ULTkVE zV+95FK7~sd-P)VlDHciwovRO<Nl*68j4|~-SD@~V&`fvEu=k@-b{SS%7J7(@g*)QB zo5+u_Ua0LeneWfZ%`>!}$?F_kTwWm~-{b+4>rs6fWx%j5VBc!MxeKO<85~v$TnR#= zc<cyt*kfz628!4nr*axbeQtL6So$3)F0syoPm~EUGVVTQhRJ*y9wClHD&9&uN9*b0 zV#K=Bp^TWr>tC-M`DUbc`?LGjNT@vTS-G#5muRPL4v8g9UhJe*MuJSTbdU2X4?)rx z|J>C0pQy3zQZ(qOm|5@_;fY2q?pfO3$Tcfplmyk6ceR?gCO>5%Y8?zrcBSkTzgVgc z8_+{wi&p48-r4?JS1tBe+uN&6C^yscN-IPp5w6U52DxUhhh+Gd%YaB_VNsa$G+HCz z7>otnWHJwjh9dJx>15%cMuFyCqj!{mDaA`^IY-;9_fkyXl7IwmEU*;pje^QDOIzR? z+C7woBY_CtV<%o;9jszd9cUo+^>Jfa@H@)7fMr?N<Mofh`nw!uxHT6Y5jE<D_tYwd zun0!`RF_hKuqw&wk0>HwlK(y^^&-s9hjOWKpjY43m+|=LN;_A%{9?y0b?a76!!#%- zU$+(;(CDgQ_(ex--{{W-JJ3#jYQjBTt4R3eqMc9s?w$p%Zf@V3O4OvLB_f=N1&Krz zyvR(S+&Iu`5U@Xv8yXy}90dwVh4OI;U}BoFjYop!TSi6?<Drl0<GzvGMk`67^O*_w z^5ON)O1lq@J5BpnpLIZQfgWYg7+70Fq<%w&{kdRmMH5os74roBfG5weA){@JJNv_) zogo_*md4KfL%x4uNCes@Jb$}VRpqOe*=}Zl#N%HvyR%gw=+wIdf{InWkIm6GfxEAb ziZEmv$f_)n6>7)t$EWKi|3#NVl~gt>2bn(y%6B(npn+xVEi6#~s;t;zrkrvtkX2ig z=yN_fCQ?)1P42AXeMTwN>trXS!^YW#h2KzZ2GInU<8zJvfc@L+qmxIm<85D?+peSS zOdmh38y(BU`d$jAjxc1Z4rb@;7XiA;@I8g__;TjF4sl<}R7)~`?O4ksMtf&IT#ok? zBtoN~zoa9NPrEqt3wT^F@7eORp>I8#*IK!}GNie<_>w#z%d*R#Z08m_mT>*9@7DT> zboJlI1u1*QHRgP*Vh8!}d8ImfxDAqW#A$HJS0OWtMN?Ip0bl&gOt77hh%zFElkv|` zyJ7up1HeM~aZ?+Iw;-SjqH@>p>oeXAyu_1R+M9YNZ(v~1XS%-SVQz?<eaj6{SM0u; zF%OSI1webjUUq!zkNhpLgmpe<@x$&Qj?j1PupxqGdkfw2$6sz2jZMCghH%o%^OHU) zZk-b%oeoCZxET!oY&5QgPryb7UC5T#*{wcx{{4Jm41v_+q4Ms#gHjvcJo4jQ`4 zR9lW*aoL;aJ|VV?-z(E*RXGY|6?yzG*^>GiSTeLT#Nw)yHk=oISWImiyv8bWTPEKB z0F(`?`RWyDztGlSxJbskpJ0IAC@Zh+m}iWZ#XJL2Uqu<2Ke3avC+2sCm%Lx#M>7Ld z;pgkIN{WlQM%rW<7z=<1T?%aMV)z=h9?W6`E;+}l9RENDnq|zc9<aH&spr0^Pf3DW z3iS{UiB$KlWV@iR={^`DZri$1GxAgwKfd4cH+7mlRe*2TrFP9DF0RphKuhzY{NqAJ zp6c4EhFb^>@Fn0~gkP#_dYyf8q+}wf^V|F6R>hnam(GZ)a~Y&PK1kf48t&(N-%x*` z#rgRIJ_?&ZY7SpA|9>wIP)@IRUi^4Se!D=oBfDv)iG6ZUnrTOb#HP}_!21-MLf{P? zP4Ku2loopz$brR3==N&YT-(P%c7T2S>N6hu7rZ^yg>xP$^<`I#pYKgg5y;4P%`Du( zy}iA}1j`>^S5-aTWJjDfU_4;c-s{eUfBA|Jz=U-;PQp9gH@>hF80Vmumk|{D)d0O` z@XYB%+yhixB%lCW>1Ie~Hw}YxjfX)A-qDjSGf_Z&LvUXIxAJfIlME@k*NY}H#v19` zZa?|cOS0imxn7BeHBtIeCJUJcv+Z5O={VTx<L1}m=`Ee<>bpuNX=^~bQ-#+$J&?~W z{wh3>6`iHERld@@X5+%N=QsbB&Fm%h{d0X&bVr`m{0tvp7yWo$4AhL>Nq2<YJ(BqT zz#y_no89sv!0|eooNW4_7s%7mai(qj+E6))CAoLa*0D1IXvFBW+5P}}RA2Xl?ydm0 zBG`8^ZH^46JgzV_aRVnaS4t9JL*i$gCbt&GJ7Y`Plfz-L;#Bc_QO2R@0frvFqJ+D3 z@p08;4Z{w#xlD(<KL*A>BK+R+q8YuAy8dJz0cvkqUi=>Z3pYzFsWdmd6I-vxLv&E! zl(>y8DSeq9eXFxf^Zle$wygnO+W(h{d<}dkOR**u=B~7Qt<M+x`BjH#%802nA%)91 zG0@so%}~iwRQ@d$sAA>QydOFe|3dEgd?>x~u_tNbro6!}i8h`?FxuV)?w!rTP;ms% zoc~*4fZwT4Y@RsmV*sLFFjutvNGBdNn-m18ulay+!a)v>mhq@YUKUAwZAavuz3aDY zvz+pm@|R94>qPi88rKP5D7e13Q|v=yeRxb0k>Rp*<uANN+PuYT{I9&Pk_G$`$swiR z&cy4d+O85@W-hk?LbXQp!b0IQBra&XJE!YOpw9;4f74Akj?hZ7)w`w5m2`pZ7r%$g zk->P0^)<IX8s-C=z|*T{*khmzI(Q?V)Um9qwj*o)z~3yE`r$>nTtY?p7ZG0`o0{^B zjjRj~92uv!Zh~=pbNW)&mKWy$Gaw!LP+37|3wg$Z{D>ISOdJ^nS*yRZ08+o0^@Fkt z%ZjDc)LxLACSOFB=yHgOIp7YAH$g9^IK=|OE@N(9urK)5wBPeC#ADT$m*g7}aG}+o zBFwB!r(8BgNW3K6kOa^Xp#8DX_U+{ag5I-jU|y*#y8F1Bnsw{W&2_i_YMQf4Ny`SO zgh=)cPcXYR+n`I#evYA^EnK#q*njH%E4dqWL`yB)hKz3Chn}tq9rcz%9;pc)^Ze!i znu_LkPud+5TgrNL(9?jf)ZGB$8D97AFJ8O$xjpo~Y%mbw<y~Jdo=|Y3A=Xw+QKg+b zZfRC@U}}!eLG|%z;Q@SIaY@PcM}Q$j96^&1UeXI#@Gjfn<1fb7Bz0&=eWBKSQsn3P zdiZ|(-rZu@V&$vl>!u=jz^%~+d|{cd^M;?*_q(B6{{EIi^^1V*7dp6au|=8}g2)}j zt!?CneQD5JYsxBkS<YhCij7)Uhw;fE6F8Fi58Jv-Q6yXGhZhYhS1x%1|5sUkKvS_c zoQGN(lzgF$meOtb(Uu7Rl%;K;AvONVg-dWMO04-~t{kWLT&?MffswHi*pR$gi{$*2 zt-|COV8BIJz_n)PocP(Bvd-MVfMV*00V}Wyl&N3Xa`vnVh}^#{2T(q<*s#Ob)YV~x zcqvA~7l*(Uj%)om99m^hekFFzU7|eZP{EQYWHNCZ^FM~9V0fn+=<}@?6t=Age3zhG zgT@NP*O9Bh2b3mYy&=2PV<MeyakqGVwCLMjMC=rb9GrHqK&~tjV{8qL1^B%$QM6X8 zFoeJWzpIMCv^As?<|N|#h7+#yJ%G0V8@Q|JP{}M=*VD&~9FWiAN<N_qIC|VccIg4R z&Cm-39HD|QUj`S{+D><c_1Yq*fwDgTV)l(4DvNx+4CT*`mh|$PN8!gTOKP0c1^NHv zd+|#{L)(h?-l1w3xJCHoHPf%3DG{z?cm7#Fei9NA;`TI{f4A#yFWy5l`tjVvCqtP~ zZM@q3%A9I)+WY1`0YglFpRn@V;50U&s31E~yttc5l0M_i{b`q1<TFlB<zG6_Tl<u; zl<d~@C&nS+!_7KRL=iaa=GY2+&P*s=f29IuspK@?y_niMYmt<IDg}MM0?8vw#j9LZ zVKjbg2ZpUwzXA?x$ljkqTz7x=_HJ=l<Ti~`*tPTn+N$=k0`5ez-abge%#8l2SSTpa zV_{`gyhH#-w5wPGvpxh#-RNiID6sB3ySOQM+x&qB=SfrJ5JFg`p6%hkvIO$wuRprx zV6Aq$6tSY%?gf6kWdMP;bu)9>9|cnYq3OVOBNo=whK7A;V6%>6IF$jF2$Yv2iNlU3 z$0k&gqa2hLMhRbsJ&o@D@0H@r0wgLvRV=m~Ys4m`^7LaWUt{~%^Lz~s3cPX$zV!JO zkXrGQ8+q_@XfV2`WMn{N3fy)(g2G<9T1ICF9VU1E^s6;UO-<pd_f4<)`7<VcUmNIC zOkejIT%{Q+O`^FhHY3&4{mf}Bj)->A6hd8k&K(#+d+OV(HtqyF-tsHe0$#`XBgf+V z%;aA)-oa@ALo%KKg!ScAU8L~I;qqzDkkaoDiUaf<P1fR7&o?2~J6&!@wUn{m+gN}| zNQE$N%3*pWiG|H)_V~2__exb+4Xx-Z<%FpGCcJ*t=yBF<x6haJ4?l9j0fk_$evvVL z9B(u?yj8Usv!VA6NEU#bA0A$fP0Yxfck+VSYOxl>yIf;(Pz}=4ZGcKvz<oOo7+W6| zO~R@2EQ=oj$B~QcYM>$lir3iGMAvNVh|r~a6*F#3YWL~x{E)k4wVbNwGDt2?+bc9s z63&S~IE^+C{3SJb8$G0b%}=ye9BZEbO8(cZ(Ms;LFPv@52Y{1PG)b}kAsnT&5QKMq z4bC>P=msXG{<S8@THGUAMg}hAkv~?szZDL55c%B@wbk_c;D8X5Yn>g$A-Jxc%1(TU z_`UsPy|>b8+SbQ*+7{@Bq@qeQ;}~>bM5C%-<Q{edynQ74ZHE6e4st9y)@S&E%1Gz2 z1i#R%-}r^g*Zuu%2@MU6(Tlk04*K298L8>|hx((AMb9Nh%FfH6^&%_Vg;#jamar6@ zsu8qJqz2!0IFJk+ZD4qx$KA&Its@-0yKVeNO=lm($<FU;BPTBRE?eHZf_xZ%*XbTv zJ^3F#@_))2Hf-x}R#E)=VWIH3QKMPq;|~u#0Uz^^p7f6WN$+Ctw_f8JZS~|NCMM1_ zx-?M=z03`f3OEdoTzW`Abs2Y2c5p5!-nOu7`(%GF1T5pdZRHpF3hWazH(Akjlb_^G zH|`d*0L@YP2Tz5%tGs>UBfmnV1<zZe7GUugu6OG`=0-o+@#3*N$AG~eRS*sR3rqyx z??&KcO{=X=Zc#AQ<V3jrPCy5_YnuMpuEm-CVRtb}u^D3mO6*5iKB-Yi1gf7NqDesj z*gyV#st<x$mWzoaanfI|do_aGl%5sWO-^g{dL2K3DplVDl_b6fj>zyAy-smr_ugrT zi;9Zbm3SokWNDd$YWa>>kdbqgvQ0}zC;XMw%?C?M^sr}GJ0ja83aHHER^N&Dv^BQU z_FOWprk_E$8JuiHMlTZ6NS}ru&itOnN$qL(YbFwwC)uvbXE}q@gy5~VaFfwNd;(zv znb+c8@eW)nxm!u6>MsV~!_a+i*M8RDFKR*R0z%=rPPi_fHKJq0|7z3mmq)yKBKiJT zq(A$s#h%F%)-U*$aI)cgEva9SC@lMS$t>>N0$-9(mP9eA`rx2hv_&(;^3mM<WT8y- zX5Xpl9JX)$u7Xl5gQ<}5`Z6hD_$^pk8UYz)S`l#VK8*Sj-0}>;rRN@K3D!iPKG{m` z)B5IEF$;>8cG4TJF$?p%9L<R41N(RRVs6GFqSP}A>Asn{<%DmRa2;P0OHe1EgOEVT z=vv(Gdk-BJ9qc<PvKl_X;I~+4%uT$B*hzwt>I`e2xwTA3I^}^Nup*j!;=m{zeqUvW zCswNe$@XiOv4L^DgnE?P_{(|;-KFbPB|Op7J3Unxt_b$HoTtvirUi?AeazO2jRx4y zMG8ZtXaxDZ*&-I38zbP0Wtt^Of?_T&Q=f3Y3l|p|8>=X0Jg{1gBB~CWwiRx&HHo^0 zMtDGg@2YGp{Wqg-LFYL-YLGfcMe+ZPO6~|HW)MlZa2+w-WeO4;mlWN(WA{ULNI~D= z?k+FPP0e5NYcD7o#l-RuQ^H{{Z_oa=iN8sYA0C8Tsw<z+xJC9?766@S_zo{pb>Z(t zqi`Bl%7D1UPTUuI|8VHJdjCYKx`7U48>MTA4Mk4xVfq>lEA5gZEoY?Z-{c4M!a9qN zJ=oCmDlFrP6^aXsiaOdQ+5p2@FoBoUGb8|lnboX4fY!HM5(i1y|G<NrDx-*Fim2~1 z{^SW#3Be7~IEujtYP*H<dIEbKh#xi`_k`rVxBEY3#EoMeQmc?;!qolxZmTm}<$Yf0 zJVSVy%#fC{(6Tf!9u@o8oB7s9V`6ZXA%jZlJ?DRqgQ_z{AT<pDHI@mJlF)B54hJ{S zBy9AlfD?qM%)(3~^yY4$l+r>zHOGZW7xRxX@2@gi8qbo=U0hxHUUXy0sAp?`rd{lL zVZB~EHRbg%2*ny3Tfo#%x@p%<^-yvkr}-eGzf8T<L9u<fD+NHc<Yq-GN4|v#kdh^* zTOyw=EkAgp)aRc*4%Kf>9p!%v42>I)I>5>FS6I3Ykh?5N|JE12jwa~k1QsxUTGBj; z)u)fX_#$t+3{g05(qsqaiTr;VAQCl*#b-`jP3CRK{dCDEobEbL@Nq<pCxm3P;0bMf z@^{s**>Yb&!*fdq(OqN~rb{*6C@HP?71Zu1a#D;)WvkE)VHv6AdVRd<yZ9pM=9W}y zRHq3fx{0;1=`LqJK&%)bEs3bD<vTxjKI{DX`79z=SFa>ux#j*{%lgTdT7iB^PoKa# zFW)}1lrnGGSuA9I1ODN<(nk#P@iwkHI+y+sl+}nQesfHomt8i-iT52G$9m%VE<xAb zTI{bc2#zz0fuDKh{nCdXR1@cNN?T$~oy+fU__G!XRLBi9yH#tS@*g4ErR!h$oyu1t zKH`7!5Kt<8ddC6AoJyK|Oy-jY%oQR=zA4&{YDiXoJ~BD-v?4%q<a6RsjBbi)t-_Z9 zw7+-(V**%YSA!ii8Av)NCLEftF4;Y&V>7Tdf|R3J;pJCSO8OVagV|p1vsYNQF#iOR zt;YO7@u5vilCEN7K)nJWrdr>X3k%EAOLE~mPXuIt_v|wAIwF0)|NL5TDIy~5aklA< zX`t*z?0k7y%%#LCW6NV(^2H1`4H|hbHEHlPuX37yg~L)64POMD_*Ug}WX4+4>O1R^ z>gg(c`-vIDVc!6Hi#H}wlGHR3Bv#fhikga>@(y<!HY=^R%T_a%Z%vPQ7aKJecgu=f zU5>8S<z37}oGxd_uMd`?eSOz|MBzvze9GE55Ibx#xV}oC+_Va5J$J{3Kp>}TxY%%u z6AwwyTcbYA`qpwT1}}!(jSa#ykyp;eRaNlG$@<A1E|Dk-huX+~LF?oqc7^4B6^+H{ zFTQ_otZ^2^%^f(C05_D@3xqth8lH%7ez!3Zu0jw6>Fa9u7-V{@8c}3o>!x*64FE@6 z(~*$Ow;{IYyFq)VtXY9}Vou7H&17Cl(<F=MxTv5G{$)3Q+r4sp2^tnYUy+o$uz=u> z2ISD5B;c1meJr$8(puJdHdz*oGD)2=w(r8iX%}8zEV{i6UvwC?$(IL%KbwD(OtLM` z%KXvTI&2eU!++E~I6S=mYgCegl5~=~%St5fbM1QCk0ZhYRc2=w*Vl4hsU)T(3$kFr z;WNw|Pp>JYEnD^B(Ww+8?VePzYa1UIYf99rvPftuYz85mVV7E8LaByu!cdQ;{qgp` zn&W+uBVL+gp8r}ra4coX_ifk=pN>AVL8=VD1@8oOORBrnPVRrd9s*%vWJc_jH4o~e z1f?ahu_Xvxq3Bxbcc>5{(9-tnVUFZ2>_oL~-WEv?D{+g61O{}N3JD8O6SodfE<8); z$9mKRXlvTawRZP*pV<*nQ;746yam^oNqZ_hXk5@FcpG#hZyg>SB_$*zfJJ5X7A3mp z!tD!KZdXLH#q)wplW=TJDQos5aX5IEUR%4!fcaf*^1Jq|eczMDQc}3Son`z^VflPb zM(L&JAkvI4tc>z*cbGCR3Q9LCE3xp{6UjNih5NtHs1mVad$xb-axBA@Trcsf-&thM z!wrv}tkl5et|PG#<IJY?gm6H;a1oq8O;?j95)2Hm3V2v<PmJvFHa1t`?TuTl*=??u zE=svR7<Qc`fuZ`tXCosjep<kk&FB4D{MJm5yPz%KI6>}9FEDtTFBqGrV1CP2ds*%v zs2qLyN8<(11Hu|&XO9ka(mAs3Y8Z8{e-$s)mBk8o-0^r5CFc5(MI_SSA#>8=rwFc% z>GEJu<HPLwu)d00HvF;2^{6s|gw{}CxI3}Q9>X7_W!(_*`{Ts~%s(zRuTrgO|M$sR zU>t3^G*<dai`uH5Ms5%_c-CE2O1JLLY&Rfho$!{Re6I{+0HNR!cv>TFi6mE14e|Z5 zaMb()b1wJ&dY~I`DRTVUq@;`|sFDZ4k+k$e_ja`E@H#`(>k0RNI>QW<m1g&EYL7l5 z@8jXxXkXPgievr?q3gZC+n82EdVRV7-u^HqoqU+m6fTMcF*V^4>gS{Tcz0bbxff~w zrP<OEF9uRuc~ts7{ko@%7)QyA%+S9E0cnJ=!5XeEkJ<bF#Unf|at<E-yDOhMrm&5~ ze|3>*nmKUCSK-apjMs(O!zW|+`$G@O(`QRn%u(<;72yWz$D7l2)CadGfzp6cxshZk zHW|iA@^4QdNO-bG0}P$dDM)}NzmTYywvX3Xw#gNF_q#Kdr9XZM&P>n00Ho51b^7R^ z2H`S}fs|D~7(HqmK&PlpZL>;C32v_r7P$nHY}$$H5IDTbFtU+Bcb7)br^LNhn+Lw` zA#`{~!NBQ`@G%y*d&+PxqeJotpOcY98-(?vsmvuq^>A$rm{9lb&He5NEvz_*9ZZG1 zf@G<obmD;h|L-F>p!^DYgr*3PvxWHyc`+{paNd!7C)Qb_7v~aaC1vGRs*9K|u(E*w z*)pGG%Lvs=L1}^gIz8o4Za$635PFq6z{*-{+DpB7aHMRGxIjcmm|gwdKuB2V!&?Uj z_tGFx18f~8NKZT0{D8fi%)~_uih@L*)wlqM2?=j*J$ufYOD_oaGHonSKrma<8W#KQ z`GO1V49{2S{ef^%sUDFi7HEtsklNI8bX@FZ_Zz92;WQqBB-e_QuNNB!v3@t23qEp* zOdvwj`SYygktnZMe}(&8jVC-8(YQ7Gdq_)mv&t`iJTXL7suRpXB`^|5%{7mbV?g|5 zdzgUjX;s5%kbN9ga^A;5IvDyrWMY5(Ee5CtCXvxGhvr%Xv^_jXJ-xhgvs)ijKISjD zXW2U2hC}#@AJ<)?22wB-J`8CvrI3*W+M13!G+4UDyGJ{h;<;R3IKPDgz36E3;P5yF zSEC@78Cgk#^+Z9=7k{$5h)v(c;@Pmv*8BjdRBJg95BG|C<$NDp@P16&A4tb3O#3Kn zivhpzpO0e(*6*LO_s3%XgEc&24hr|PGFOtNnX!NF1EiQ}4h`cv^lU##a4|D2NJIic zkvs{70dJo;>-4>sZ+m=cMyX)D-ra#jF6P;GXQ#>jE#^?;iBp_++BLuLn`myJh3IE* z=a>2U%NP2Xrs7T#;8gh0tw=q%Mqx2gFfBIF2?>6fcYE(39zd;KzIfJpW<>JVeuYRN z3HVy-9$i;cf#LjtkaGh;+On*=-YlY?ySz~Y+gsRo8`zNz<P2cM)i#0PxkhtHKNGFn ziNP2w+?QqH2#E{#LZX8#$@)(f{(ZO4XZy0ApFpGcB+H8f;&;1wAHGgdGpU&x<=+uC zy*kgI{z+%3Ndy8Sff^7AL=GouMo+Ny8yt}s4LxMurjw0LPHG^VEpCs-m{B~7aoJq9 zRxKiEY!b=?IIcv7gN|;wpuv8mOiJL?Y0**B5Qab}MMXt><43Wgvf{?g#$cDBDOJ$f z*?{|Shk3xpWTA(q+i6s|7)jYzWZrGO1C`~2@B&T?l5gbt&Y{fc7Ga^59a17lt=9u~ zU@xZzF#fUap0t*j&kO}0SmdknUk|z1KDYtmqw;4m2Cqn;M0aiRilv?yD1!)*;cRVw z$SRr^bw>s;VSsRPHwtJe;aTb*GB7$*lGA(gu03pQZDsY?x^i0J*htq=u@K&ocK<x# zZlRo<oGdIY{aktCke;62v}@Oc5E#zn$4nrLILqNyDNGZR8D3s%YiaprVyC8MOMYMW zPvy+qO9INQ2&3Em>YLN;JQ#5fO3DQaub3Qo+QXrdVts!NsZfI6w}s_l`iwZo9|n%@ zdpYI&9RcCPFoaSBo9H75c1+%MqIOlI7)L7I*-0YGW5VMb{I8Be9Fw~@!_-aAL~y(> zC(&-{#O%7g5JGzB9j~Wv_ud=VO;(XN=XJH)($eO5cVRZFj{s){0RqRUq}b<^*Vjn= z7QZOd$eW1~!+7MKBX3rUfdhm;^JJbLFZTnscajDxFK>Bq=p)X%3^x_<!dJNtchO7j zX_Vu9Rp$NqdCni~gHcPf@%_R?VtJCZ$|30{2oI-6Mx&gVF`!+!W!(C0OG>dEn-&p+ zp@51<f)9OIc$-qkvjMA7{(ag=iZz6H=Qr+i)KsBN5hbrrP>%e9NN|%BWa>jG{*CAF zC{^mD@v<&sQ_o0AQZ)Szd9YQo@j<)mEq05<P39k}Ih=gs0P7<}a4xF2_2YOk4mipf z3h`{lw^%!;{jZ_s38Z@K9gQ`FThv0WW@ctUS{<Jcg-S!exdb#ozjYhYvIGm!l9V&< zEx3d1)Jzec?JqMDZfumMy2V+NxsG)sgBk@4L~c*(A9j<BoEiHgd6?n-%is9R*Hr&x zTKHU_N`R6fEL2us6~V>Bk2$e%p`a%?u0rsIlYfV@HLLwf+@7;vvBh0#@lVdPe|3{~ z?h6>s=+&EAlXXtQx7crvSK`tmIoP2#qLZ$Iegxk!lvVI?-?g%=(PRZ4J{D0SJCVKs z`t2P63&GP3gqD^;S9DWSXI|dMvCAhnQc+xt_ubUAvA!M=bS#41dK3oNf;mRte|19| zj@jU9UG_e!tUN-rrw6F@5`h2D6pFBqFCxxGr_*~nEJ&Cl#sKVOSae-ev{%)M1qAcw z{+*>*Ge~!7XE9<I&C%TEbt$#q2xfz1-0RInAj5ZLIM*(PIY>4#q<wlksN3&dbmK!K zSj8f1q7BoV`S;;)HxSknK6D`MN_pS)VJn}t<4^};FU}&r;?wMc1e9MsWOn1X;sC~n zi@dEGaP^28xDE7_Fn~C{x^|5Eaci@tq*@KYhfOlgW9?ayI)-OstQ;J;pTgYx_qYJ- zP-9giSw;}`cMjYQesUOT3Drx_g{d*%I05o|&9hW(za};a-}x|t`bo*-fsT?<Bi=wa z>F<1)zdN6>Nxc~^uFWtKdZC5vrbDIHclb=-6Om4xAucbDg`Yb?yjeA`5ZFOnm8Tnq zoa|7!B_Fvq_JT6h2)LJ60ljN-|N70E`S4Ju_{)YB*p7!NA5X8TwEvC!7P*lA5UQ}9 z4K?Z2XTVBNBUfptBch2rB{+>geM0Mfn>NC0K2&^kyB8=$O5Nzv>-Bw|nHKOW5_Wd6 z6O)sY;Fa5l#v{CUlrh5wwfY*tj{smUBlx71z%)hzdwZtKnX(JD!AFl=8r!8mtjm;R zoD}3PlJyW9xm-Rc6RyfmCveRmMd?MX4Klp3ySL%=Ccq=S5H(zMRHl(bZreRQePz1} zHEr`Iwq#M0zQlL+rne+kX3??(UgMw7fhT$@YWw172ng2c7HZwiVRxjez`f*Zms+Su zw5qBo@e0dGM*_$!#ZR8G5nh65zS93j_OpZu)Mtu_afcHddFn6%?e+t=oZ%78w4mr% z^WzL|WMCv}Y<`@bkZ|KYkpXSL5gxMt-2P^U`N-ttiHaW(2fu!`*0!s#T_SB2Rlspq zLFI@V+-qt*&%tO%Z%iV?7?b*}k+cP|=-nNmHgJiHzS|o%1lPaSCixu6)bt90ZU>5C z#4|4g(?1?>!E#?&;yBUhbY!AE4sve%o1fI|g~OvGAOu7hWZn0fzkSiHC4qDh<W|#g zZMohb0ZIsk^v(m1`?(HCyh21JAV{=@EK!v$V$0JN2o_P)>B{TBlbwF{#$=9!gve0V zv*#42BF{q+4#0?Bm-~{yP6p6P7yE!&!kH7eT?omltwpX|b}gBhoTB`L+n4?<R|>c@ zvv!~9L!@n3Eveml6zD*&i$#U~djs+LsOwe5!sGaMiqpwy*u%9H0cug@YSuTVxD1QP zi1)P0`u=jh2ZmaA`VwWVNvq$Y@Q?or<sk`<)1=A?EEn<6t*qHyTB&4qZabe66DHgy zx}3*s%wVTX%V40*5$QqY&-uobYIXWbgS@b*z8<p9sJ#7D_0)d-NHon(lGgKRSOV~P z1>Ig=Dr%USk^C8WlLBtqnTwsQ)HXUoeyylDvb@X)^aM<z-lsPu9=wNfb_d>?q{c=L zj1;v470g8M+qW{AZpnB-M?HQ)9SvY%jZtKUHwOrWD`R<P-h1cjml$Hc4)}}q2x}1u zveE5bNA*|~N@jfgq2Oef?}$x!19xx!%GLBW_3R{SQD(=j?IOY_{R#zr^Num0uKOV+ zg=fLXJTZ8*AsjnkeEi?{a%R7muhemY^UCx97BD%f1asE$6Zb;#FsbLm&)y?A0*pwx z1x<>oMe0-Ql!!+keUl)z99W4$EFz}XE9U!nmm&a?Su2fld6XD&dWuzUJ_q&W!|c_7 zH6lZ3G1FD4RNA$AI>%TjVI}4{P*u1?Nw9O`-b_V~OGiU7j?(&U2bx)^{#*bu9Z{~; zd`Ql&s>pfu?X1vWqayUTKvq3oh)1I!Nk@pH+lpoy#_;bxBn|0-!(N{6SqF+4q;R-K zu-2Y*V?ZExpI*O})u%LJw`X!F$S%IV9X@>M)TUX7mw32^EdBlc6?JWIf%F&K<~-S5 zg=!dMbg<r#-yJjH$com~(8qw?w&{Wh;0E>M@@?S}a4Wc8)ldFLThAm8D^}rFsXY5c z^*GQK!D?ljL;vQdBACB=$R#y!*7xn4VaD2OlN{9D-l9NOCH(jA$Kyyl2@f6aZ}36? zrW}PhV1BfR@ny=&t7m~;sA-h_ejP))yS<e2bxTf<hLlvav@G&6B8cGBbE=+D#v%q3 z{MBQrfSw-u=i&}hd%L?Mi<9&+GKTw2$(hqw%ipa?hRhJ>p+VW?WV=+Q#l_vnzY00n z+3924YO@xo-IE}-B@a<%{gWSBNFSrh`6TLUY7l|Zt@qG{-&P`e?V>h}oI=>GQau^i zO;rOK-R4FaBg4<dl0;@r_H!}JXCaPu#XQV^X92RXF(gE$lQizc<v3(@Fd(%*x}F8! zlCT`tE_pWJFFkvwG|v}!fbg#)d}oO9(eEj^zr|FV6YQ(8tM*lSz;M-7pYf7|f{KBQ z50o~88*GSRuzDN-?pWZrQXx**a<#`XflL5?peH5#{@v8pe3j{jhVt9MN)<WDhz-v9 z^JYVR{iuvXj-CB&oZ&M*DsrIawD8({J6Y;dAg^9<Q!EeEbl<-pj6C>w;deBU8|*c^ zx<TLp>e#XU-AnsXg#GURTd~LCN{E&C4eh*OPO9%cZKEz6Dn|_G&hGxk9~QJ6o1Kam zwFcR-;_lOX*5s6}l7H>$dhqc0B0p$&rXa#X7Xnmh_BU|#`wbAhX76K0Pnxt$z*oTc zU^aqNxn%J=ekKRJKcNr=8N0Y(ZE@<iPn_4dy14*!COwTuJQ8k^x3J36l#b>8e)N6z zy~LuOot?hEqB-kK#+(C6KgB753To3bsZkZJu**xnS&I`XdnNOMG^KeZfRNpXd2RDu z_uzNths(ZkPitq6TJ|q`XM`VzH#}$?8?@~AS=3ifwm7IUv&{J+wJpc9RhQZPmuqFh z<T8^X5v-{we>45N0$53ThKipn^Vbn+6aFcW;M2QvIVXR33Bvq*%*WjavG;+*fL5ww zj?m8qAIXtY^P}&+0s4aoV?;zm-0u6qwY4w5=jG|B7ELt%nEMoY1FKvo6)(%!$}Xy` zEX!$rzP^s%=zQ(Cb_QfsbB473|CBTrxe%-cc4lUvSFiVtTT7#QD*B||Ywm>CqRYCA za7auY6C4ndr_sFSM=@9!6@<d@RWKf6JGK$Yl(uBp8;czi6dzxsw!z6{mFa$!j`O90 zJ)CC;@2~2$KEZtDcU@T+&<mSDY$O439VUX2nFgYcF1y_TM!xXaRZ($3D2dQ8e+yGr zR@a97VfxH@Vp-W<`#;<M%F0SU%x9u=#ZEQXCv2>&(r@3^)x6{vS6BZqP4}d3D51-i z2pc}pL_+QvVL*$Z>tD|YHa?V{b`;6Vm_Ah2EZb{}lHBYXepqw>GN|WBt8>5huv+E7 z{MpE^7%y^!&PLTto5enD34uUj?plm<sr^VfDxl&|T++yY<#@Qg%Jh(R@R%ILPiFeg zlITScYQNR9o%Yx-e1$=cIYdvJ6W9YX$SJA+>R&M^R#p2ITBKI6?6VI;Gtkv-+&$t2 z*?0kY5#|2QVZv^4vDI_oUoJ@~v{hrR*a3rVhDKVEdUk@;(a~6LJ>}I_dWbZshDkLP z(MIm)*{$#iq3B$76@jrnN0Zw=(f2`7y@1!2H+gmrD`M_(6k4BSXw0Vl>Yb*Y`#$ro z0OiOT{}^6_ik32#{O|9lR8i_0ZZ;}*jlTpU+z2OTR6Vh2qI|QPiUbm3xJM^;TP21D zAw39`Y32`spc5cChu0>Ti-8f7I0m1<T~W7(=KS$b{F<X+S9t)0G^O6w#3mx_>FKcm zPGt|pJY(kIP=0=7ojH6-hJYA8HNRcOMa#s_-m%o;Gd4R*lhM19w&<k#eU^tCzHl(> zme@!*yS^E^F8z5towD9vo;>e1R*unxwA{meTXr5r>sKcx3E2-#XFuPAGTWM08WH8Y zbNHrqWA@%ag!$)FvxkNmg_@((On}p|wuZj+pf!99s`RfX4|C->#>ZY-b)8WqS-qpi z#U*4w-o~@>qMASk){25-qM}yAI9p2rasxktVf18=u9Sc*y%z#yC+omgL%>po?I%lX zk<SPBCHKfd7!aQFc=tuKN6!pNMJL{;^mW6`EZiz=dgSm^2dMs1k*lpH;t}=-4H<^J z;hD~cj@#sthJJjojz4<oQ0n_h5hK+KCX?fD0QYd_br_7k@YQAQ1{waD-QUXBRUC-C z@Gg($j6S}Ht4FM5xgP#ZX<-l1O^u^t>Xg5q@dR-IBCr7>9Dr~Ga81LQXypsWpRitF zyDW30rzh{2*B?uNp2<C0(q`IizxqT38w=|K8(<}q_wW$pL!TgwFD=J?$KzB6!TO_) zWLaEdKM-&~wy;2VV#RRAxxqy!;p5dxtpZ1Rz3VV(rd)=*ako*z;T4if=I6X(QuBj^ zmtX{oxB~W4ip{Ca3zp6A`u#`c#Lx4cnHbmp3yQxU*@HS|{R9rT@CLTnCQ=H-n$wjy zcAB!dyG}h%<L>%9T=W-W*w}z9bWgJQQ*Td|VOCST4Ott@^LPR~owkPe=2Eac`!P|Y zQ8suAZLEf*@BV>u7blqyY<{eHEHzSZN5kinvMC|Lio>ZF6GXi#-0U)eR+%Ep7hSg& zuAoDXVorK(r1E2p%8L4kSl_K+uf*OkrUDfA)w_a~og~JWzir9%7r^{dAlOL{S=l@L zj^!t}rNYh8(u#JA;a_q0uf+g`A67oOD5(9>`!wp|;Yv9W;Mo6)O{KCDu!IaGZjq_4 z-ZW8!c(_9#g<JqMZ4stG!b9_3c5yZSUGw=VZhBe@K!oPDNd294vAxo*WBA0BT%^3X zxU;q8UR6yk@j`gkHxhD@+^!|_E<S8CpJBms0FIfHwM+Jbgm?Rpc9(~ucroYB$w>5L z^;T#RPB@cWxzUxJKNV&a{Z^01{g@^Jm#MxNHH60m^&cDIPeOZ1(aKnHfC_>&EBt3A zx3kWLAcEe|j~51h_i0|D-a+Us{;0=Z;%;G!6Ikft+Vz~2|GY{rfF9*gY=<^dt2DU; z1(b_*-)9#4*x1-$NlTkAiE?unEgGb&YHEJ0K5QhPJLz@y2{irY@qB%FURN(SzY)Fb z#rMXls)S##zV)}Cb?V?=X-ryJS$$bsTLb$L`#pbDY${khoeT@W>b&V5H#hmh9E<%< z`N|DZk`sS8Gd*1CTM%4h%_}4}!>@rM<mh)(fVGtSLx@|mQ$pKK;pqO2lKuGTAow%^ z(Ska^T?M*YU4m87U@69SFFUKA#d15m5Gi%z?m>JW3815eP5{7eHs+7x(Q=)}uj>67 z6%0L3s7D$Ula5bE;ac1sw8uYXCOg-eWPNkMbP2lW4ZIrozl_u)qqkiuhb<yf4LCxY zn2~YFCBU!ex@)cD^u=ptKQMx~-`#zCp3%kZu&RWq1ICi0f8-~HdoI%U^5wI_d8Zg3 z(zz6PWC%l0E1|oW9l{*>KzH{*77HS!x;5#aKYvrR(L+X+=j17)dXLBR?O!x*bD$5| zo%ujP;U(?N+BZlg8wmq&Ty*TCcw9gdwQ4NgKPiFZLq^Sz7YGPK!u(fiC&RoI2SUgZ zsULnXzLA!`4|-ayHZ;s|F!XrFlnL$gR63fM8Ac!G1s2$#Hg!w1grw8ZpN3YL?#oz& z1@}qVRBgAgzCXESdlEU%%cl?MMYvv;Xe;+>MV;K_{a`j`>7zCPWqMyx)cO!h#&wa> z+R8OWl{Wn~dS|syu=3wKk4*iV_ptjNXV`3qTD9kGK`R1V`H$s>$TRWlw|ubP>*yz^ zQS^oY{v8@GM~Oe&0+4K00QKqTuCGZ+4r|@4v2CZj3I>Kcl|F{EBJD{X-}P9(yv_zn z9ih2-`Y*3-Qk0T<GhEH&B&;)<qD?*`!Q-}H`AlePnLa-F0KTl7`78Vi>+!;<f+(L5 zIno95w~$1p-tZ>POmU&c(IzmzX8QtdOjbqmQ`IGxSi$+XK>K{V#w*ZjDUi8ca#WQ* zm-U+avbyyK$NgBtVSgfO>0##xl%zHN$c4a#Q2+{gM7)Yw;IPeOzFWF|;2-@RZ00MJ zrV1!03;3y4Xt4X}O2o@KWNGdtoRXTFTgcSt9OOR=n>wutF~xNAE-7YtXK2WPkDn+c z%9{v_`X>SF^{u8h%vm6lX3gRoNKX$A@BbnHvP?Nob$fSLKZ!f(w8@zS_2EWXT7F+~ zs5sh!_}pMW@8<Vx15>)KNFowr-wre-tnhgQIbZC<fUthY`i;@wlv1Cu@>&vqVIE8- z+iZWRLZDKaC;?rhhRrh$Z+o@6lekWEfX}24iLE2l`yb&6#Fz2X{ZPg36TRLU#8*)z zYUASC8C018psQ4;um!l`&8zsL<IbM<&jp3D#(8<EP;Y_zp|}c&kTIfYZj;`LGm)B_ zmx@4xaeua&(R+~uaB|=VgIeC+@jha24fhO5D@9)0mJLvl6Gp{#vXO3&pWkY!QXa-n z&MFU@IYJ*|s)#l*!J!rXxlnjy>R<WrpgbAaj@LXAZJIvgzcS5XAs)Zix-Kc67Z`SO z5<{0E!%5ZA(huI~ilrPydAt$ab`<K*V5zvmrXwosL(A!8l32ZdmSc|vAhXA*M?MA> z2Sn;VdcNw}@Tlv=fb;eToHtWaQ=KFcOVX@rwziH=4{Ldb_n(;)e4vq9btwFMsnKAI z7JcF=NA@!+e@Z_IhCe=Uep^EhD?Zk@Z;)Cf5n^fk`RbKGg<s}Netxu|M~v#B+o|!b zeatj82EAZ7UvN|RHY~v~S?Be~O8E~p)Q!p=51~WAxPMSp6)i|?{=Xu?KmylnD7sdy zCZM(z9g&iN@7U4Tfl&OhsNnp2EEX;IBmQq*Pbl)G<6)&gy2_ommHYDc(c^)^VIKAN zJV-mpU?vk;zXotG?`QzrmAZceE}^k9-a&8Fs$TflLY^XQ729Y6NY{Xeirn(R99oQV zigS1)L+AaYtn3n~jwU<eN4Z;^cT{0wqqacH;kGO$pxq4v?#T~Y*d_J%N4RVxZ#2ct zQLU`Uw(T-(F6_S+c-QMF@p;cDDS)@SYz?_wZ%&sKZW;UjH#-Osy-QX0Utdv!f#~oh zqGm9SoK7;NeK9_?aHS!D`@T{xL&o#4>OSzprms`e;p}<gA!n@J19290ks^WhZKPYx z>H~i*8VFYQ91i{qZ6Q1|)XaR7LmzM;-=3;fV$?vV?<-8g@_5_=ekZhsVvgzs1?FPy zD-8!EroZybJu<>#F8OwVv|F8pFrD`!S)P8m7EeT>#K_!O6vFM*4~(JcB=fHaom@P% zg^Y4r3t)`>?$n!6C))m<)&aMesBRt-d6Q}G9P&en`jrKg#=Vg#eFj>Sx{?=v&CH-9 z%r3}j62<rkR}#*}DctXLd%$zJAQOBuW_F7d&qT>v|27xTOjSe2Z$11pvC$8ypeYwM z^Cpifgpto;y8c?4Jf?&rL#zIl2uP1!ejK6icYqIo2Ic6-*~TeoQEM9-LRlH#iUEJ% zS{}d{2?|tyJ2y<4Mk`g}mps8JBS1@de4Ll_%^T&`fZj~k#Qq4!r-?}i2Zu{frWcVf zH`>G>=Nz;;XwXmB8#!_o$3AtO5pOO87l3t~b^OM^Vk+nKof~-!7^cE?A^G#7{8#rJ zVjOui3Q8LpZ0h5RIDL5Icj`23;&R9XT0g`^Y}#+2f}rTV-sjw+!U&>!6gzEO4!GPz z4`^%&h)$;=aPw0L<UtA8CZooD2RM<=uBlk2X%vNDcq+KV)}&GX>JB?&^v?x(vH(bU zdmkWZ_?|TwsDj~JTG{7-wgg;;t*l%vOG&ZRe@;1?mq$<OHn-_WYWOgHcMUU-j8wC* zvw9+O{0L=lpQ2v~lqY0iNMnN|c)U_1HqBh^cgsm@^6jEn58PARUt|ACik2ZD8qVca z1|<hw@>@jq8~0I)*uQOBoEbUvLS5wx{TtGRInr9L2wkh7gZI)23IgiZ6S=5}=ponv zC;@ACums;5MY-c;LxCo-@tu!XDDHdIkMeg5H@0Ct+LdG5f0n1`Ax1u1zLF$Stb2Ya zC%5~UZ=YoECW>P+LN-E&;Fgw^t*sq%0V@Ik^NUt-N%6w%JDhD<xa?%TIbMr%%U<t$ zZVioGRpxVNx4wmi=d!)fSLw<|<90X(!!G42B=MzZFN(#YxL3VeWs?td^-@M>W~eXk z3-78#h~#Gj7Gw00aJV6yw<IJf8h*CSVkJpY$Xl9VFu%^rj<VwSM1j--ZpRa)jWGrv z<v8nqhuhkZ(7>+h>T;@@1^B3r5Z1WG{+kDC`V_Z<2F$M4lalefmFKL^`B3@Sdq_9k zzKfex2a){dEM4Jzc&PXN)5I7sP@?axRGDQ9T5GtL0JY9V69t`CGlsNXue8+ahbvun z65s;=;@Ky6ONFR2s!jtHYjrdu1+Ljl-`sctqe8!cu?-U{BPvJ|X;v?Fi<RL1Y*1Q| zskVkj$muD1a!Se=0L+wj#7f$KxD)x%DqHhO&{=xXSZ@b*IhL_Sb8x%r6p#gsRHaiK zB)rb!`+?6iJfOs7Q~*z9>*WY)MW?(Uii=*r5@#Ykz>1}M_e}la-F>vN@<glqpWm2q zf`nwl_7XKnAxAz}7jP+|kS&H)QDUy4R>XfRf>BrWK&M0}ANUX@61v?6W?$ks*2Atf zL)?|IJ07vCpIYbQzE_0g-}ZcGWsOxOBa_%K;(v9QzQcnI-~T?auwro<ALDp|3EW2m zuwE>nz&_0@e|{e3(}b=XCE?Qp&>{iLdo_7^NE8P)cs_<at(-bW1xm>6mHtrcjzQYM z99nE(WmgrLL<LF=14BdQyHKG05+fSqwDamqm;K1zZorJ`a%=(<(9{HWNJ4ae@(yqZ zIb-}7g%HD2`3KNq1$0ogIgb)Dh~H#ETYIU+b5adX5G2#F>QtolA22kY3yR_^eMZ)c zo2?<ktSVstB(6G{=e|y%^xnCi7ArpI50UF%8>wLjcOQKGpudpo!(kuLV7tVX^4m=z zqucm{wWRp%PkdOA`LI-ZX?;VNaU{nO1ztiQCD?=$?Br*6^r^kP`HbjfwLdkOl-~Ug zsDrDF{W(T$Dg7I)lUE-uXv;E7SNVED6<?Lt@2)Yvefu`@&?;6`T)bef=!Lx90)^wM z_%yY;(lR!tdVY1$-`)KO14u^fwDt7nkF_J^Y3-9N)_F({Ut$%uYo&_vyNebw>gwvM z7-=!e$SgHF){UC>+o6XPraR+vt0+l#uiVWf7-kp*dcA<zTjPa797E88Yz`2MiaSw{ z&#$$S4S=P#Z%N!XN*Je=(?4h5K_ICqoajRTmAy5C69<+Aix@GRa5Cd6CxODh_>v>h z4N1O@v|S(Kh@IWd{@K(c8-TL*BRzZ$p)<vO9bv!y{jqZ+S{`BT$NWe%@E=G3GU1vM z6k}f!`|OAcr{~a_a5|n{4o*%}<Ku6@`Md0<CdCLfX5=l~o(j4bD*W?a0l;mpCQHj= zZXu!kGYpJlA1dfKumlI73%W>f4XrFu@-Ts4Y1%sPVupsEDfE=Nd}W8nF%!guZ|*?= zdG9q~kpC1Ir6QuqN%esXJKJzgSwxv=hbURx{7FUwL6u5-YY9x#L~Z&&;A6jqw&}}P z`kNp5F#bNju-r-m%DYf~qk}Sc=-@@k4N0>06sPwsf!O8wCzw;xfm`Q(p$@~XhQQ<7 zcY@*KL`jlbKHm39N0Me9{brVzS)j4qE(Ge1=9hqN(Q^USvsP?7-8I+mnEX|v@N$1d z<0xQU^yQO1{QOA>*h44#VY!oal_bNM^=$ZhuK-XQR98!HZV_|w2o+mdS-qdqH^sze zYq_+P=%F8~HDdz4(9)s=I9EQl@@d^N=C^yCMsNrqcr=DJM0am{Ht*-immvqJ0+mvq zF{U|lD7N-((V;e`1p>aFngCYaA+yJ7><%{`-SqP(*==J9l8&^~tjgaehz)<!2QpCi z;0RMx{%T}cq$$Qtv^nS6TVH#!UfE5PSqB??vzl*4YvR9{DI!p(h8bBwFxaqo12%SZ zk#y(c&%2kPc6@9xZ<6=#ffS-Y6zG?DyrLZ+G;)*7GC_Q5n27tqJ@tm`+Kh^eSr+AH zKDBP1^dToZRhzL465Z(oI8{}ZVe+?c6Ts#>iD_2<gsbyG6nNIjhAr<2rvg@GpXQ@B zE_4T85lY-|Fs$zrZPXrKueHlVgDG+vKD%de;4U`rO<#youeqj2GEBy1WJH&}3+FMD zo36HAFrsTjrn){cY?q%9Vamc=KsVtt_?zt5Y~j^`A`~M_+%JE9^EJ1J_q!QG(vLCk z$D)$2`6m8m23Mr_CcVC}g4x=>?8YBV>R@MA)WP_;NKOZfLd`PS7d@`{U5N=iyjd3j zm<H~uG(|O5wnwpQeRXg)R@vLz8(E$POx17-v!XBaedu7f01O$PN_1G-$tiJSLfzEa z`3-T>SG-<+0qky`&D%y>Te`1o<X;FkfO_e(I!h0N?6gWDfxp8+;9|;l@{9HV$J13u zMY(<Lp&O)8Bt$~#kdPV`1StV2$)S-3VdzHbPHCmPy9ShyE@_4#q&tTi_+IY4zwcdZ z{u9?Z`<%1m+0Wj)uU|&smQ0oS2!3v~Oel&OkYkZQ4f!?uh&X!)hiHe|Qskhu0izu~ zGZ#&8zddRm;O%Mti_Sf>&ogRZ4v$V2ROElisb5E%-0i}m5Rqtt7R!CjZ0PhIo1jDk z&ST~Ue&ji^Z#WRp*nMmSGO28Jhf{<Ng>qP}+Wk@v=BpWV<&NUo9*`1n^KhVm_?VIP z%541PrySm3_7Sc5^ZROA@Eq~|#&w7?6mQ^5f}7iw>pnG6zk^IQd&?M)YbZ;9=#DNL zM%`X0x@5=hl>78R$QfJAm_#Iu#!Hg^ZVf-QSx}61$0yYCRoh?t7T@malNp~%l;2Rc zopIIsRI@#0qvY2B=0+-w2{?)0(mYk~n|_Rsa~{2ins@A*ceXft_rh{>F(oA6{1Or; z{#8duvg2E|1pTMv8=W-qZjtyoUYJ0B(2uWPYPE$}J$3_lTzfy7=jH;%b)5GkT!q=4 zpmKANUnV0E5VD$Sjtj%yULT@}CJwbr!U?I*J|P{*Bzr-CUg1IV=+QuTh)ldd6(2_0 zgMaT-zwp?Nf=zETugGgdzpi7;mZx5iidkLk+4g!ySZ^fB{2!2Y%LH|jx6^tmh^QC9 zyOJUq`QMs^@>4vdg?v4lwM5F3eiwRo{WWLR!@~w`gO%!Nh<w$}*bPWf6X09)JbvHf zMLd?DNE>(JcJ!=xaE2QTTha&2-mjK^^>mJCTF8&>y&@y(Yx1O1O1TClHhz}YQ8{w8 zLHGx5M;Pvh><5&kZ;Til%Nk^g*~5NikZ53G3k@^RB)*)>m<{$1#ee@m?7LqWjw4DR zlOSrrn<<pVw#pw--^OdDmnBHAMa7ZYo;^D42&lQjnBd?5=>xI*6#Q%r4K2g;VkSLc z+Vr$SWe{eoZFKSCP-q=aNl6KDRAl7N;I7SzNN=E1igtra`PkB2IHbldo$$4Zl!T5> zD)7LiUmAlX^u4{z#dgD9NE3>yeUa+z6`4?|rJch@@;DL&guPnmxNIq4>%f(3UPh<N zy~7iw+aDfgGe9i!Z+NIyCw9$QB}x2u3gr00uG=h-FEg=~pJ<jCmoFZ2k4|9;g6xKS z2*~!EGd|t$J_!z?zSh9pQj0gSuj?c;V$#sh+KBjEc7bWu`_-<Of4({QvxuXIOaZkf z8VJGgShgQ|H2zgP-9WEXEhpKJqonHRGo#C}Fyr02v%cdHp=52lE=<ZSPoA(P)Hn}3 zQrE+pS(AuNb=Y9OKJX}VBL1RhtMAz_QD!|x>6QhPz~4Fy*1L#9G`<)K`hEM7Zu)1M z6paV3$iv<)VO;cyrB$tSh^7vV&Fa~;l-g0_K#?I7=bEtxD;ht=UXu;<@SIDk*4_+q zy?^sr3XfIW!jD_kh~$CbwRLiZUgwzqYg;=jX;;?<3QBjv^ZE1k4+$*O0Hje@C$9me zl#!8v0u`TLJQt5^HmUjri?z$O-vW%5xw*OA+FDcnm&Oj<`X?8JejNnKTO?6~Xgz)d zJE5P`DlBQ9zj=_y0T_EDQ!lxfO>cCk-eJ;3fBe4hiI~GF3_VjA-_J3yc}+S1q$=*e zJs(L5R?_rv#xFuN;w|YW_!<m;ayDngQ0-rOyb(m}bq8T?uXoWYIu2*D4QO<~&@h%s zaz}72{k$L>XENfiNdRe$OAfz>^c3~IEp;RoE}+D#EDT^m>!0i;Bg}l1_7zr36<&KD zk0(GjYaeLHUYb=t9RUllK@*j(h&4~(!ZJMU6n0)lEKEO*TUbpG4u6(hv1Um5AZBd% zaBheo<?_ReDGS^zTHP|9Yd7Oh{5RXH1#CIPJtn;Yr4B+r>tB3rs8j#ZTuTF<QVTx6 zB6EJBu>|$p$<5}(YDwp8f5+M1YIi{L@QYEC-4ESL2d>+@wt#(x;|C8Y-B4UR7|_WE zG#`NU@GUcC>|dawW_Y38?gQs{etN*4F^KZ^yf!m7KK>fo*C%|@p7lFh;j427z854` zp7KXs-P%8DNsB`Ppdhr#iWxr7ba#Jar1*!FEj!&zg~I$(l~(1@&(AK-vAQ#3Nez^* zO=63m|0-*nB!e8=^pf_Jrw{9qD*fx|)P|?b?7Il9mIWJ9L*71OH{kRcHy^CCpMytH zglWAW*}55Le@`@GV(LM9Lcnp+>m=|I`|!{2$Cc?a#!MFQ^!MftM6!!5^5&Yllg|_^ zISW~=dF>kA=1_h;=m2HigWSJOy29T^T@x*&lV@QrV&o<ZiTlS)-MPiHnu@9a>|EAl z+L=>82xIr8!gsj<tpfMZ+cb0`@^-=a_uc=v0P^deWCX*|1BgNAszp8sw_RMs=9+VR zKHzCs7BJA^w)yj^aMJ2fgYa_wt<G~Eo}gDohH)^S&JXo&X`R)*AbqC#k+jx=kGcx0 zrztfwS>Hx8_w4|k^!N4r_K~u&S>ILfeO7W3u)J=j>KhvyDJ*r26{>H6E(8E`Bd_qc zu9i%-1Y5HQ9HYaw?kv!sZ@O<v+C`eFzdKyZ=ui2pvnRZj+B!bGygepTx-)40X-ieU z;K~ZT2adWAvDA(-TZFqLasR#gYst@6%jUmw&NORbqVp&+yF1#b^1SC>W&qmmnOjnh zWTtf@^Qo)&U0E&zk3b=tSkl@YIetMAJl*I#ECUBB@56A0nr*Y6bY4cZJ+B&JQaH3# zA!L5~PFR&bMgoWnCiovItkP9@E}YEk6dxkMr>wN;;V+~m9NZ<xxGjBG;1SY@fN6V! zn2(4tHz5(>(vj8h7UpYrWlrqlnp35kGcimcueB695r2MZ(hDl|m}GI&^5ojzD(-A+ z5MGUHw<;=}A>U_3b3|?M5_lSAi2`PKZ2hbS)L!vXN9Sk95}&OVpkuVOXqeyWx|g!- zn1J2^K=1x`0>EMgU=B?L@<%_ZOM7%=BrrocAqSuy1AHZ6PM*#a##cf9{LV^PiZ%|3 z6_N&`!h52#KPS(nn-C@r;kxjiFyk5s%)u^bn%nmEwO^OS&n3IRBkfff_>L)Qf%#on zJ3S4D|7B77F<9F(T4wy<t5P){r>C4z=_x(P;gMwq*^TeXS~+M{74LRGB)#l;ACWE) z$Z68~IW$`Ce92%KZLR*|GMUp}zUO7_7-A<(=9JzT(YL_n5%@|WTWO$>dBA%2sEljU z?YzPFL;rw8nh2>ub>Z<Q=^lEj4bL}Q3E1{QS5pEJ|6%XdlhiyL=IRq1*we99X!!3b z3xv{$ekZks>|u8&DQ#`ZXdCeVe9yr~!WX}I?tglt>x4D!Dgsa+*bkd^O~M(yAVv{g z2JyV_Mv;3&7onkeipt8?7P2^iWz>$elXbO>Ujl$J{CjrqDmghYkK$KgV(*6{rrP>i zadj;%PhJCVA$EqN>4)hGT4ff}KQk1iG4EFYP*`Y&xD1?Gb9j5Ais_h3aEX<9{HghE zwVx;~5URIsMX{28Dt#cI<O$~V{Z~mOFsxHmEOm{hOA7Kv!N7cB1wr|7uSv3nLY@e@ z)OR-7aisEwr@a35T=214Z_tR*lI<==iX6pCXWH)z$+h~W1vBh^Q<--UXF&FSF8ftJ zp2ru{EJ@zlFNLKls=SzTO84ZJ2N)W0C@F<3W3KS|&M{JFiqk_rf0zlPnb|w4lq3i5 zt$2t{DJz;Tk9^2_np5$RWM%RKM}R8iE5RS*&K4`zW4(sMcd@%Lbdi@r!SN<e7lQ;A zXlQnp<>NRcFP3}l?0YbfE)>pqrhq~8pGNd~Xvc6pw>~sDbhG7(oUj-+_A-8hJV(lD zYd<7e*E~-vC)3+<r`OTd$*s@FrVf@p?N8)*xS=pDF)}zju-hWM(Q4<iuzDaYD41PT zr5eGv)88$#7Wlg9G_^kmJ?4eFf9w%Q*xKZ7h6_`FA94D-1Rs`fG!ifQ8zir>$E@ub zEB9GP=dT~BsAh&qKA0y{nDS2f*CGGJ_Q@H-@i@_(z<_W+<>J9nHb{nglctODm7hg) z#1=9-YL&;wjg(DhV~XS(d8f_M(!wG53$*B&VEYW^Lqy*N+%2h^2n_3V>R-$DI6K+2 z;4qoJ?O%tD?DkXeur_x(MPdc^!fFa|0~vfd?Dk3`&F>Tw_+kZorCSPzRN;;KKj4r~ z$X=`6l<;UtThvDok1-k|E#U_gwX%71G^TKY8dK;%zDM^ZMs?5Y98~~An{f8`V*0}p zbh8rjB156$tEjV2kC!l3n$F}bUnveZ+_QPIcj_xELy`?7ivc3~=H_NhHk18o`zx84 zO>=GIt+|ARgzps%vgYRIU|znLm%jmWqpiG&f98FqrMh6Of1*oe+TW<Ap*I=s`qJTP z-VjwFKCGY8e9pzSEcj*~;j4u~+WGaUTRJN<<a4``oH!L0_WO}fUSHYAh#E-i3(yOf zAa|eG7#F_&E9H>S)`#re7n=MSc5jzC49Vnp#HkT9SVElKWlOZmSrZkH={s|z$UD|1 zBOLii$G9o6H>~&xTpJ@_#?4YAa~*cckwy?@BI{R7Omjk63^Y9(II?~)cLRi{Cx_2| zIdLm0lembThu9TEr3&R$_$oH2gTUT5ti_&X<?37ow^jcLmH~vs&Qe}yeEgz8RY!Px z2RjmfMpf<@V+cEjya;*cH#A8}@7Xk^rKKVw00fe}zCr%F@o075-GHW0K}-ZY%1kr@ z=P$Y+9~ri)t8*=^tUiAo&){k8(>1bk&f=A<sHkoNP7w^HgjHK#nh*}VSH(2+1n7GY za}{*QUNO#9<96uo+XOV)4E+arGzkO&g>Zp%LD?T`FHp}Lp7Q#A?bh%*nGL^k4IWuN zk(G_ZSTXEn8ZLV<R$fk<Bg(%(#PK_*uxhZWQ)wWM0vmj;xiGHQ-5(tiQlA{scE?QL z&MOkYLpWmyhqRVa!cKXv4%LvrOpoB&tHTJiCA8Pd;2EV?AVl}lh0%wLg=j|rB_oA@ zMB&jIHYOSTy3bJ|FS@<}G&VVR_mrJ^`^SX?psuob`MgnpZxbG_(CBcKebvs;zH!}d zn{HfjbaB9m(4rwn2#9*L6%~;VDMgZDs+_cr4p)-%v3D#xO)M)M5t2zKOwd(!VeW(% z6rj~J)M}U!fVyV*HFY8|>~zJ}M_K*}7P9q7O@C2B)tHN2GKz4SaVs^5YTo*+^*upl z0pz+3oS+;uhZs3B{EkLLG<sd8ehjjTjezNuP9<)P<xC1}NkA5Jx*U=eK~TWwwRL4P z2=H<J^WNLX5EHmA{_eGkcbiHQ7v0xaV^iu>)`{bOZm)JF6P3(N8Rp>vpRavI0rYgU z=lX)l===WQF6a6>x23f;0gx%qEi8O?)WisieI24Z6Vx3bIxsL$X>Sixe6OSg%%}L% z6W#Pr&K0et7QWGa_I#n(6A`VsP5bm2kleG74Nged#T&uFn6b1FgW(rOA1Lb^+|iS+ zeI6ND<0o?ZwX}OmMk6MtJ15gP`1)Yqx-xn-T;#t;W5=)B5&Y%{FO!Pn2}>1bEH!J= zsgtkoW7yrUwxK)G=!*cjarR4!$ezv~kR|pO*_d4gqd!#F1Ksan-h&%AjQ#n~j$TBV z?zI)B3XP_Zv~=yBZGtpjNPwi<=q>Kj2={UhgrQ3oCK*BkpUi{Z3N$RevM-xiS_r}O z>5W8lk)rJZe7R<$;!freJdBp0U|C*1z8`S7zJO9>B$RLv-foiReqXR<^Qo|;xU_3? z^BXrOcTkqe(#9}f5B&inudt0<xcCcUK{`7dn??>@P0P%ub1Cf=08gHj#G-dSE?#ga zUV>cJuI|?Eo8`}q3PsMtby8c6qtAPOKv&kKdUNU5%l~^W{9aJu6@A83k`5>BClC?Q zAHL@#y@z1z-i24fG`p#1PFdS6oCYD)hv?}HEZK0b!6aJo;If?n<asXdVO7JDW`k2w z8H=DI9zgi4J)?7roXh3q)>@&vVdUce9tJRDgYSRW9@}T}2hHU6%{4DCiAW18>fPtD zBB}3h2lh2m==<nYK_9H7#9GAtbD@i|@rP><&)nQx<|8`nCw4<e5JdT`iSCCF0sH&h zDQPW#ghhp1tZZ!~acpp~{F{zAo6pY9K3Uo&0ooXTxe9$PHh-rP;?^iqPjmJqaMFr1 zK)T5rg&m)}Y!@j>4;G*#G6=P+{PJW5pCUjQv4{)t{&q;r@~>m7O6;IrLt(tJL@9Fm z*Am5p5Rd8{Q|PRmB7(9w)_@81!j&sA4;()ygt&-BN<64aaWavsSA;&tzN^UU@Na*F zXYxZ&Q-8`25Jn{3#b0i!&MY^CxXrh0s;xc&HMisCgB7~Avn$9Vlx@E$M~*_00=tKC zHM}YOKRx>70S(`>iEi}VAt`C+!UD_93DB4d=%@ue8Nh=#d9dOlWc~1UmZ0FIRAM3} zzmQNl0I7?=5_6%??qy+N0Wxjz)z#xl7>@4xqr*_&J)KP_6N0J^JtGH(v3;8MX2<+C z7iy}BvAO}mnOaH~&c^53fX48KqGNeo*o8BmYy1bOvB^}plor$9p3h5N5kTlVwinhm zhXzS7v;&-KFn5Bo*7#Vn^$p~TOAv~+hqtd3C^PReuJfvYhMy0702wc|DbR}oMx_Tx z2j2`zx=|f<8SiIqnpor?&M^2=AGGDY1)trvjE;TeZolGX8VhKB-19<2+BpzfNbq~| zZ$9<Wbl?Us&B^WZH)%#@%4LW3r9CF>^|Y+UvO7J{PBX88t=}|VBzjt8h5gitbcBZP zam`Rv=!QG6f3aF$gaHsfnItXfJHRc>(MJvfcTJWCImyUJIDz_tY#(*J>hyd*HxHSI z!g9JFfBwW?Mw|-=jYQHcrv2-8XP41>W1m!3;z6?6+CAxg5fbC3#=keB-*3<R9L!&p z-yM8?CNh2NcG`Ub4q<twBHd|yv|Jeg6d)wbOUHgA8BV8-Vsi|EM~jbsh@|#G`V^Hu z!(Ms|As`DqSp+Vc?G6Z}+M{Q><;iv{-(y{lC=cU#O#61j-iHWwmK+Q<G9r2<TE9~` zSM`Op<+N$E4FEt$Z4YQ(Gmrg%-Dlze4$kkTs@41Yag7jK%<k^MhYt%q>1@-*d^)Q* zczAv--bw;JZqkp$?ct7ElU=KWCiW4}XV7#UY*u=ufqHSd1f^?H6)mk`UE;?vS69tA zHHj8LU>NIuQ*rK=bK+8#6?x|>EUJ8|M)I7IzGox32J@_{oTY#7YRs&Y3UugT<eZtz zZEK6>L=cbg`i|G`xm!Y_dT#We_g4~>wc=uiDLqknk_a+fAc8vfRsZQu#bZ353^xJF z{tB|jJsEDfGig#W|1^LfVXl9s6d+xzad7mPhC)6zu}adkBbQs69d9NMVvdg~q8R|N zWgJbq^@rNcvKpHzDh)`oN(zu+iZsnY9QPo9h~<eFq_|cdGH36ZvuW?TY`->#&(6Ml zEO{ffx4ZkwS|J>Oit3FAfAc;f2{JWYh1RNS2M}pc-YZ;y4$>$ho=reNK<jf`XBs{< zz-K38_<8;AmQh3)S6WL0D3}G{inr|j1Jfv~fkSKX?QH*{Omq$1YNTY#?B(LFle-gf z_f)@$T6hW$T6zcT9OctdUeceVf6auS(3(!NH2;Y5Z1lL4y|y;eV^|F7T)!szSJ{y2 zi(xH%B=@6e`o8dj0vmwf^SiJSVFU}_7vZvJIm+$mdIngEyfQ>SvW<QzA;(!=)*qx( zaIwzml^>-4HMm=VU6QumWuVR{^((PNNJ+<nFmOY`Doe-wi$@#ajuGDqB@&+tgCb7l z*C@e|=hd&9xcP;tQ^EJK?)g-#mHp=R_I#P60Q%#RESMh<ngJs&-F0o10O~ZF%h6Kr z;PmF)$ZPS#mu~5RvjUJi2?)Yz=pT*&U9F_C;Y7XO+UOc5^}Ed=Jp{5QsnhLM0q_C= zPOdrxf?S&H=hgRYYD=<~JfXoExo3J*HrAg0{`-dlGoWbec`0WFkOC%Kqg;E&_58J( z+Nu<^t`0}|+WxP7##0f=x`f@)&tz$zsQ*M;;<h@dT&^@(dXmzT4^T)sXDHSxjRLJM z<SQM1X)$02kzf3W0==aettA*f+taKyHdF^)s35hv0?|bzU*v$D4qp-yDP!>3(KAPO znO7azF1`f6k#^Vf4uTrwyH)OIGI{NwkW02mXH0URcT&ra@wR~aO5Dp*;9bR$0!?3P zEsgmbiC@K5Yy+)1NPzAZX)~H5!TyY8_$0#MH_3qZuH6e*T40Q~%OB7xUz({RkJi%C zG6L$Y?<rP7Q8CjLg|aEO>gR;HN2|Jk+uvs9%@0sD<JHu(1LaoHn!d)p6@KQKa_3ot zg_u&;$|)<;5FZ)15_3lN`sN&eOL?fJQB~{w&|)NGVyuc!uT>;sGBFWqCOmNInOj|b z9E*W-o&$p^1Glth>gA;-va!ziSpX|l%G-nL1+q086fTM6IIq?2N?<qTm-)KGb#mK2 z%-~KjkL~4>j*xIHSAxAS|Eoi>Me_%!0fS90oR0>rFCHX6o*r)S-7jG~{lNp<-0w{5 zx)8)yCvc$(a|wFF)Q^z=gY!pv_A{zhx6v?b-?pe{n!Xta$HSVXou#q22>`9<+AwgD z(-OGkF-_Av70do3w;-5ArLyk<3e1ju-kwC=<+1QrDCS;<Wf7zoJ`{f}BN+GCFrb09 z5kO();Rx7EPHb*|bZ(A4(*o#9vS#vqp}t;~_Ho7Fk`&M^14xhn_7Et2|HuPriaTon zbs$mb9KTqt{i;L01KAQ=+p-U;2Dhm`@n#ou0|%2)@Z)~`_dp%F7DNKTCi|cp&u(>@ z&=JUAPLEo_U~n|Gfyh4v%VGzO7~tb8F&4zmV=)b`i>s~Y^PWWKP!-;AZq+C?{~^<2 zp^`1(k@q;1%oUKiY&_y_ef_#~^G|NRYEM?4Holbq_hLFrEr{nb(P7WwcMW;Yyo}Dv z)3_N>2InbfrpTN3Bt|%v_83seNwP8ZE3h{4c1jaaEjsCP5c?b&6cs*mai^oe?+B^1 zVrI&QD`2W1xMl_#+1STKmg1E&x)7N(6Ba%j_ZG$l(soJ22)I<AbT55k3dYLc{U#j7 ziuqkyQrzg^NJAbUKQ}RfQqi~F>s)dov}#>++1`E~<sTPEc8Wyyot_Tj^z`&H$Q4X1 z+hYP=)zadd@5P7SUxC2P+9MMnKIco_v(<Z|H|i2plU8@YBu9QIU`nfms7Q!F!3gu> zz`4lpFOSn(oJBJPKY5$EKLn=A^!)xEvgnJ@&21EM6}8dzeMPGKV#rT2TYs_~19!^( z(JJ<jm`{fNT>YCtb2wtEcg^KGAWPlmKN!+WC5{gx{^zkL4BZy;^0HSwDazPzGy5cS za5=%SG`?&0B|e$VoF-%scYRS|m#n9ggOt*b*IMK!{vppID(Au#Tm#wF%go@QB5g=| zLPW~l&IZVEZolcsucFGPIfbFp7pIr|$9hA1k?id+<)!*|tG?r9x_hW~jx^wzp<NCV zQ<V{($T1+|bCW0wWOx~78yX<zyR*M`o2KXA+s3^XJ~>;e`ClpsXmhf?ySv*wLM88D z*Kra-@aIewXi5*T+JJUIj)UcOHq|!<kV~SdqtQ`IiJK8{*UgRB%D0}H)t(x09H_iF zhI4)C!qMH-;URDP(M-c>0pjSK_Z`w|`VV($0$MI<o{Tj2sY2*xDvwbM|LJAUYHDi` z5yrkH!5q%ga2r$w;Bx@})P0f5{g=&^8>-kK>4h6HpL0Iipu7_Zxq0GXHrbut-B2~e zFG5uP>FY=!f|aRXDwK0Y2rV3_Q5m~CByX&1&<sfD#Ks2LwgtUQdcX@l+slI6J$*zA z8vFJpP8*79db@BdtGqG`@vT|(wwO?Y{pvoIm##HYhw7g%TzJj~NN#ZJ|5V^%m^`88 zo`a6ing&MR<wdw`3u2P>fOp*KMaAawDjI}IbH6=YXw0~~n=StA`ZS9O9SktL@2frm z3cHbm-Hk5^hJC|^UMQ}nrsm;_g6!#NGAtW`T2u>NT98Inzy5w|zVS>zM40#G%TRmq zbFQ|`&$S9sLQ(0hxkl!ARFG_aO|3aE{^Cdazwog)#*>=z8e{@4iB|K8KDPePSDESJ zs`NK8-ksV}@wyCs;(b_=Rnyrti=7h|@$vz61g&o*GA!hit5yuIz-kb(>}JNZZ^V1E z+-~r8S$UwWtu8xzOc!0N;g}U*9ju`Z(U5$pzzV<oN%<T%K7p%ZB{LWn$OGof?M!|l z)S;quFf+sh@CLIVmqRFJ2*<Zx3}=9&0n-bgN8HZ~tHM_!?{pokY&ioa5LMj=#6Z(= zW#y4S<-jL)`}%N2Mmvst0~*ZME5t#Pvc`tn6Y1Ma69`mPDNjyMd#C3ui&m^Dl@AO$ z#au4lAHY-DXk#ED25*|RBPS<!JIZ@{^|S(}7I0_R{)ewvvRqGF$>o!YSQn}4K7LPP zw)MqgET8ai=@;79cQvjDN6-w{i~|_VV&GV?9kQz6g=ZVrgOx9r+VLuwS;@oi^YC*e zoo~NV(9D14Ipb647;e7upB_Y$e>pm!NFed6R^?qhMJlV(9J6hFZ5`cw)5RmUBNSC1 zwRV!JuI}89>+Q#p=3TD7Brfgh+!3*gkJtIO?t6J>r5oCa4Wt7RzLfJu@#R}6(Lo|7 zoe=LMToCYeyxsBbsPZX-CMRrqXU!~SEjm}y6kz({xzC)Af3zpu_9z4=G@GiWp3aOQ zvRmx+?J^@D3i#lFz7>}Kv0LB!#PobKbHx5nGBa!=N<&l8$1#Qd^JPeF7N#?rUT5#f zheNge{r%#4Tg39o`p{&*wdTy<zW7O+)Tim54<&;em8iKt^1AM)H(6O)9>v?*y3;f~ zZfuJyi8!Y&C4BPt$H?d3BA#}g0a&SE`*IC-%Abf|jc^?DQbe0)H2CgkxTyD)^X=@H z2Qpp^^R4bRnx!9I5DPDzBy|_TJ+}u?7R^P@<V8$g)~J%|+8UbFag#XOP7lHj;{5rf z;jld?rF>SFeSQ-^hI?5!;AIScfK>bFHD-5_V-dtD!frz&Z?__G9<GA?J_{y_+n7Rw zCq3;ymclOUbZyro`Yr=Q^?vC6Mg#fbO@EncNUje1E7%vXkNPPC=ed+{Ew68F8>;Zu zzhyTE#1Rp@`ib<rxO=tI-d=%s-^yE^cCQq(5t9o+Y__yi_U5Z?mU_cZFFNnGZZT2O z?cz-#AKRPVt7~!D&kR;K4QA28x8hFggJa_*$saFYo>%=i07quMHK|;LPtJJ^X8EjZ zL!F)fMt_arE|VCibgqF}qk=XhPgV~auWP8UTqFC))klU^&>~VG@bQWR6P^YtI;GI? zk2FbiHr?4J<IA`u@92|h%{I{QWuYg}R^wG6p1)21tEoKtX3zYtMCp1bGlv1+@FxSf z#^i@K>3D{yT=d<wt~0W1K#|q`L;TlTMunwHJkYn_)%E;$?0tIGF&p-Xlgo`$4D0o) zy6M5n2dOfp9_7-ns5=sU2sK3C#Si7a7ndukKW`?c7cDjEjlND5EU}#$OgZ|d5cBzB zuEL)qOGsFFCzW!btYjxbM@P2}pb6|>9#7u}G(IIArc+#-IyOm^f9qsE0*tCYDQ#+M zLQGdj>;FCUpLGXcA6tw<*CR5$&s%){{*IMAh~1OTse?nnSIq!9&U^VMmXHBElnsR< zj+?;h8NH0{iwk<K6=r1et<`c;v2WtUVSu9y<6a!R;tLXx*GB`&dq-e*7v(GIDbyeV z0jNV-LZ$e&@!5pz;<@+LXq$cY!wI$l4Yjy$?3#TLy;8aRe`4A_ZPN~sJQy*Nvh-N> z^^_O$MH0j8CT-$5M~)2ku@n5b{WxwOSUFBXs%pJm=GR1B%XQ})4o=-q*0+J3+x90s z$9xuSJ)c!@Y-xUVYN^v^m8VgnQAaPf4^%2$ZaBB&H|L;EEHt#^na6<FC1^4HcqmJF znmw`K9R|BOFk+ycvxwg#pS02tbJ;&0N)ygP*3E7}+eg-`BLf?)PY8H6dl8Pv#!JFC zm&j_b&;1?34&4eCPOKjaH~Vt-x(~`NYF=Hw?HO%7>tV4RS`cAhu0E|#XF0wX4JetD zK}$G(;A~0F6Sc@=6BpO$6`q{rjN=#Dzv5R>fb)x%YUmFFwV>;K5=k(`C6=VAUZq1X zgg*#$c~^7`%~jd=qL{8->8JZF2XDL5^1Y0Rx}9zTn#lhBFz@M3I*R4c&7MrIEFRl; z>`<PvwyZBF`oA|6*R9iT^Zb|aFO;?(W6a#bLaCWTMg3QT^^!gHmWGCg5}mRs4aqYO zM&5)2G4oU*+tl^pjFa=1H5OoZK7ZYxP08(h6HaMNOJ0XdPaq9Gfk0=xoy-9{Ho5VQ zs#w~)!aL7s`j^G!<pRLpvS)$)R1?efHRX6TGxkC=dU9zRv4R)}Q}dTXDLD5(P;qRr z#<ANl-piyTCf6xKzvVph*z>^mNt;6^%K(il7U;QL@A?a9oFtOmejMhzK|3_4&^zYL z-^S7Pl875AZT^Jl?DI1$kfJn|Jf)Myf&&jFy8^_a9#y)3d18UuVQ8Be9O$bZ2)@5D z$cyI#Qq8k_oUY?E=T5F?=jYp_KYoe2ALmx+G>w}Nw}wTE5OTBrBbB!V)HB&%37oH- zgWuO>9Y;kCOTHc$<A-jm52XlP`=@B>L+zcMoT@7HyE+(_2Ne*$)!yHC1|LdX@4BLX z$3DHZeuL}X&hv%W%7627rTDzP>+ZsqFyfSomM2RA_lI2`4#;GiSuR*tRANts^-KWl z|D@4mSl!(wUJ1~LZwS8%w3FP6rBR)p<6~1x^N7n%Tb4Et6v?h1Fcn@Q^Y9&rT#wiL zuk7?@!(z>p`S7PG1^WUFrzASoHdeK_nT-_8HDN1CAP{T$ZgbHJbizo)g!g}3fJP75 zMcA`4>8q~A)vFn>?HR&nWR6rW=K*kYzA}Kz5c4TL9R)2VfC9NUL*Z0he*iP|F^~Vk z3ZgE%w;|Bjwa4eQu95okgnehPtf;2O33|OX(K3?$GG}pd(dRCzN4_QbSo;(yp_Z@M zC)E_ss<d)K#~O(8>R(>4sw<`wbG<wn0Yi{2Vk&N)FEHRJl%nVP{^XEwo7uvR!8Gc+ zde)R;3A3k%?_)Ve8QmqB`OV5oHa1&-FY1a;;h@n@b!%CEY(2VT*XW<iBeIhBCTeyD zmTQ>riwxcH8W@{EIcwr=pwr+y>P3uyDci<gy`oKv-@*_s8$D>ZC|l?GW=C1lZ4=88 z%kk{*fk{%-d}74}7WM%MMBaKws@rvYO{Ixs>QiL!unG2ASvT`RrM@)3{PMHbEwbCX zlD=e;r0xq5nm%ZCYKMzU)Nv)32hy&tK*dwviHT2}T-W<x4%XNP7^zf2>-Egp8jF;c zoxzlvZP5v6HGnh^&(>_HmrP!LapG~gwm{hb^V0H_(u%hx^5;*tCe(}6w}0k-sSLLC z`eEd0@TrAf#BFrC!uNef#@n}R9Nu@fe<o-1;@Rf+)5KhdEoL!55iU3aU-CZ$e>lTv z@A!`W{7R?Z&?BpUbY<6g_{Y7BK!N)nI%9ZHh3R)M<djRrc1di&{n+TdQ6zryC1++B z^_rPg4+JAt7wfFrZ#N63x08f<YP<3bx!qO$*csw!JtT2KexdV{78=l+>-}bA4Q=h& zU6U@q+E88?dvQ}q_Qy6!2-5o#?j|}-gJQl;S-ylPvZ(It+kcOXU1Ey(!3?t-Z^S&T zmTo{py+AoDe`}&(=<M?3q`0`Pt!;aA_n5h;=vuGAN{-2O8W7srK0e^l4EM#el@t}p znUDYNQv)RP0@_cJ_QEnQ|9uAkW)_x|xbO3?F2hLAiP_0Ki!4+*!^_XP-0vi&Zp&t2 zCmo$qSx>$b7^+9hRmuN!ZFsDq8WqIC$hRp|HlrmjmwX~8i(-*0p;p$4J7xcpKV#tO zVyr}@|Ie*@%cndZKAYsiDJE9ZymK%m&`HxF0=|$tPCdr=S>$!mP3>@)F2=fA^_<#X zr=`w^_UOxVY-k=&Pxc1TWMP1o;^sF>i|wY;u_w-R_O1qe=eA)-i^AI7>~VUO%3_?M zErS8o+s#t10rTFtzK>7kygsOHJKz3`noIAyb$L@yYO1`#c@laMCN$XhnxvMlrZ+7u zZ4yx0mJ|8fzFB?UUi2HDa6^ndn!lF=SoIKP<>>monXM6fA4%WR$F=k&cT+jC(c3uf zzFcA;Kh<4ues8XHUNJ!=C5@jyZQX~uwV1`<n%An?)>^~b<ZoES+~YW6wcqa7d2NaR zb7#0`Q0k=Y3gH@)r^|Ouv(R!G5$cYM^*D+vZF$`|vcAAY*AqbxgmSCubVa7Ed!M5) zOI$$kN?9w_$*WnbAD6U%qo=S}Xu9WQ69~STdEbVNnrt`ibUvB+h7<qB5zY4Z{dKuR zF^&-bC{LO)5%pQgt@v1_7*5Sq?f*0Ni*Rs}t(fx1dOolDi<d7J%XQ7Qy?-@Q7l$cc zcwG2a^e4s+5YvnQ-I=mik(HH&TO>30eVg~K@wGUwVUXxQwg$<da5?*&H$TeGg*z8- ztYo`p8N=k_Xhw<Ru!b_nS_|5_2%!+P`@PcW-3i2UV)rvkG@!otdQAAw%u=k<fO;xg z3*WS6M8e-&jvpYZKfsQMcWO<SDFifDX!OrNXce|BCSiYu2M(?Xa*&Q-fedFJS=Y?i z^P$e~ybOHrmKhS81~_9|<KBzZE*Hh$J93Td@*JDyiOz8SIvpiX<i3{m4j-h=Dsku= zpM>`wi@HrWi;yb{(-8;X^BgHb-3%Vx+m*~ZIP?ih87}AkpMimPPJMpWd^1Dod-Dt{ zTnhKngo~@J{nOYR7e-JHlVjgt-C5VHGpNC?tKm-(<}f0rphYp{I-+H<-O8Z(#y~$$ zZ#eCrBc>i1GR^c!%tc&}CynQ-)|2?*F=}qM_#D}IpYGX@irMMfX(?qT&_AsKZ)?s) zaTJ(+4K|Hq=gS?qcnktb?R>vKTz93a5T&_xAIDx&Z$sS@#Bu)DBsUe_KCcVbUKMPd z4v~Xvib*lJ#IOTzlb*i5MJ;sR1>w8&9eF-AOuOCnU|tmY8gB39Rp>kNs$%(s&H(Vd zc-m_x4`6p_VCPMhtXFnT=zAX*Zl7SX$i>l1EkIZP%1Jtda$FVT`WDnxi!f5?9a!ds z30)pAX>Po$K+m;3ZMBSN(fG3=Z%KGUd?rqGzgb?#Z)tHeFfTjZ5^&v}^c?lsm!@t| z57@O&A9k06C<yl1Dr?>t)^M4ur5Qfc5!HIaooy>G)nsY-j7uaj+4R##{e)j^fCD%8 zTGdgXll)hcWsB`q22WdpBxks-)A_>aod^3S`ZvSgg^yT@d@nXbqaMF3o|-agw^|cS zqvrhPORl@cZ-Wf#?^^RSe_84NymP4M0Hy*;aM(W-1*RNV=)zvp(b2`_%IA$2yeV(t z_`;hXAhDL!<j5fAUL8q7-?8b!$O1IZ3nJClo4Z|Q|GBUqmv`b~Zy+haJrVybV<0U9 z#=?*FpUS76yd&gqnm)xL>Dq330%Iozt!fFKua9Smqf&4GZcQ`yA*!r0?R5BL!Hu8G z?b;pvlekjtj>pfG<hHW3AN)RkTbaNh5nK`lM0?~-8JgakLI!tNQ|;tB4Rzi2o+sIE zYn($#O+;;HEP#q#p?5V=(TW55n4WE0w;;wnb^+b*9;uWj6iMX#@RWL&#%d<#=o&9t zuj>|3S%$3(pMp;U(T0$C!x-{l9zxwpw<*!1Gug(u3rC=ahliiof<ZJMu(8B+(VS-d z=7=HVQ85)uRO>kL3#Xn0w+b>^*r@_9)#5+zSI_HiVyMn?9?#e7AatCad-wv&56_X% z=JaBb+{5btZ!4u%K1(U(FSy3MeZSEt*5@MV(&JYu(1MsRmZJ2<(oSY@@Ufn1E2~EP zV%f(;txOBw35%6)hFgh%)4fnXi{rB&AH6qjYfb$;RAX;Kp-KvdtMG~%r2ge#ZeDq( zJGuU9Qh~~Pw%Tm!k9rZ9o4n(f$ovM6i?55T?QHW<gAF|2%GDLVYEmY@Z+O@C1as0# z@M{cq0x^T6*P;V=FCHlQ>>@)$<u}Lo9<a#%64QCMape<YcINTOlJ!c<f8Oe^sj~zH z-=n%@1t+Qa#<1`jZ;+y%oJYjzKE1c&wW_ycuc}-*uXXBOe;vW8nlRUdEduttJatj; z@%s}8JJL$Qcrs;Es<4?DUHWmsWIe$?_NrrsWjzpR7~#uz|JNu>g#sSk7bYLml+c?& ztm0bDU%V@0aCV{|d+V3=MqL98t~n|Ie@HI-;)oJ^fV}?vse#XQd*4dJWg*Mw>LCzM zpGrVN5dsFkik^IFW^a~|kVt)D`2k+fVXpvc^y=M}4%QiQ7Z2?di#U=~4Z;qj|D<Ax zz{@Ym=l|E@&~OX3`Rt}6V5^__n!e#TgBY<mdK_z5>W30)vnC6K=thBGjH1tV|K(MK zy>`Bsy>>ArA9KPj>GVgZ=Lr=XYf`_Cl$8240aoA6=Nl~0lDIMXl`zEfEd%PSFAFl& z)aYY=qXQN(2*t=z?Bh`?Z(+W@w>P;D_uP0a=CYtw*4hI&7NUj@d|(6e@n0WBVIkL_ z+#!1hRX|XqbGP8s?mDvAym4KUB$f#v4w_glt}Jrd@_E^SH|8~#{dMZXbNE2QZ@_oA zd{afi0$y#t=C2nvYRDT%@V1C(O<@7<u&4Kk@BTbHDjhUVH?O2V#6?090zLsP7)fF* z1sz@Gs;b={XAMLr#<e#cGy=bGr=#J`MtwGSLk!I_uJGnJ1Jv&YMiyDyB_R%6o>{v( znR@%7gY1sw(n{u(l0f{8Z9L9UhA4=>y&>t>Q2nhXL^n52Hj4EMT&TzQVz2mbpmZpk zl|8sDx!&faJDl3;vU=_Q)?T;YqPu@N<z+?Q`Jk`gE8qq@c(GO8+{RhtwHK8k9nZDz zDr{m9aKirX17P!??6(AXs~9wqPa9GP!yN2995f}#2-1C#MKIfb4r@0(vVVdYzvaWM z%!R}#$hQKH#>ztyP;Rx=3VrWNe@QMSPk;D}U6If7cgsK2#shh_gSu;Ogm2HRP#0wb z&SyWj%=3OMzsS+m+le2iG^G@1c`rf@@<W?5@9r7T+b?dfTCPN#O_{MKld<4GnmZFH zZ%6YRXDsjSdZU@SFnBz_U!EhYTYGs)ePgOS?>&3seXS;GR~&3?yjj6sn^KgQH_703 zIMD8XVy;m#Dd~TDjIx0-Jgbys9f4ipF|x_UffvVSC)xfGf}T2g#l3gY3>OQdli_wS z8jXZqVL}gdUS>IP-=C%7%<i1`_(-Pc!~;>MK5`*qztEwpri|ncE_kvWK2eELic4+! zl&{y}TQ1a|>}fsNZJfcwsv&E?aQz3uM$(5@;a5{$ajVQ%9N_d~CJU5x2ZM#_6a`G( zJw;!rk7DuqlT?(;;})}o2ILLQw1|_ev1a~lsF|L&65R80pSCa`Nj*!kuFy9bif28; z6GAuHMt*;iJ`cFWL?gDR-k!+GXzCZc^V)`!gA{LQT$fLG5eb&1gbNdDWdy=VEpHkS zH;%x>l(#L4WUgABnY$6g%$M1bwek`6rsc2u4T7YQgY_n7-l`)>dIbnP!+?`rk`l-= zdr5H`gRnwF;vcQ~$O=z$1fE3A!I#sH@Z0t}g)?86ZK7S1<By`+H>RSPG~sHFgxH|( zzUENd!-9JHF}4~p$<sG-3BS>J9iuDwC*xjxNpt-mFFV=lQQoh?KQRk0n47P&oG=G_ z{VhbEpZ9FM>oVlbw4k`Y3Fomr^Sw<DK5^Lp8jz2n5lu$|BhVhLr|Bp}Q1wP<Z6Y0i zHi2Z8aPt@|D#}%SF+>piYU&2u8E1>tUP+Db@b9-o!%ZULTiBkJqC_@yl@H=Ia!2v0 zhOI)0aC)1M5R55Ei6HZak@IaeTI5a{!*zYC<YDFAkQU@9s+>M0jwyWy562Kto)hB2 z^<_H^b<G1|LT<Q#NBeCQTR^Sy@lsidx<x(;hj=rOYrb{wPm$O)!8++&cVU(+A(Qz0 z`1m%&W9bP3Kw&+KC!ZX^R#|f81@%B$Rybo<oO$CT-?>NcLT!t}?9RIdEj$F~vG3Q+ z`)OaWFHc93Dt6ITu0X8#s%LTa=xZ^AE2)YAM4ov@UR}3x)U#^t!)g0bsqCon5kpB` z)`T~S&D1X9rWke?Pm5AfNKRA8jC?LkA1o28ATK|S*>>9e*&BC*kr+hNJ5-|%d5-kd zjqYzPlm=4(IIQ8b1!(zoy2~z*q1Y31@o;r@Me((&`^Q&u%eYLRN}^5lTxaO(du;0> z&MPF33js`sMNTfR@(3H~>z8BKg5L2P`ar3o*5w7^Xi^d|7f5VW<<V}|Tflk(p93FU zzT}-e#Y&fQQJiMd=jnlKWj;fEP);|Cc8n`>JDwJ4-5pFnrtf=^Tj5#MU9%Ls0Spsm z4L@V3mT%A3c?@<=5l4;atrNb&0QFd3Z^f~7pJ~O@!=YX?i|wIYgdiyue6dVXsC-(c zZ>JU~q?{$3S~ri()ZClh;X@+%(;DkJcLvX+ys~!aypTpqi<!B6TrL7diQ>R<zRqkp z5+h#XKPO>nb2%n7($l*lP9UmJTZ2rOr$7C$c)tO^PWc5&&aS1TKJh)ZR5`?~M*<Nh zD2D|iF>vyuo$Wkhl$_zNo^>R3<?axMD9ma%sgt9U#hA!zDZ4P2qXewSgMi%BK@PyB z-h2WwO#dvG$jFi@oP$_!ZM{vMd!X`~8WdFa%Y;9L__4@$KxLoR*Q+7TG!!Qa%Jw-N zW=EbpVsB|~0RUPQ2MKs(1bo-pJd!a`A|CwU*zh@}5s%%qkY@k7>*J0!$#cd2s0n(p z(DjH2<Cu+-Zg=Z;uS|uy2VL(m@3%rz8dEk%Ms2EK&E5QWJcozD0t2n1ki9Hv>xje^ z+K@HT0*1*A-EEcJcEo!w9JACba>u7_AWWZhS#ZRSTN_2tql0>&IK3t~1r*7%m3e~o z$x>dP^}HZGCRah1w+rNbiWVc8lf(Kgk~QAF?<>wvyEf97p2|2NOG&~sOEkQZo;#>m zSy=vRZ}bMGQ%%L1gPrJ8stvVrA-%;Z%ycxp+uI*S4Xy3+r7H2!dFa%W-}4~r?@4wg z|2+t&KBZ$rzA3XUQ<eC3?`^_)91zeb%a)yWwIx?Y{nn{y<BvA{`fFtM_3bS9wwr5l zQ9IEr{_+IFOX-6SEt6{VuJAMr1X|7f`r-PyEqprPlqSD0rUT7SL6TSZ(Ql3Bn_#xL z+D-y}<XQmW<+0qIe6!RkwMesx5!43LpR4G9Jw_)6IlqRTeuo|Rb3jLuVdqGCnvZeJ zqO(&j5a0PIz@y<l88fIz-y0$p&x>N>-6Y4J%xhBeSnZ#EVes!RT)B4GpQl=}YhKF% z%B15N{r8%RDs)4Sv1Yecbr!7+kJHXx$W#ErbAjP%oj$omZ_AWGjU{p?m4Y+YRPPQQ z6mcR{>$S(p6?b}bD})7ja=iU3uV>e)4YxRt#B-C|a~le@aER&u<PY(<d3uV?6DB*l zmXi22)YG3-h~I=%Kwz)oa5zSgeGPu)>>cou`FNbsDFZx;C9;eZKr~--+RkA<?DP>U z?y^*krd||*626fbd-CH>7!COISofRYy(l-+Z0*wLE+U(z)oVaChBG|?@uuQzioDlT zA5`kaP$;Q3>zfx*oN?MNT|`|*rXKrOTqS4C#naCy#aUUh=vRbr1cUq>7yYPgEnM0r z73ZT}i3eK9N3r~#&}A!`KOtFbX4^vjj(^d(!wq%KnyB9syIIq(aI4cXTV1Yp_y^t< zL+Ecri(d)SfqnG$%O7Cd9ZTVUc4hA{`0Fy<POKgY7`<TTl2qMC%0pt2dUrpuXe-C> zj=dZ*sR-{k;h+j1*cE+O6j$!aRW|;Pha4oM%DHXG{<GPj6g`c;^4ceyS;Iu7;eP4O zTwL55rkb&e_~wLQKo2>Qu+^s&?~I7oATKJN?NetuK)eZ3&bwiz8INjKs&<W#H<qqj zU7_Tn(Cq{s{bu!nWG=H@e5rXH1vFK;xyxg2#LW#sv5PCx9e%lpksPGL?H5aR>_n_w z^4Jt5O}s|qyqcH+$`#(%X=2Q*7|;JF2*RGN8!YB%{<~iFP44YZeI4(6G*HfS0;)-@ z2<&J3yd71dmf#$QtC@zgbB&Xm1D~_9W{)wAB#lX~a)o>n=1lHWO?5Z`VsN@T8)Ix~ z|1uYaYflb79Fp?T1>)L{5W3$=<{#o3t?E+G55V7*(y{=fe13ba{DpN(N_ZCowMVY~ zEgx{IV8@3~+wI_2lFND#Hx^i+<O9F>F8o5OilA;{W6L$lr5g-_el6b^If?DEitqm{ zy@T;8S^J#hz)D{J<1!AYr+%F8Ce)j)_EZWo!Qf?A<C?xDM{u0lz3?GU2uJgl^%3Ad z)7am|jg#fG%7xY+ycGP49p%RjikLxzo5*%2bOi!-s-fO)epw8%xCWoJ+RF3koTs@P z<h&akNc=o-{Te{a+E3un+uu2m31E(5k&m!3Z1`*dtqP77ks$qJlSM~GwLHiPQ?Cmo z)!rJY&PO%%&q@i)(zYCJR{qQaDH%|NSzdNa*x8fY&6MdEC({h)IPFc-H5-Ef#J64! z+<&bVJq`e!T|4JV`idO)CfF8HqdT6zzs6%C^}S1GNqH{;@L0&+rxTbsx2gR=z*FgE zu6BFmQQ48xzCC!R>cs4>fJb7pqV-r_KZg40iI~?)S11~o2h^x%0QVd>bDYYzpmg?E zkX#-8SrmUfe}8d7gw<ltIk-?(NyAv)Mt69c7ifNbK3)e%|9u1aHIQCB2YdCq?pdCQ z2uj60fA)Kjf(C*KiZ~PECD>?Y#_H1-JI{E0tb4!80b9TR)F*$mWTDEn_6W4Li*YJ@ zu(zmB$r@x}SyAx|yl1<3JqdiBl%(l<Q4)RC4BeUZ-cP?GfUX{wXnNv~V9+?SiFt;< zH-@`o_xcd7W9BT^r%aW9BOj5S{U_w}>pbVNmJe)VMV{6#{4w*t%mVS|M<2wAhq|s< z#kqg%JNuhy(!8I88102McDIO56mQktoC(%5fDCPf1E9&e6Zp*%eWQpJ;PCbAFmmbQ zm<crUm)m!Jw5A{0&Q=dW+|L9L_V&0^(cdJKS6td(43<n5|NqHXne-m3*i|XBV7`@I z7Ldm{$IL;Cm<fF=`pT*s?(Fxc5fr2_zS~x7axYiEaCN|8S}>DOewi#cw8jTyD`(<! zjdDxhH0O>x!pHCQua;JMtfvmV;nVikXYwKO0;QpQI3Sw&<I>1p>&o(e-c$R3bb8;L z2bR1Iw|sIQs52^w2FDtPmsic?jp@Jle6MB?W-hA{cO6pg*3;!)kiLK)Yu;gg`@e5* zg|Jg+&OzJ_`G$^u>TgwqHF=iMX}G<N$B^~f<Y@NyOYC^7Ky6;-6?;+}-RA-vJJ&}P z8ay7Ymni;Rpn1;(F@E5E|CoxZ_dp<%<PEy?5B6-R<AqM3-Ef7C5r{_L@_Y52d^&)~ zd+gQ0?@e55TU$n?VC>u-&8dy8#5%<Nf)vtV*H#RNd!zq&^2G}rH_qNXYtnd=rF@BO zyrBefC+B+IRH-;W@_(J-CbZz9#brJH>F538K!Hh`3DvC~#-c|xX$m7C-gT0Lm+`qO z5wzyrOn)7J`aW7j*^jj5&%&;uh{n3aSSwJ+MGW=3xVe^LqRYKa7POAUal~^hyGOr# zGcxq&s-Z0h9%~v0du95E*N$sG?SZIt4-b!8#|iVh?WfV(fPU?Ee<k&Gp$C~4u#cOS zO!^y(_h;NOu4Pu|hov`c%-iIfnSwdm{(xBqKEH6|<JLlTvX-=RIWiPr>2~zaRznsq zzIC&7grk%76$v!2jllAv?^dZ?o5+-pjmZr>5Y6Zm``x;tz$qK5w+Nrv8Wf@J)cxqS zPMi4&a$rIF8gG8E+&n%@qRJ3)9M>|ad83fTS^rt2687EDq)sE^a6@bER@=el`$*Bv z!~Mm!UKo&71!Q}90$8koIOb&m0LLoLR*CpHPQR4R5~tD6_QYdCuqMH+%7gBH(ID#e z>Kk^Kw_zrT`1sv0p$tXPw-8AHZ1=wX`s=n1;gMEuATm@Pwi7onM6t3<jGT#b17L!t zvCkk-`2)?nI!hY-zp8+bS#H=F!2W|ti*$E)Yj3Qi#q}Q40{nyP%Xy*zv7G$JJ+_2P zNsxF6J98kPyw~1Ke;4F?y=9@kx1ZEf@}cPOL8AAX6BZ~}A;jHVmXzkt1HWExHX?W7 zV8-X9EbRZRHE{hc>05WEl)kq7;!wP95N~YC>4yPJE)=TwY$@JTufN<n=tYcmH;pM% zpRvZ9fk!}yAX61Rf#jQ>HQGb~8A?Bnx;x_}?z>oKcPx1I1RWi4MY(SKODf#$?YVpx zd3Zg4Weg9!^Y+2Oa-xN(m1&+W^bFmO+#M&5JO&a&``1==I$7U&vYr6YS;7A?_0>^P zb>I6J5l|2@NGXF5=@tP|5s;P~8YCr#ZX5>T6{Ndcx^sY`k?!tph9M+|j^D-i{jBfr zuEjshV%YbbeRe$i+57Y<N9y7*SF*EUdB0Cg$*vCxl|+2R$L|_v_#4IOJ-F<yB{O}$ z7MAmizbCor<TfB<s7^UBo90$utN@Nx!pse-N9ISpMNM|4WsuZqNhNHe0gu7m<(2V4 zEz=T8ZWZrT_;AY@D0TVuQlZ|nqPRF`(h=GHTo+Oqi6E*`(E40V@tT)|z&*2%z&U}p zBFy3T^zKlF<%Lk`Ie5_m#(|P=V`kFs^Z>-u9u&qhNrqkQ*`APrVA0kD?AM(&V}mFc zdhO-s<ZSkyIo01Sqgkp9K^J{%-S=j}J>Fy3Wqlvv5S;!n??l+njhv~#K`gg8u;Y3l zi+^`q$w%(=G3~`eR_)ibAKsQjZROFMT|$@mKx1}=?&%K*(?8`SHR()~f#BsVpm`l^ zzy76fR{S)YER~AeWr-`?)%*s2h}Lm7^>=beq~J)9&bB+`ai;+ZI}nkh6aI^7d6Bdo zyII)p8W+*o2VK2acz}$|Xg&dC^F`)5?mu>%*^k2%-&WpPtJZqPap(Sx%;Xl=iuj}v zRow=!A(p0k(OCFE%)qv&hU)CT=c5`8IrCNtn(?*m0=7}V=+4NOOr$<(rvMNTWigZ* zxg$ZXO7X9MWkwPiFhFwjb8BQ;x9pgC@9z{2Z*NaknU?KN*7Uo%nP*hA_#eNR5%7do zjl&|-!MgN1pXHHH{Y8IGFgR{*;W$F1sI8F=&|8w?j?md8Z%enV*uuA-3lAT<<{W{h zhV95DJpar6Vf*EUl47QfB0D}^<Y)cm$_B`6t-W{Q^!>)k9^Hr8yz!4$Yq~nUKF^2I zGYod&t@_~K1qAJHW|UBKM{C9Hh!&+xx8UM>FdzP*ZH{GN#<B3430LH*+{2)@vGMM2 zc7&!~!Nv;*LBNd_&dwcaW$@42=BfhS>ALpug838>Sxz30*fj~GgKm`F7~^k_V6g*7 zo*mBQJZAmVke<!)TWSy^zBrCCxWJEFc0tVQDIodry)w|)>cGM3ZJ+VFa9dFyvE<1I z=so8n5~B<ui+g1`f4mx9e!0MOy_|ggKAtm8J(WjK-IW3W(gxgJm=fY&=DE2YJNSEF z97QZ*doU}*BQ3S(tX@}&fbL_e-Y!dLrgT)Wrh4;3;_CFJic9OMNU;B`F*HkV_H@G_ z_<UGiM2W1gZon-9d-M|K2-cSwJEH@)?81P1N9mapCOr<lzbH`Z3|Ztidg0+8#-^J@ z8U?QOT!o{ghGa{v+IBk~6I1TXq3hcod)<_lZq3l}E3;+y*$atzkhGCh9l5yQy8NX6 zN2(Rj_!DDgE0$hiLOypBDg>;rHOqi(AXm#}hWR>^qT|EE!@F_D-{n1%u@7GyY_^WA zI~q7wC?GUOGkg2by@=dTeWS)TC)xmD0sl2pK_TdO#_2&;i6>YE1Anzt6TO2vsfx{4 z=Hl#0%B)`P)ecixa#GMH0~j2aL**tWMu!SduTO2}5m~HtLz@gP8Xp^1!pyjkEKFkd zrXpZbDV+CPU?p?Xz0-obV66Rd16^f4Uk}r0_>$HzHx%ZidnZ80xrR{LrHX0@dO;&O z1rqvhf`qFfX-(n}AvMgBkN7|%OWqqEZ_n!uvOZ$tK0Mdf8+v#n9}w6h)6``io3*3; zCM$;AEaU3ymJgRGF~CszfYGYTRW5PR0e;51J!98p<hQ8B)Vo4z<ZxgkZE*1ju#T<5 zWtnwf-gIdmJi`LoxWk#$LVA?9bIjU<5?!x;kkyryg$LTDLdWGj1kksmnvtvTq^EO~ zj)ku<jDHOPsGbd2x}Jj|Oj_P|4{Z$8&=J`d*|`5bJXN1)@-`T30))09b1s*jXL^>% z8WeE}$Pi?ujlYLVv=eq6mS`wEPo78=vn7$Sl}2xLrKhCSc7Zw^T@bjhANGYQThPw+ zAY{JUw}1dxF5l*mX0Fh9$k6MV4sP(x0_wsrkLniB3lW(NabDtqqc&ydt0B<SlK;-U zc8w$9iTkQl^*?%G0JV{@l5KCpQ@4yy%<)%3E#>(kR%Y>s5v-pq!>%xa1Q~eC)XcA* zX3k6OJ_f5KO38Prb}!Fm@r~X4sq<Jvhw!)AkXpt`?Dxbe9Dzn7Xo^-?Sb6YcuWD&B zIm&&(@Qzy^Hn~(ByxcBf9Unf2Iam8Bb5Oti_7NO%c(B?XZH~!}9GgFuo5-vrZtUHO zu9Q7OXcU;W_i5Kd&q0JL54)ahngpaAGA$E`eHvfcuc8C*`~V-a;kp1=XH1-wR_-U) z=1pW~j%;C>aIR)&#tb7!lF}-SsgRBEN$qjiUFYAF4r@5?Qvq|QB?lGxyv-pG0AMp% z&m8&GYHb<D_pX~vmU>^Typa^w!)B&oPf>!N2-Q~nbqT*ox!~yQ@s6<Tk>LCRI9%RJ zN>}PrS}k?y_5}IFEU1*%-H`gtcz!F@W8_X%LiF*u0FNpsh+UG`VR_fD3;vZ<%i@|# z+g+$m$#;<{91XG3ieuB&*|DwW&)>WS#8{VhA(MzzMrBJ_YV2=hC3;&qN#c*Mc5gRx z9Af$o-1xFUzrZjOSQ477KP-=HrIH~9-1&%D%-xt=;zkao{LJ{bjz=@<b$^DWttQJ) zT|_|qh4xakXgX@O2!uWk*@gdv+ypNpgM))6HT>Sz-N~TKZ`??JnOpU8^ECS}i4pKx zanP3RZ?0sBMjfHah>JSgy8|sq02%v9jAGg0b=w!o@T(Kl>={Dd;?J)@$*MklfIQVv zDx;#a+_6u2l0!@M#f@CbaIE2zkF(2xUxpqt%9|}`_9p+8$?a&yV^=`+>eA~p_S{Vt zPF**yYqfV1SBdPkD8W3D>*sU+r|JOk+6u2PT(NklQ)Ow1PA7p#qvV@bV94LX!@@5$ zCM!w;<p}&|bFgXK;T5TG`G>b*@<7Z)?L`AwaAZT=VNT#VhB8@g-IA@$FYGnx>!k z?3?#T=0UqPG?k^eI<tkAWnTOG+L!_?5&?(k7T<8!waMKR5L4Mt*=g;Qqw0NUM*4PV z*TnJoE!J9Fd)E!?B3Sr}@OsK182x9ld5a3<mne0QhaCQzdbj+Jfn(v0N91oL>V9~Y zGADCX#NXxA`)Mp=HC9xhP1^n{tSSPz;dTpP>(S;yUC);5?q09BM%Q>s`f9C_#)qjb zaojhrmWeRM1GKo5SZoa(!auniZtD}a<4iDsc;dph`_ympn|*>$Mj`Bj2=lRt2&VA! zf(M#~ZSle)pHrMt7Pg8jQ?W0oCzn@~)2N1eX{P^=0DXuv{}}Lih@xF1G4=B>q8W*_ zOC?x`+;`M$b_vyLd&+mCqk3v*$wLj7{CSv8*>ifLR>hKxyJ-M$IPSi(9PJCPDV}|= zNbjHdt5{0bj+Hf+_m17U$eI<>_BM*S+klqY`D4FMTAL%ExpK1#LW%PaAlf|uKVN1e zU<j6eMk{3h36F?+AB3Vot}e5?>CTKma<9&`TEWo=teH@JWRzF)<z-@^NKtGKc=Xr1 zYrcU$_L+Hkg}Iie4t-CbgW1NJk0g_!`sRZuJht!O`+rLbDm`cF5K?$9-TrT4K#prU zRA5e~X0)bUl=xOtgDc9$0cdntf&N&1pF<>EA(}@fbDUgnhd{>5h&}Xd(Qabt!%hXT z0KIJL*b^Td?aHs-g>i#g_D0@Mi;b{=%Of}o;kx$&efUeLZBYGH^%!*GPb>zkFM%78 z-a8DC*q=lD#W^N4?yvLVLMe5f_6?_D^QSv+t}n>0n)snpGmHt$O!K7w*nzNA#`8R) zrD`4)VNsa}lBUUb_d*{yF*!cJS^CC59P)IM*C+7&0@})--BH+pb&_iOS8gF{BKR?A z4!$!UJ99vuhbv3#nr5~<mTY^K4S1yT3adA?4hdebQ<4%+AASG<E1-{AGORkc1XcTS z+;^GLe(B`y4ZR9dppmoM9W^zQqhtU_T|}BofLEx%;iu~zmXJJ^x(c`8hO<rcH|`hC z$*&rBOy3FA5CV-~;{{>1TTflbvP%@KAC?-4Ex+`VEZPxXw9?`YUV3yRw#TBudp1<k zG-PU|$O2QA)hDIiDr%C+3FrZnn>LevHZJs{<8`_d*?4sDW9mE^$q>!6sgQB{bQso+ zzNDRn6iQbXX(u>By;EI4(i%XXa=l!tr}&&csbdK)nQ)p^2lDDRBOyAY-8GJ<o~H!m z7L$ss>a`tladG0p3DdfttH94e%3J+)Bi8nG4Le+0mAdi*2BPQ!>G!~QKst`jlrwIq z-e$dv(l72hm!bOnb$6>k@cJ*XrI$U#W^%T^KJVhSbNYL&Dok1tUkeKuNNL!Uj4mx7 z5hkk5-p(^V$C$5WVhGE+wk*TwLH@2N&`9s7zyGLuXvA-))+mR5r@0iL9^^(g0+-49 zA^DG9<<hq*K2!h1OJHM|It!B4b1-UoEBo})QC~YjLUOtFcV2$}@gG_encFNM7_?3L zvOx&(czeDGEL&pkP8~UkxCOW6f*E>1rli!S;CIp%6;`bkNgdQbOm(|ag<&^q4;Ity zg_mdaW6|19I_63Z)y@4C$$><-0Bagw>1RQ1CZqR;$Hd-@r%_%XPEQ>zR-O`?uW7jC z5379n=P_XIOC59KBfbCexKM*7me@Pz`sTP=zuz(a+KhJxFzS!Q&Ii-A!Nq2uRoi4? zw~9iY(vJu0y>5DQwaDWr(P}cK0%*!O-`hE`;93z5bw9+AZqGO9f*i-4gR}RQ&B|fe zfY$pDQz1-5DA(nu^wuR__X)wE^ycxN8D}Y^yd7SDN^3O=r9D@@N=VoL*8Ie(>=e-Z z?T3TIGl0-?Iz`gdotIG}c3xDPj~z;)(7i@BqXN<Gs~yAQ^w2K>qZ<IQZVK10F)+oM zb+gjYAhsSK@Sg!QW<YDrvBzO^gbD1Nl`M3d8E)JG+d_FjE;Fk})t~R+1w?a#u(NW4 zdI&NM>R1D=J&2FVC0Gm(rb&zr4yFbL1zlhy!&V~Q%0P56K&8$SBmG_j#Y|Rg-Sn7y z)WoKjj_6VZtXqSdKrbbfXlTJ{h#5l=Y|WvgPof=Z0xuOvmdPh0t-9+6$(KP3%3k=g z^5ARD4MqEclD3XJSgw=Ke>`M%=(l33(5aVs3jnecV}t_oI(uEm6U|Glhl+V<!8#=H zVjv=RMwqCh0)aq*w0&D7NKbZ`SCpQ)VI=T4&1tzPDlhjkAGkj00jEOT5WHLV9(&=> z9Fc8;pmtA1&T3}BJ9_WeV^5tr!@sT4+=vW#i*i7g*pxnbDJE@L&BNn`PtZheL$i5` z0=bG}+8H<W7~CaE3qcwAEy2`d*pk~-&hd4KdVb4})KExa+>lwdPI%69+D!bPV7X$t z@g*Or>veqenCw1z(3lsPXe^X+aMLHfRQtT-%c53Y{%Ni@qgO4g*U%mUrWR-k-QZNM z&hU>rNptKzj?2d}u^;Z_j+&ji@wgY5E8azc^)%Pxf%9E%uEL*9i7A-6`Nw&3>CCky zFa91`?<{OH<5K5DLA3#uVXyilg31l*>q|FG>dd#uloS2xOpq)QPsTiTKm2XoUdr6j zh)%=tkxJBB_N!BCWG6j=%ctlg9Kd?+NGxpTQ2KhBvXrg2_%4V8Hm)ut;aY2Rvcx-E zjI&f2q3kZ<MYx}y=E&dSCs>b~7yRcczVgAXrpG{I44=SD?Hx`{<BS>Sp_WBY#;-8i zDdf7Lt8v@aU%yW-j`CYV3_b8h?`TF(!><O-m;Knf9x3P0U1I|tSID8e)EOl`#}`GI zDP(1D*=F^cq=jRt)HVsdG7^k(vtc$U?>rN<_h?yfM9W+0Hz@0D5JLsnYF-<07Uag$ znKr7b>+x4O&5?7xQkkYsc~n@l{$*z0JS=_pX;RHP_)j=gS#@65sqK`oDVRQzrNZU@ zy^x#tdBia@Yr^NR5|BsDnebiFu7tVPMM2sxmvt|&YTP@w&R$h#+9xzu*%Jb<iIk?2 z3?B>ANxtX5Kvj;|WJd8ZlddGSe6xI#&o%7PnhF4)&KZ2K{`B#N#rAyIO0N1w{;2v8 zMA@RX`N$z;`GMHbBxj2Szt2B$x&<XCmjf54wj4>@SQ`o(26o=5IA8(f(xj|0QGCuN zTrkz|-WK$@{EY+sim8$X6Ceo<e8_`#Otws`vwqx<{~%_Gio8{pLU_G;e|RPHc|yE{ z6e<B+l#$<RgF`EQM;qGkE15aJm><8w3SEaIwJAjLfQ0r40q(;cLDg7EsnYyVBKhxh zLsDSi7W%`4HKta1kB{&VX;J5gy0HgK1@OA{{vQwgj^E0YfMv<HUs9?}<8&^+zMa7< z%E_$f9&?bK%Tp<Q&E=8YF|7Toi_H_4JQ?O_bsd{rwa^*+(Q?VDJ;6$8CB{|~%o0CW z1r`{_VlUfhX*n1qaG^Tu+A(|ZnawC(M$#p!2mZ^+0Uoyi+^xn90uh%w84_f=UMpte z%2tZZA3Q{QBj*a(IHq{h14hqg+jc>$b*2-Krp$=8pk4t77jbQP9xyUCDtiNOh=)g8 z8jeSWe~fr=Q`6WnaeP7aF|z$!w%Q#-HNCe;8=lD*JymxSS3OWjN1wqjdsCWA{qgI; z`#H<>Yxti%YK_Y6nCKd{!p0LuASGr(VaKFpy0<KIBWu3C&9F70sn(f|1hhtAi1>>M zb9+{Lym(`7@k31znJ%mLeaq$V6^CEA-re9k7V5hbeBBuupBVKy?@|C9?loDaluom` zlSlhLaGAIvt$C~7-?dSgFQO=cHV^{9uHZOJZEzQ-Hp#U`_GmXnWag6tI3B*;wdC+_ zNSyNAy7P(2{PS?8J^dv;g;3ZATv+%oG(s-=J0F$tRANJugoHdKL%OkZe{X|MJK0AT z8}$0jB==?ZEgnI6Kyty69BXHhe}l~^)$~;=xD+yGch(rhmesz!IDG}ihG!}aiRe*w zxNTh))GsHB$Y-eGmdD*0Y^D#@V!jTY+E%&(@=o&=BQxgsHn(7B$~qyi8wxkL7LDZl z6_ZNRWrE08Km7G<$Ww@qP=S$jGZWFE-jYnZXy>FTg_qg$1A4W29m1h3p)%E9da0&Q z7b_*h86%%`eBSJS<!$$vfe9PHC7u4szVkX4FUfh-C`tZX`Y8ZBxyz*aWoY?2v;T6l zz!p4TakCB(?ODthwM9QrKfov8S-9s}5JOl&i=Oj5^_r%HTxai+zA(5;%3x#hs(;ba zZ6bi9?>wte@BO}?P#u0De_^Z%HT*REXswldSe!FHCIM3E7f3Hl2Q1WH=9U*Y_j_qN zRILW!(Yx4zS!oCCL8R&mN2e@p&G{Qv-Pg@M!n<A(>v)-%aUb`~fd5IcUK-kBYs5QT z+_TW~I$CAD`<SA$#=LY%iV<9hz$5jruwSe?wbs=(W?)^YUr3ePKD>uj*T!+GoI&_J zRB#JorJ=wRvC}HWk<V}&sM34!IIkcXJ=hO-O-v7|;4h~IJS-Y}Gx%9!Gv+TQ`QtUG z2Ca`{W)W2jk)yg0%3EN$AAC5xS>nec=86@a*y1sF?};z%-OAcGPn5&a22Tit$=PsD zGj{_EXnbvPwDfWCP{Vm@0XdXg4e9+lmNf^@6aHhzFRc`(AFpOcj2&Hx1$b>}(ih%v zS=Q^%O5=qRNx%h(DK*zu-*DWdgQ4o<jV!@=n<b~8(9cN3ph68IJcoKWa_HSVZ6Y~1 z^X4Vj1jqgx;5TiuSzAsy_T)ST|M|;`eurai#qdW`pbE7i?Ax-XIXR3>f4u6a;jKIG z8?9Jwu0#j=n~Vm#(ed)p0t*+geDKPI>pva$6L<1UwE?{kP9h(uyrkQwX{y%o>_Iwj z6iMk_QiAD@vLwl^$WMItaKiqlo<sRnA0d1L8@``5^gr)sIG0*mR?i=Pet!!D?4il% z`nZ{NDb)(lSG;vW<<%IX#1?${oQ9rE|5i*MU9EN>wV2+^+AR)lSU#(&(^C9dB<&Zd zR(Y7uU#sgl?Kcj}@3gFFiCyhxKcB_toPhWISi?e5sNW1ZuGVxLbmDm3XK3u~4T+Yw zP3M-?;=9!bMmgssx?kVB{Fo&lqAu*i1|w$hA!nYIc5*P8t*SMk7z(0S8ROWXX7a9H zuKGO~CCB#p?@{~o>bR*Vov!b9hE<f+Q-6fLSNi-(EdTUkaGjD<q0VPl*_WP`E{Knj zW0}y2G0r=(00F?@@y%iXunK;Cl;#TZ-=*2gq-Iyhk99g<*@BJD<ju2q%&%6AnI&Bn z=dW#1-eTMs-{X0+CQrKP(++#0{}wR@r5jfd$0QsENq6O;T<Z<VtaT>q!?yW%rrfsf zk-hwD6w}X*U&&WsP8bupnY35v_dXg&Sw41RRewF2bkYnr(7hg|RgK{-u)4#q3(dBV z6t2-`dH&)JXoQm}A4KNT<$g7hJqzv6SCWvBueB;wdq4gmJYdlQAU|)1`%~XldeVnb zY<dx0sLLfydDTrF72OwD#5>9cUJUs!pR6q;R*8Xxx+~w+Qt$AAmr=%dlzjs#l5Y7H z{muFYXpOTl_;`|#Tq$3@Y2pWSah*0kb=U0~*?qsAZ)mQ(ON`)lQ*w=D+?4XS@aPI? zeJ!;1iSGRaaEINP70U@Sj1jJ930DmgPRMonHcg#ylT<da3@m);W-9iG9f89&8NmR% z<cEJ8HsR^6V~Ax|xS&z_|HYHaATG8iA;Tmv%aY$#dSgDZd<P*Zzinm&fSd;KbSj1t z<f4lQxy?5kTovshvbJ_Vsw}o^cC-w(;d^r6RYx;VWn+~sKFe=bLRBAe5}~+2Aa%L= zJF9$Gho5GP<1v4Ig{Xu^_0XFm(j~1Rsf(y5@kBt|)?xz>^9v?C2W?Q(p|thdAi^i_ zhN~KCh+p!}b*V1;vi%0E0w048N=P4HY~(9I4c7jc{F6J@gtV@#Y*O+0&8Ll@nDKsk zcFuMNiTggvAPDxE&_+}fMt2y66~?`lY&e}mtX(f_9}P6rsDC*c(Px^r)m2-yA!ZB4 zZmfz9c8ZIj6Ekv<q`lJZXQotQ&qYb`-6A2z0;2P*Nc#5<d?_TKjDUU8g6`|>_F&H) z!zi8n`9oVK-^(IBSy03@yuXmFK?lf6DJi3%eX8aAUfR#^VQSUu)04Syi@!@qE{Snb zQYnm6bWMn`{2bEW1@W!PFPEJenkcNvI*2yd*wl8)FG*@RvpGL2x+r!(l9l$0^xj{! ze9XrR$ozvlrj4I!l}6eA;rh$;7wF8?rZIzm`0LsdC@v7dIXBSGB^$>r3rgsy-QZdg zn-zY&uO7yLLy5!|`R@!XnPH^A7?*vZc-Qhn?Gv;3p^MPslYiAuN`w{6452$b>h}`g zP=D*xdUm@r+<8%`z|*Ky?Exp@y7A1gQD<+Q{dj@&_O8f9n&U=4ToHa0L`iHctCElt z*8sXup~`0&?=0uWTon``ne*^J87E<2n>g8H5L`7-GF=TYC+i>EyLOG%u5=BOWZ;)R zS6{R7)^(kbkN8Swya#p&gZt>gIf~5R@PYKQ&jwRV;6C7di6MD0G|TvPxnlf$)@!Dl zpzd#2=Uo|`?AYTOYbdpx#c3fmuhN>n(l&jnv1+O}p09XTSpIxz)Zci*>bge*eThyk z#WXn7xSy^?4vk2na9k))idfjal6+ha+G}@%L*M~6d<eonI#PZEF}!cH>Vr+-$(REt zEU*Ki-c@9~fUJF#@rZgnI%x{6daQWA7_eTYnTC1T+2=L9H5;nqXBj)7Ma~+_C5Q3j zt8Ox{XcKbd5WKLxuv&V2LtykM8NHimIVTSf#rk;9@;X$#S?ps@L0aX@=Z2=3J4(-$ z===Bo>W{bNqjO`a2G=3Y%`^pF(~hAx>U(eMQEP~UZ4fcrXy`r+B=oshl=V3jaYW=g zo>>gaA9=gmU474vS&8en57ZTQdn*~ObUZXXskt&wIrPVYl;>zDd~%xaie;6n$yd55 z<~;$>+~noH!>sAByPaof3yw|TZhMEdAVo4n!fQw}s$1^2-m#~A*}qe-({Nd4-W!SI zBn$a1#`d2B7q7~w>kv?iKX-hI&N|1wWcIO>J|76GV{|w!fV2~QkJ5R1^qIe{=??GB zsk|5dnf4-qn7J`CoF4U!FtJ;>lNpVRW8}r)ROb*o>wxBhDHbNW$(<foRBm3$;$gtv zUsLA_s!~>V-y|QCf@k^6Ov>rt4V|s#2U39<*6&WsdgnzkSPS3J=AT_rl3!zar1Cus zOW({Xb6v<0cJEKjV<m^O16q45Eg_c8>Ac}QE@4R*KQ!&z3%Z9KUJ8Y(XA7><$lj#w zU=)ylD7>r^6R+Accqtgv;?I}iFVLvB%I!1k|D#6Uv6HoK!eq}(?<lMD&fjSYjm1Zu zn^wmf&0LK3zr8z#HZ{V+(jlaAe);(sc}vx?g_^v>b5&+R?t6?NO&jH=8FX@7kvss7 zXxNND4~lNn>QZs&j;!kH=l{p9_dMqxbIk6l@1|&7#&Ogp<3!i+I`%m(a1Y_z5!AX1 zbFP_#wZH0=5kDXR3{tKmRJt+FG~3m%)o-v>Q4xLaO#ZC(>!g=0zD|=!k$(e!z-tSh z`K5E9>h^PNpDH!g`k1e-dlM9~HMRCOg8`*~c}>=*=f;IJl71>lA4wV(C(DxxKN5ck z7eX()&JoJ_DCa8%wQu^2=|C&%PR(H8OlXUVp-s(W1gaGqdbZZ2G<E9ghGPGG{a%Ax z(s#2BsxKmV-CZ_r90@Dy7b?P4jZ@aV|Ew4+YYs#(%2k2QF@s+6+ZeYUEhC6btQhd_ zn(_EF)-5c_QXV=qf3-q*)|y;h_`1nasW_!Y`+Zc@FXXMhRItzp?oOi`3f{&nczxC; zHnc2w&bIg=>Jiz<=Rk?Du#fYCQ*50FuRe^KwCh{{HLl(zUbHn|QI86S>!NgD_c6cy z@(DKoQSm2znHDL*)R<vz3)F(EKfKyjx)RpPvZk+HS?iKo=dk_z&@PlY#&mg1b$)y* zL$rYUY`;&nz+5nG3RRZTKZ=G3c2$qUUd=~Io$=XEu5u=5-bF#IoY{fKjLHTbk+D-a z%qVXTw!T@FL=G%;3DpHN{@&9%-7#NBTe+XAvTD9&6`Y1FkwSjR$k)vd+g)#+4ubub zH;1E5j)+GNASCQ&_9NgS9|0Qy`dD|l*>-mn+#p59y)nwUEXuiHj|cdW&t0k03`Dr= zwO$;4IWG5O^R9If&C#V?s;=01zqTh}^nK&xN%Sk5Y0aFk(5OX1ODUnjUURZ3O(8<G zd!u&K5WbG!QPR<{iR)n<lvRojw!AuSgn!l+s-%cG2Jh*mWZu)bcos(fq2oi%qi5Ox zd2T-Jr@_|f@cJQ0slJ#KgmB~I1CXr}L1DZk9`jrpmtCUG?MhbeGJOhvx}@Z+^@~Z& z@PisHuqWh3-g}B;S+%ZB%A>5lUzctXvgJ2$-ian2A_%EDO5E49)cX29gQZCD6a=xr zcRRXLhb6num1mxCV9vdb4ysq8_Wk1D1HivrfcwAF#h|jNH&v;3KsLDozZ(7J%hJx= zRrP|sdbjFah2qb|%?_PQZmt}&#jZh}>6LS@<xBnCrTN!(m)RT=QG-EsSwc2Bb!E8) z=Tj>?am4B4LCJ&6?Qe#=bQyS&Xha#vDZ}t}c7NYaUwjKJT$}9nEpOHLz3GQ1+ac6) zOG!0fNrIz!xSYccMX9U|U(9`a@(B0m;}}!#@!Fv;1hpF!ckT^i;okXfKP1fEBKfq@ zp5H#4Tu^5D_L6g8;sbWS#}=#=2AW~e0{Tgf{8q<N;r<JoJ}YEpt}-O|6=XKIU+|L? ztK`KucN18jot)%k#~2r<)Y-U`#n`!(S~mvEBgbrq<<iGVC!45l{W%&Ht76>ZVAYkM z`uS*GiNwk!G!I5QWBBY}t*RF5%P(_Pmw%I$kp%leA{5Xje|1sQUzeUYc03xk7T2?h za=bfwvrBRr=THRDVB1a~&#Vv;vNRGFQ@WNJ9S*<PEZ2iV2I-hyme)qH;H_t_kDYzt z<+7x>Pqv$RZLYjac*>n8(k`>P9h(MzYb1OqSgXeGT8?}yeER-blR=Smm~l7p>}r$! zN#uCBQG3%&K+Js_H*KO_q4bSHBm>Oh_zMbwg&>|-lv^nMk`z1>LU^gO_r^6y6=F`h z5tYn5^^ViWmucwjJ>4U``^f`PC#!>aD;ahBydr1IWZAaEmq0?Td!+Xffj3%d#YVpS z?n71)NWwp%Z_odbtfRuO*YGTMYLTO;;BA<dl0c9dDqcRcTlC*t*dDyn_TUaLOG1|O z#z%At3AtA<J58vN)Xx5ch)ixjl>f_|Cb1g>^hTLFPo0IOBGL2rYfEpk5RF)lVLiKI z(hJes4>-cLOBsv|<hK9m?p>iF>A}1hFQj2;t6*|@(OR|Q5g90d=%zGOcxB+~c+I&D zL&YS`!Ihn;-=sSKaX#x@x|i|L^GjEQ-ly3Ns)TsaIpHz)3g`=|hwntK*)o;S1!vOG z$Ga{XyEQfiGIRS1q1wWAnJ`?B@Uf!iI>^T!4d}8N$rnuweg2Ub1MH;B4l~WKn;F@? zrfDD9gfyOokUjo4X4X!By|eG#DqM}WzCU1OL$<uIcPT+aLhNbi^1iKG;9=0fO?)CJ zmQ9@%`(}KuV&f-85h;~n>fjLru<7#(7|&NQHm=kt&qGR&eO6KwRjHWC<746OpLalN z$^N)7`II?(9&~na9%POViblY$ZD8j=ysF*$pPlA;jq2*m8xDoxyj@$+qAi_#iZd~? z7BZDr=K6qxgTn9Kkt-I4xVYY^|DkZTX|itJ7j=Ak<}krFs(a!G_kgsKqTE}yK86eI zeB0$lXI44EY4&YYuq7Y%5%${S=b97THCw?k>JauHkN$hpjq|>wtQtpaY7Y1MlI3@A zVh0THM|vgl#G^f9{sHU!fShbsy(-PTsrZprfSM{Prl<3Z{k=L53f&hgx9t@B#!v#} zV=V2RYuQay3rk@i+}U%bq#&&$aWaIRtk*xyjdY6&w$P&p%BZd$VuOeuDFza{<Kcq$ z&-s%k3M6!1r%yZ4DhS!vf=%qejH{sP?bT{J^Xv{+2&~~K0r!EDCjuu}UET8fFga-q zK3goarWlbGfn$6sz{&$87=BWMdcFi-HGPnF?R?dnc3iBR6h&lJ`+3*3+YFt^&)mKm zSKAR2e?4Q_lf?Y+zjx;E;I%8*7A$iJix<-gKw2P^W*i6Db!sMh>~=`x!}~4!9$JEL z-pItsTjx6Wq_O2BaA}aMW1QZcRGN#TnGG<aR*)7oVREx%EwGf+iMLyc!m5*1@5+eh z`yy>CzZ==)z3S-kvW%GA;2CUaT2RwUr?RC`tC9x~UxNBAU$zAQ@p*%Vo4S+8Y*9^R z!-#6|j|#Y5L7@5FzKqLe;)QK?Gj)5Tv*`l2L*KfhlU(rb+ZvWn3^-z)lv}^BJO<nN zStpOsgz!SUG)Q6uvg~jXv%V1x-_qBvc1&fm3d**!WDW1IKYiy5{6!%)KIBCoT0i9I zlZmgS9%(fvT}^vjHx;<WY4ZLio*SSTKTZ-{P_Yh6<oW)<SYz)cX_8WIkAPoT&CJA; zyFK<}VWUc>?&7BotW^zCiqW3uO5RBC+$z#=WY!jPO!<#E$-X&5PH5hXev$bI&9sX= z)^Q~QHxqPQ9%M3bJby?cqQ27RK>Dh24R+QaygN2Fi<h^YJF9t}Xf&qv;x(DlALFty zK7sQYk+*3gXAAMfD+rGh@%r7b8CVM|1_@7@GRHYH^|aW}c$r=wo3N=DCRgoi&3>DG z!W=~SQ$We`^Goz<dFRUp$Q8+4lvt%;-_!pYb;%@p5x6=LK@ItFDQ1?M9c`>R?Yf!5 z#JUE)H}E>+{t+{yS?H&9aWUz=4uXDUehZgtjUZ_ZmP|sX#1E=`-P;SQh#%_@-ZRHX zz3R6t*m=23=<iDZX^pEgLbCFtX%o#<1?i<y3%~lqBeKGkmjSO#$s1!wFpnn}1YaED z*4ci0=OldbYyRA@;q7q?8w!!>x12jH;<?<wF-ojZd1{Yc7IiFgwQ>J)5O1FDIHZ9u z`+>27D^`jZXR(kf6duYno=&7y{ei#1CBw4H6~Vd%{baVXi!0`YgTp&JTAcao!_IWN ztT-!Nlni%W>h|9d@ZE7od(Ca`f(`Vlt6oBPG&+=wC<8&7(IdP1`!0xI-Ke&|=v)a^ zaSP(hg-Vh{^3p_4_Y1ANLpa72;&+fwvP)ev^=32EpEnnbYm%x=I!2<yl!L2W)QgCD zr8_2Vjh_8Dt0wGy6jxSH26sGjPrFAb*V#a68}906jLs_5H5YNY)PSiL*3eF^Uc;8< zV2<5vs1`lwF4kgT%q_oLTDRB7^!vLR8FB5Wh5OHX`M)J+#2l(K`M=2W$7<}veVuF4 zW5psQ+Td_%rd?^7Q`lgPSbZ<QV?~Vo>8Wf%^~z1)Swo+?y?=fG&q!CNr~kR|A2~uD zMh?32=&kB951*16tMl)r<m$1g7Im7xmMk`FPgB|?Zb7R&XwUza?Vbw(d$wPYf*i1k zhgfZa65KEU0&kmoTd8rRk#~*6h;;L;WNBP4r7|*4{?QFLtlo=LacoB99a2a-3D*uc z)Y@cOPF9Jk;OdwY`dQ3JFKl14DNXI`(=D_*+xM4#7CuhpAKIP0%%5|*#Bnhjq4TsG z<i(lEeQT^7*<}AoUBc;za1&~Ra96sjWaDp%@y@3XIy`7bv_i$Cngh+JxsLnQd30%O z^>PYz$FuUrS%<q;>x^m4;Sw0D;xE^<=5Xi>jC1uPtiKrX0KNX(r9$#^a3F{bboM}s zx5~&9#~{>+Nu+K&MYqbaL~<@}<sTe<aQ7E@&L*E!PjpTYvQD1;B25yoivN|z1W9|X zLjzQoyGwJ56jBzcoAT?FNzsZNd7W)mI-d4_GxA?bT`nNh7brp@9w*p}#wucRc?W(< z2lyVZBsEV>!e=1tXikXI8X?1{L3-+*DLcW=_Kmkm@I1U)(%@9SwZmT}_L7TqSuZNY zx-}vfD=fmHF?;4$f>uJ;7TT~K{W_?2GMjptTHcv!kJ)xrH;LU2?EY7}|29{=!{5G@ z+@+JkE*Fc3!k&{&W`3qto~%%tg*!;~Z(J51&j*DgpOhgSYwmJ<cy;^PCmO{bc@7-T z``82E#11#PiLXXN%dx_Cm@CThsb2p4!OF_5<A&2SN7&gQwaP#UGqv3|(uTz|NW;_d zJO4Y17>3JMNYc<Q{Er`(7f%6qb=t*!-K4xba`qUwZtP0QnDN-~g63#Ym-pm_qB#Wi z6?Z0Ts~aJL4rmp2o&M!gy|-la#;Q~3vJuAw{hQaHwLoc%Z>nQ;E+RkF)AqoaTGDSW zuE&Mp`G2qY@d;NAOS0O*G8y}@*YvS8P0QiawyY3j{S|0EPUigS_{Dfh0&;H3unYE7 zulYC*zbd2{nj$pVV%IUY;g!_pM8K>nVw8KXTJe(9mZ6?`95We-K0geFp)Vd+LdQ&K zW>dMg3rAc_9UdwZ$1BFD5D493D7}}pf9?~!H9-6A4?a?{kz#KtW`Fa?h~}$RjTE-( z;|8ley7G$XRg+%gD&~x*Iyj?4Q{%VXc<o>GP?R|=`{7jo*`i5oD2J@GZV#SzyE?R< zy(RENi10IRs60$C7x+@NE`tn=x_Y<Qj>i@9Ux+pPn@-HCYxHxo48dA|u45M|w%LOH z>i$7%A|7Vk#mTON;(1K%&6~<O0PAtuyV7Kg%H>qTezAgAxovx7th&mi56Kw6VsGrP z$uqsIoG@G1K}BRHSf_jmb5qKT#!O|2d_!EVz+J+xmV&Y_;57%GW|n0M%Ph~`p5z9h zGd){w`yqh#$Jo{AP;K{N73KmK|3>Aa@BU_`m!EO{cJ0aEW%t->8W*UTN3FO%D5_!8 zF8O4>);o6B392@gr()8p#4+rRFfm`ORo6h&Le>v4YG=q8+~;#&nM8JSE_<2m>~1}S zghXb+x@2~GBW!Au2pcZ4rUTf${xi~*_ZsS=dPgz{&HKBO)zB-?tl#X*tv9_WGLyfy z5iyzk7S2K~lK$RT=H_@eG6`7MvU;%@@I@>a<+3CQT1C-yzqfE{lqbgVU|VG!jbVP7 zKA;i)#KlfZ`ST0By`#S50{A(1^knaN5k{omA^dI4-j7ZB(h%+|b%zT+j?fRnjf025 zl)3{LNP%)QtC4>?yARWRgMHoh1-<KTE6i4s5E*wG;r-4#x^OI_lZ03Ey_I?c3)Gu) z*hAWGc9aJd#_JD#-=9E5gtiT~<u%+fdNlKkmDMN5HnvquL-7wZ?Or`5f@D08T$A0? zZZyJ0R6)TQv4upqmQqcBcKR;>o&B93DxYYB6V4_8FX^<y&wPig9U%QIT<dJT_p;h$ zGH#zWrwMTrrpOi8fdQklx=Lo6EAF#f9458;7nVA8EJ_=Se1N?TIvU&5zXxf_^nkzZ zeJqYx^b?~PwW%0AGcy(4BG?+FXjI}D`X~8(tGU{(U0QTn`td=svncG$clK;z4-0eD z!{+~#!{I#IRJ7TRZD-i(;_!`hJk^MX&##(xqSZF})f9E+>#_>EWGDG#b^N~GyAJfy z@q~)q3BN3rqRz!*6Dm^^K99%SntuY1w}K#f8(px`I}op4-*ujg&>-b4;+^5Hy}*$I z2loMheLpY*wwWg?l&3fa@mR@CZ%~qJQiMwqSxm+g-9NPba%0dMnT`tl8?~$`iywOU zK97%xkLpW)!8|s}^aQA`chCC(r^|RzLjQw9S|Kwfgt<18g%+Q|DgwIhXH@4nzB{j{ zd){i!>o!<>G5cxSm%sR06*GM?`hNCwz&~lqwCibgiWf?utVcOhx;IgVpEM-16+ZVX zk(CeQQkGwnuhz}UUd9Aj4kG@ErlIc-7W-&<N*!s`He+P=X-6f*s^C`u6!RritD|SA zp~?K(n7i%u|IC<oe6A#lXKAbkl8}>Nc8k15$m-zK<TxvQW`<ZLSpf@35GP0?O;qW2 z)Q!)^T}@*l%1OzNr8RZ`zC+tkcewd3@?oUg6VW!^oEO%sNdG(wwSWdd#(xufl9K${ zO~hyp44Jx~g-i2myA@KOoYZWkS=BtniF2_ym-Z8>IeLrrmE3NzU~2srhdZhyF-!n7 z-0Ao5c<cE3KU+lU-7=d}RxlFOtjKufW!>E#b-ku)?la5~tGBoUm$r=eZ^&{8m$9so zIH^?GJ}724VY&4e^i0vjoj1bGOj*jVI*3Z>oT6?+rbuG@$Zd44AJs4$SvY2X2J~b| z%s+RRa(>Rqdf2JXrz_0)^o?_4`GzWbug*sqXUR@CP3IaSrr(&ZMx_!zBx3^udS;G> z4Jf|WfNF5HFt7Dx{tV+}HuvkaxiU*&BHIl1-R5hWxp1{+<&Hvt+yy_dQ2t*MGy7X> z=QMg~XOtj1LBUuUr!8H_Tjp$REIKc7LJkYtqXe<27y^Ovq1&<}1CL}F<11<Rjcr(- zd7x~=!^Oy65C_`d`_}a#^1eU)Te3!(HPV&Ra+_z6$Z@SPlS^87^d%azo_@qL@~SJU zBGQ|5c|_c8R8D$mHh6~tj`e?HXg3=gkD79^T@KL0S|u9Q{2}Uvbf}$z^Pz`%eYZG4 zg4toy7kyS%TBAUUer=|9Tl^u+hFOe)kO$kb{`KCbg?gDikJH15&dWfx$iPaSQl5s` zpll;Ju19SC>vpD<qak6a&IT$mt>LOebNfKV#YM%3bh6!_FX}E!fQyAH;W%2p{$e{( zixOxweepj(8Y%#>Ed55amNDP(&jw+D5|$FH;6JD_RyW0`-zEEQ;Q;{(qMZNaCb0$? z^KL?>baMhGx?$DoVz_Qycmt!3yMhTj&~B23A5*Yk3U)Q*v(mv&FD^ESAAsExAmNUw z%Se^LloKT?;$9-WPbtEZ$eFh(p_$#L)~H6jjM;~n<%t}euoV&l3x_^%t-mFTjr*!C zP&JHrf35luMOiGo?KLq60ynS|gYa>xUcpbd2Cpr<Yy8BbEtU3joqmi(oY#(7^$PKW zlsswynhf&p#-J$8xDz*GuZskMS>+bnEDs(arbH!8Lf!JEXkQjO3Ei1cyU;}lJNivq zD-F6wHAI;rf&!O3m@`fYn$0O$M6@|5d&x5Zcnp6a`U^Hz|5O)#_D^?@{j%Q=E%E?^ zXUzC9sCdnzRWBUhr(p5LhE>?k5*khjxy{;|wu+3+`637K53KS*-6Zi-bB}Y*IX_&& zM~z@np8Z1#+uwiR(qkxl8k>jWq;JPGaZ$kVXQ5JIs;uaez=m_V8v9dE;*U(xLbjJ2 z?ofN1Uy^JPU6(_#LIO~i9{iV=Hyb96JFph~sjev$-en<m<9zG)?y3Cbv$t0#g<9o5 zAKdaNsW#kJM+OxbDW+eFyS=a|w6d6EM0N(;x@BLM8El<LIcr`Xh0|~Fjr~@4_7zso z#@XO17ca4`oq)7}BBV)1QIsnjiS9`fI2+s5F^Oi~?p5#1dB;i9Tw2i=htrwC4l7DV zV*{^Q|MSt1y(yb^Q+?M<q<<9)dGIflUXge@r`Bf1atzW-2i8Q={i3ptB@|>`O<95t z2gp?U&aa$mElFzLbUSlWd=IEzrwKyTAU0ogX9y<G&AS%aDWw&XyCn{W2)&}0Gnpg> z45PvyXMf9o)i;u@aXM9A>{M942cP>I&8`{pYHZ2yrP4MTA*WmhJepCW4nb7u(EqS* z0zRWDZjP~hYIG0axFzm-<531={UkTzFy>@-+8p<dq(=>HZ35z@E8Q;zB*F1Vo+Rie zOkQQ3`z^eHUJL%13};&^hV5?BXHxH;jPD!B5*&`mjN9g^QRH>G6LoiPzdGy8T%_eJ zBM6bS(kxLkCY0nf@s4=D%nZCXou8x^TiuJ4NSx%Bp1-I=Z|@rs96&yx*T^f!0>c_j zT~~bTSha;>A(Bo^dLS|Xf4lp;ZnBzUUY2dV)trn{@Q{;j^PmIy3AX5lw=aPKu)Ft+ z#eiFn2LKLR>?8vl(X?FMZr$?v^14(0A{|-*&ZnJfb2yo2+nSDnvQf*Mb$(+5FhLzf z8#*T>R^gKw8?2mbdP%zi(yhd9alLOi03)SNXL@O&J%OL)CMvc7559|gUT;K@=g3zs z8!JAg8_-*)c~0*X8#@!9YXsJK^gjN#=g}PIE9617YSGwldNQ2y)w^(hPY^fh8;OS! zD;)JCiB2JQ)#Px$oSN(4&^puAgMrDE$NC#?S45na@n<>!FBgLjb91cK;_C%6k6@Ir z;#~A7h{4uP%w%dja1T{*iixM;cD+}zlaEB~#SHTU9zoT;No7k?Yn;hPD;fjbn!%Sl z4w)`x!%kfuGa8L-9JtBw3SG|r_{@7JqdZ_&*o*(c8{U=qsOlP-!k6RI5caiwJqy1d z3ug~K!VHH*gfH}6^_eCbH`OnD)aC(?a7eMOWa?r;r-O{)=ayp9f9&asKr76|K9O&` z9G8=-XZr1EBlEJrt8zf~co;5ze?bRn{{=cPN8yMIke6J^kYsC4y<;Ol&L^A=5V)>? zMO)RCO?l{ulz8ruwY{WyQ>cB}u5H=Ovjws;IGh^kZ<NwwX94t?#P3ZRI%S(=qLV8_ z2>!8osV7$aPKJQuwBQ<3ZxRtLtjuP%(jV)N>oJ%+Zhx_w=cSrw!h2X{H*kO5_TkSy zoa*I@-e9Ke(mTXb@#8wKtC&|D9p<nN4Us3@355Lj?U4Mw^B~Au(NH3z@wrz4`Ah#a zP<o85l>Kr>#Vodpt4)_Y_-Oj@&)U_LGpmVRCI%Nsxc$GRxkrYTvwF2fR|!3q(2Db$ zoFK-w*h4y1!RUx<xFkB*6kXA5>7w22%LI5RW$VbU4N*LURP^oOjyMbJKNX%qE*lZH zeF@{jim{zt=i12%D3Uooj9MqEz`c#2Rcg8n)Y6%ApY-Drhj7L6ZZH6il9UUd<#aPv zs*=$CA^dIW;zx{gF7=oDB<qzGNabR3ykqF3W)$PGnz5N97Y{Zd{_a2cJ&~turiXiQ zkh1#3vz28}-(r)ZPM-pw%_ZW)0NE~FE-cF-SpWB=;sOOT6~G}?1}*d-XDQWKjYX?% z%B#8bxTv$~kFXF#5Ty`Q_vgGio+?PNT-&X;E}ptrL)1G=I;>rZvpw1|sxUe>hPDs^ z<n?nb8iQ&TB`VUI(<{b9$zXCAUuLai2{#1|Gj-$j{?-+740E*lS3wnUFl_3be|ZRO zigE|BIiZY~AKVWzd8IWV`<vfsdWe20&0PuM+<|TGX@`j+SMRRZI#bPx`H29pU0OG} zFh_lI@igfgQMQHm6Tz>;9_=bT+7Vf!Y9g@j273L65yO&?=SIFSV<Q^1^5otzrMV&- zP&DaWHiL0usC=quEyATrEWMG6@gXMqvCo6L6=U84h%$vYWhNE%dk5p`HZkgGp&UfT zYC!LR>HKcX;^QgAwMsuzLSBl^6j*k>^PlvlOSyJrISHQ`xM|xaeMK4V$15Fckj$6t zE57R;&q2M3P<gM>T9T)#`5Jd~lGkp2yY*_BrwB|OXSKs5aLShKp|R4>LfCfb341 zBN3hH`(3I|S<b*>@@DMDn7r|X$vH)s>*(3r^9{lJh6)NfRz}f`-tg26OI-1T5j#9Z z)9!eyz<tmK-TgQ2)QfXIKU;lO#x=@STmqwA{+-S)Qo(FA5V>kF{p-W_OMZ~Tqmr#+ z?w}l(oku?*Ls=k$Ka|4H#PSYu=M*<cAh^(cygp5b#_m=^`jr(+0t7b<hxtYAWCJ!} zKm|kAc>YkHtVZ*TSjU>qZEcSDJ!4dPO-VO!dLldI<V4lk%ujjt3;>#YsBX?PkojG@ zUo$3&_;Ht5N+Csf54m8p<>X1Nj=-CzPVxku_+gZH!CoewHKsDT^T8bD6b{1PbSiBk z=uVagplyBa8v8(aMZ&cENL10n7RHfVnZT>7*aN%WDZF<1Bw!v(Pe!&JQUAKkDaaCj zy^8X3Wy5BFau~BNk96GVnU&w}ZfE*ba_7SM0yIfj|DIqD*@UwEc8kG_gq9qbc<kK| z0SbLPPSddInf+fs;)!`<%6?!0;@obF7l;3tJ>G`qyO9v<wY3Nj@KzQ@yRpkK*o{A) zCh}Y5x7Q!N5CGHI)rXUWopr2~AVE>NN^$;;u<Bryh{GigDQRE-<xT}>EKb|k*BLYm z!fy9-KI!U-k$wYNUXAx|GE_k3F~e{#GigLo7v35kr_K!K;P@N6FoM|Q0gu1HSAbls zM?$yW$VT41iTC|rMJ{OqWq0Y`Xx2HB?;Zb4qfQ`F(Zgt<Qup;sCR-PdDL_ZWdhU5= ze3yw~*1GY%MJzp*(Y&mlBUSS>f5-DwB5m!A@m|V7G=^)yly*SZ+zfKf>C~UK`WojB zz`^yO`c!kEGNq$)5){~iS}l^Tapff5=CabfO_ku=w(Iuq&=Cg>wYbHvgXh-Gco}+7 z2j-VgTMa(3&p7l<8sXS?UsBpx!=ya7tD)=9&e}IR)DPA>@<ZFycer>J^Vvp4fPfO0 zBP#aE9xS9RQU+qVQAXJ>Qp4(ISuibo5GaQ%UqyQ18{-?+gE6<~ztxBsJ}pR*rYhy0 zI!QV@|IZhymD9BbB)mqbNH0dF51$JNn0e#IP5XVPlp{~$!U&GtRWWMIFq^A)ad3pK zMVUfispkatEW6=faPqglX!k9WU~C3488_8AJd{~Xh8`E+#I44O-0>L%U-U12+u!Hj zbkRt(sFh~7uL1e;39GQ><eshcds}=GK=1ayKEIKt^vbjKMS@Q!K5g6gEQ4<%2NMTV zb-Q2Rq|N^1!1f5|%;<6ELT$N}Y39j{?Jh7m3*y}6$va+oV{4Iu2v`AhAT|N7qKRTg zrYnznY*()~)~>!a-o7*luw1;DEXc~MSzn-e<qW*O+>2JMu{iznD6he!`t%IJXR;{N zW<YMo_=h%mvnX&rqU|fl0`U58p^PoH>>OPcS?)a+@!iuy3azrdxZb{^cDXh6QU^5g zmnbQfwfKJR1Z*w?l}df@XrerP$*;<neB97k$BuaHSa2@szgz(S;Gx*{uI<9ko{oXr zGT(P>FwZ;api@_+hAefdWw-1Xr&^<a+sN)Wjqzat9M805XKj~TS$8?unwf}GY~LPI z;sviiZj(_|P9Xx>rC6+g$IHo3G9b~jWXF;0(ky?z<okV;qoGH-qpx;Rkp|d)bk4WH zm?L>E0%>TB@2B#IkfXeK<*n8$+L|-noK}LE8UHP0Zz@a}2<N`V9q!h1w=iwTtyILM zbq%-mWnT=vKQj1fw1w&>_k)+Xz~dQ5{=@IIZ|8G;3#Z!dtW^&9hLn=sqk5yzvf0J@ zG7Ow|!l5|a^l!|8YB>}|M~!<jA)k|1{)(hMQ2w2VeO7Z`nf1t+m<Nny&UjWErE(I2 z=&cF1p%&7auF+bq?(>|TTAWrvOt&2TD`FIH%M>n=8<dH=vW}BEQM0{Wy|tKLs9FD+ z=82JL$dcO=g!s)mZC9rMKdQbmDz0tmwsC?JoCFQ-?(PH+?(XivEy07kI|O%Vv~hO} z?$%gv3-I+h_uPBl+hg?qy?a&7RW)l?6`Y`GxA#KEV&V`_5K1X)%xbH3O=(>Qy>cKV zO#7!UQSvTz@1X6ezS#VaR0f`zGyZOoR_(APIQ86Lr>Fc|0HoEB@Q4)oCz4>mamOMm z$9!&CYS70tU0A1p`+*QzXFq$w&BzOxga!bLyv@?D@@OBb<D<*6uSYaJf=9!}a^93c z6P56e^fARmC|t-)ljpO9UWS(=9Qtyp4&owYH@-O6rI^=U6IWCSH2>G&O(GLAt92VF zI=7GYjr6dQamkW@28j>d7W?G57DhvXWC<-3Az}pg$$GddTTivzG6ZOBZLlDb<Li%9 z#bE|>(@4n=cDyukpQeL;&Pm=iUhixx_+*)LyMfml4#zsm=b{9T4J>9Ljp}M|tNTy! zwv(I_+3F{WbKO$Z`$M{1>*p&0^5+UATTlS%0r`K>)7rn5Ed3@Y>bczLGuNf5z}H7z z#<<~|SN`TW5IR8Wr$|LyX0vw^idUQs0l3r7kn;GkGYkjE4A(rNpj70-`zJID@V0%- zl}djOCi9;CTx@8OA)8ry1FVHoCSd8o@q_?i37YWKo_HM%O;)chhGRP_xbDe>lPz%+ zeyblR1PYb{pa7xL{|UL|>8&*$!R}+_1I7pNti<xPMrDY9CU>^6o}PVj3X>p(DmvxV zU^vE$lVayV8v806QRvyZRdny0P<bX-&0+gGmFPfPmrae3YR7YdBxv?l?wKI<F}x%k zU?#R1kjRM((wOzFd7WwM>^{~2SPl;JF)KusI+T24ZrVmrL>Z2nB-w|&FeJDA>+dmY zV;TAK5L&%nJMT7V=W%ZO=j*d8eFM1bErwB??bMr9@GRaI0q}^wu;3@CVcTdMq@Ol( zR)Kyk(7n-dmKRLX68D~=O&z)0ObeFk@vh13LmM`wVC`ApD5AH6(%wN=dBZ||`_2_I zt`@@%aNX7q`V$1Ssajo{*HT~OZ8fyd(rB1a`D|A!4)i=PzS5@B;7LbAu2!*s{wzE% z=U+*<_Zux15u*T7qe^+NZ60AwhB18sU%i&~mQKcxYi8#z$otM~02b2^R#Ri3gQf{~ zj%ob$l0$U5{V#T-<D;N%>}g2?XsS;CDFP*u)%wk`-I(RPP;d4N`&bJIZ^G%hv8Gnj zUMdX$eOU5edYZj3XfG;nN$(P)9vHHH5lMxNwzeORFa-eS|Dnm|Bqs;4t|hi(t91wa zNe7j@zUfwhv~&DC=H715Gbtd+U&6k)_JkQR4ow)q!sYf@{li(p0aJ$NGk^!^W57eh zo>&pjWi0Em``gvX2BrJUZ0FJJi_)n&??XL^2L)Iay8tg8Wv)EcuE7vTknRFyRIlU2 z973<pt=G!2v|R8aRVrDQ@rl#=<gSm2eWxAL_V^D?T7sGSg{4TATdy;6izGVN8=j`7 z)0);4vg2YGVqYy@8M%tI6thdv1h0VcQ*Z+#{e~{?{UV{mignhSIKM%{d{PJP)L8}2 ze&_*C+Izn}qms9qex`F-6rwEMGV|%G6tg9UGsb6t*%VwLcbmWBt>ZYs_-32&cbVL% zIh(^1Q*TQwN`R5se*q!>y`UB^b8CIgP;UWoZ~#kJBm?FxslF#|n*S3C7cDOG)VWJ+ zWF#y-An&_}=1mf<qeFa^tcqIPQPG1y=UI3rA)6-JEUL{aD~!>sl+o;VVa>_U^{^91 zD0M8yrmKY9fX(IWcjIt@vK6_7@)~z#H7m6o3MKGjmQHm0WxqJAy}ynL0ryo0AksGY z&cEe*X^NHUxK9ETSg*6+<y=@O=?Cx;g!W|5*q64pmu^V9TX{<-QIS&op+NFAe1-C4 z!p}Vm$S#=^m`6uNj?{v6FUkghyK*%zXA8bS*)ziSllX}j+N*@Zx)}ozy#=j~=8?;) z4=GEbDnhdm28xA@FhOp{G^UP2ztJ}z`)7c2IZ@9IzN!2p%KR3j1`|3!NARB@&ziB7 z%qvMZa@y}AQ}gh<iAE%=;`eb~Bt0FcW^iAu!0$=}-luZCi9gP&3~VrI%j%X$lL`dx z!MKyckhX9zW+5)=9M-B~N)mKu)gq#*Z=h@njLVzxZj^P0`USmfNP*v$8uFF_Pk={N zMoa#8BuGcwLPI9Dn0U^;qMq}eZ@FRCl}xu4n8fe0R*z#F5E%boYY%TPjrL90E3sX? z-$#rY9_YbG*7W~a@4uG9c=~Yiw6|&RJhsmw$R>_zbPx%QX~Z|DsyaTYs%KXbEC_+V zNw$2V9I#;%cI+>B03=o*R{m+QM3WhaA1qmc=NkVF{e>RO=G|78)!7c_XGAy%I&}G` z$Q$GcS-9wTd9!BPI*sm^Sv8{*lMFAX(Mmw>wg0}CBwC8RZ2(oeEhHUUZ?uqgkG>o6 zhssW>dt$aeT5FIEcmOp(c$L<QGkT_)n6JsDOJB|e0crk_h80;dg@K%w$`+)R{3mgQ zSMw=jBEdy@;IUvTHL52AU*P5W^Po#%A$t4qrOzswm%vx~eV5Eb8ToUiGOo#LI0wUe z6S6a5fV?-BBcp4+<7RDiRPY>_ezYi?+8~v^1?}HVt8JKowDK;r{p5gNqX}N^a}~4J z$NsOhW9cUWuczXVjEMu-X|`-Y*_msv-~nf+K?bfsYdy}4v9+<gMGEK^r_V3^BamGf zWR7VRwg+7~O+-;>M&#$+d2vtGY&g111w$P(<F~gH&qc~|@j4a?`>ztKTKuUIBw7No zq{M)<8!DluT@@9kxt+&`iV19y(lZ~2sg`p=u}etB1pA+C$NuZ%RufHLfcpfv5nqb| z8rRZZZv3OkpM8;nXOE5|h~VP*AVEy$E)IQE01g|HPsHn1bwGm}D{&buTa_}gs@JA1 zY15F88hsAEjjp@?2<)|xFTtlBtxoCJmjr7Qn{wg^($NgB?J>P<zI7CO=t;1`yK;#Z zL@zs#cy>Q_3={+cKzp&Xqjed2c>1-&I`j@(W|Bj;rks(G=)&zEFlmfuPtbXxP?+PD zJJi+sDs`J})MqviH&}*<O}EId=Y7BFFD)H|UX);k3Y;is6V#3KQ9T$pg-JWVHC><@ zyK+8m?Bf{_+VE34lgrf6V~b6IlO)-j1z>p{E;MXq$Ss!fwH-iWZxN+)K`mcx-bn5< zk;0Iu6n_zQ(#7lm4Kzd;fV|GaX^x^Vn_Q-YNp;1~oEh16hug2`ZZ^NF{c3oqvmj~D zf3Ge%s(Xt^@TPtjn;>m)aODFIPcP~&MWaPH+fT2DZ$gg)L!HBMw#2TB-8)B{q2vUg z0rIZ2$*mN?HT|C8YF$^41zecIRPuG;Zn2sfWTug}TZo0THDoDbTnFC;8I6pEP1|u! zn5Van#n^`hF=eEU{c^IFOXAfPpCz!lpxrD~;K-@A4?DuaV!0i=zUS+ECNw^~%`uD4 zweV|`w+Oc<NC~0uzrkcY2c}jL*mh6)*m48NCEW6qY8wQsBsU!|uJK06N11*31v7OF z@r3=>HPZXEUDr92a7<D(qYSyBy!N#(p(Q2l7C7!C3nYBjhOTdC=V2ag0*CrHRO{SZ zKU&{hQaBR#PZz8kB*kZ|V$a5N4~v`e=UOAX7$Yy6_w&w@#0(RTXPcsAAb6R`E7U-` z5By1<H><$cvxP$Bf$l0gYT7ivSUT6+D)9e!zl09IL-sp{`XhsSk2>q~N;)40KeA<B z%MZJtN+hmpy=j-arx9VF*1INU^Vx+wc@3(0xWHpwY20@wnKr{WlgQ6sI%QwN6jzqg zbS9o#PU)3|YE3@j21ZnMM8$t0u(M`MjQL11ZLfPjuNYU>Wf;>CSn%;LUJTVXWmxyi z1r%Vzs*a1=CWS3Kvwd+gw{M{5ryHhgoI}$1UcJdLcmN1v{O_3`phgw*K6hG6YWt*% zfUkX{E3A;M=?57RjIa237GG$fvD6f`9M?T1-Y$_d*Ia-}-}SInm6>Ua0P+`YtlaG` z>0jE{5XnQB6su5V+ji4m5`0#ELELvEZzg$6P{U`+h4g$Ky>m<ad~T=G4ibABcpWl~ zC!7>e3Ibm&|G)qeDYcT%HgLY+>a%wquSvSq&WK(cC@Cs?;NMnF_^2*J1B_Z<5g<Ld zkf$WfJFYOfTU}|xb-#S2yuK;m9sUQBZOzxyrHi%lswpBnZ7>V6i)1xXptYf3Ii+^> zaaAglsVj<NeqyRer`@uTR{K*d5J#UE8Zq!4v0?EuGj_VGYhZ_uYQWpCYU8J_MUBT0 z==l}0R^MAOwj&r2_OW3par6G%u%6oFQEO0(jwN&KN#;jognuD4wDmYcy#)9pA350U zYww3WzuW+c1Z=^@D?wKY?!e<Jlma)oAbqL{x_U0mqNtf9<j$X@ezs$;Nh5Rmir<)6 zw(kuY5_h}_#;-?bN?tv#9jej!D*DD$?TW^jdD`ie0D!!xRZrXXGMrz5FaUgle^608 zO^>9@PW@IY{bTU5cn53FnyXgs(+(B-0k6@-m2(e+GECYeYVDYd#=sG+(fuf@Tot7W z0zMEXHR>}R{o7_C^PWNWs0*CY4)~%md~qBy5Xxx3%5ZZVX)OR>QjSe3Rldz^!X(j0 zI|ovh=dd~?Sb;FJqW_6}$1%=leQI>F4a*p#9QL4%gOQEsTuC0m8un{f^>PMdNW;*a zfya6;+L5E2n&O|emDY>A8d`adDqkuedlx$sib&Zwps=Q}aVQ=4{B4s)Zblp(J|V(n zW9Nb+(kHbz3_ArI%+)p^qJe-9hFKOS_7g(?!hr>1;z>z`CS<W=wZ~oRkS)7F|2I4k z+w*2qz+GI-M<4y1253S|G(ZVEv&X<*<u;R~>=L7)L?E7G6`8xNi{Dv(cFyQ~IK(uW znZjW0Wy@rs$1TaV<=sb(@{u6LXQ){pO@{FWUUzN)K!3fueYRv(C-HTm^a;oXsqEB2 z|J`B8{!KT7=g-2J#sPct^=I}TqOYIQ{{l|`ZT8s3FGmTM&>)WLyGVUj;36^`ob1U| z&eVXY^qB>?!i!+ueaN)k#vB<W@y;T_1TEAPh~W21ue9%zxX<Y(@IIA7-*uy4?Ni=4 zWYa{Z^uxaROi_D<3d#dyyaGHs;$MEiVp=rrCwzC{T5c5U!WK^;Azw>QvsP$U&FrvT z)!n*lUBd<q4Z5-SUpMv7DDR|M0{U6H*t77}*q4uX3qAKUEx>p{$<M!7CLqA2uN98V zllb_0j*Vb|j$Q&eHoV3{_sxVL6AB2UFI0u=ZqKA%*a3i*e`;Fn-@N!rZcA)6(hnx8 zg`D<5=tktoMk<30aQtaE$cEl}x;cU(?`Z*ZneAp|MDaOr?49<0Bv2_l-#r@d9##U+ z{jE|Ppiw%Y?)8`5?T@M<cZ7g%)+H97<C`r)s9wEA-N>*X8UWNtnCs=uY9;jwX|oRh zhpHy%oxs7~WAppk$6FOd43cPA8Fv>t(`V{DR_ZSPByCtTYJHYIR`J~)a0GsuGRui= znv^ci<qc@oDewrw<aZYT(EHZqY+2>Uu=2TvvqT|7$w=?K+YRH}`0bleZ52v0MF<n0 z&6_K`u;aD>L>@EBOt1+6so9=TS}UIhh?m;`VR7Vrgba%L^iSCxVv4dURLB8$M7HJV zk(ELqiP53<F)<ZV%0vTUUoq|guxQQb&#R24<mHiYLzwA>g<KmS6FnO`^F^T98MzI& z+iZ|rx0h}1S%a>}5*v%AsF8sOn2-SjW>-0+J)JPY<Bb0tvcg8yp5qhb)y`mLo+6T? z%*?+snIiy7B=+@u&h7o|Aw{Q4iGLguUp;(!;UraCi>KQ=ic?I!mArM>mY(EzyZVgz zxG>;R>oes(D}oS*suL3)n#dAFV>`3-Wqql(B$9ouJ77Qz0zM~QIQ&{-4oXTWN06(s zcoqjicV+dcj<b*{aPFe}a{}=7&zRD}`N;6ucU1!alQy~3Wa^MK`~VnGlGSEsdD(=# zYp{wiWH8FRf6+qab~om2eV@J}!V)*_Qi=v9+D2vjaXXgSSEFUKeO;e6kb9plaojYS z6a&y!4{rEan26^qXwK!HSS@5LgojwFoF*SR!RC5+NaD+t%#=w99E<uBE!pfXSxvx# zX28o;7HjX@h3iCsxFs4E^1Jczcl|Zqp|`*f_q9xjP9hEZQ&UIsmjt)1qZ2*IwZ}sC zKZ{}*j@pe;c$$vYS9^{-35htU+Mlp>JTwZ+bbN`)S$mE2`OHA;sw65SaRhw?hS#E{ zZ#~4L8o)PCVB+^=T|yvA%GL5Qrd>^yZE;+#=#xhHg6|OjdrXje+1+d76ne|er-muf zZAqNDH5b3k-ocHFr=X8dK!&N)di}ktoO^5LNc0l{fT}J?2_2{(>t$lI8x__Hncrq4 z_FsqlepqSaBCAk!eo}W~*cCTm-oZL<10^My&QRd$O6FVj(>=FUsr|kyVNrJcYUH;> z9L&+q0k<WbCu+G>C}WYGLTU}9cv^@<DvJaJGH_KV{ity0cFaT=pz8&dTcj!yvkabB zWbVx(od43ZXK}3yLLtJ<yK$Pi`fl@$G?BjTut59~60TL}Mm1yy!^u*)D&|5k2<yL$ zEv*e}Om*m5(Wdtap$W<5AYO0QqY|!5pm-HV&R2czSHsQO_#G?JL~Lyk{PX~4uJ&lJ zRRe|BC`Pqg9=MG&s#WADP!kiDxT2LQQRs1k$OSo}I16ZQGWAgl(Fnye2O>PKpUads zNHnQD@7od23jseLAg3ObmKZIhXhQ<?@N;vbvjJIZrU9uCBtl3*0`VX6C{)IEe1a{p zTGsoGf2p=Unma~2`9;YFmF)`54+)|xZQp(yC`C~+!9~&rIxHro(|RZG&zmP?YTVs^ z=`l`fo?B=e8`Uuo>b$SbS@D=IluLP|cKm$6R`?alwDU#icA?bejnjOo0xf_v7$F;Y z`e#6LEH}7kkIiEQ8dUTSi01J5xCqO2B%{q|)t?Cs07%Pwg<uEdXhWSw#O0KSAhO&W zdPgDVP8Rhcs?_EDjwcj+(@VL55uM!BfpOiPkIm<T1%{pb#^|`Cr&Q;U2!bUH)W-_F zp8)dCsIreo^E&Lh0$xiQ4Z00%iw(uIuf0`GL`^#U86QAXuXC!j(|O_hO;S~UaMRAh zO~Xa0o4#&yLfsH0V3i>Q*c^Im=3Sz{mAD~hPUaI7HW9>0)@?QW1RO&X3%JX>I9PPL z>#C}h(6NaDpyB_yi<-F}Jv7mJ(S65b)=G=s{_?PSoU}iB+B9@V$dLXQdGp^Xj>0vD z4>v6xJV;zbST(*$o}VlcIe^mDB!ShpA%{5&ZPxk3f$!Y5Qm8#nl6PSuf%KL+E}Zq> z;f?}JFBQjoTB_qNh~_SQtzG?C7M`+Jk%^)~mdshDIDVZ?X=`fDS(lsud4sd8A%h%} z34JAd{-b`)g1&>!#n>Ai<f%1^e+eFx9WU1D(RshwA4@s5*SM1vaQll5r#gy^Jq(;w zTG5XWMv1}uvJOj!-7f|Hw{z%+*lmvw=WJfuarBnOuz^gs2iJHl7F9KzJ+OhsYE;Kf ze=7-zE44k=qd(0Dp$$qUjPDzK^gMfPW)p1txp}eTpLaLVOtN>^TLw3N8<ZS{Jz6>b z)2;aOulf{K&D&a%jo&`a@$b4II%6oO&mpW&-yy?0>Vo0^G7ENz&uGcGFr6vsQ#*M= z9utpEg^jL*Yc4<9_^wdXSjhG&<9T<#Y3oorAE*47I$^%}I$B(I#Clj{l_EXR5D1-@ zS*6=h#_8HQRPJJ$k52S-%-<}tAroXcka@EinE1JmNUkR#1<e^!BYnzV<=%IW5B(YS zZcEg1!%H?7o6sv<f6u}K0SzEuEw!wvm`N3!vvOIl#_xrKuihDZ^f=GVw)bysejI;c z+<5fYE*s~5etxFoLl>C78vCO*JUouJTTlc;P7@$}r*62&b~el*Krg`a0u3D(dwky} zX+L4-U0$YstA%Lt(Y)!X*@fiu*sUnSI)5reY47dk+FdGSz#bq0^DgVpYlJ!J_x4hT zHV5yc2>))|p`d0}Nw7HGIiuUb%B^3d*RBH6T7-H!G$iju;9D57PK@!IZ+;nSW#Hk| z_yHMr$@cdP|MzCZIJlMf%{fG$Gp?>knQXY%Zxb_Du8t~`?&yJ2<DJVbmS)b;92)T3 zs^JD-T&y45{<=)s;&piexH;ZhqIQ~2B>bV9XFGz<Zq7YEmUajbi)7M_i$YNZ9f>tD z*BwP=oD>?aB!$U89@qd=hjXIPCNis{mU7H{#I!xeq3s0#@<C{g+Ml>DnP`vVv%`Q4 zM|z!(X{)y-+(0HsVEGSi#BPOnbS3bZ6=Q$>G2E8z<q!X2Nez%<V9~T$TcZC%0b=lQ z5K!{bH96fa0NiaiZ-4J_pLAK29`NlL6`(&3nQzod(;fa(@p{n)lgEqTGdj9MfNc96 ziK}ZxeGoK{_0n9VvkLKzz)in@H>6htED`o(zgK5|jqk+vw!1=U{bszdc1Y$SxK0c( zV&j{dDL!Iq;J9$RuMR2C6@ZUkiLg6CpS0&#;et&2QZ|PBI~cZz?BLTfi=c~fp~uZ} z?664wE_r?JDSq<lI_m2#vYmUsPx>N**W0Guy!0EGmD_fBUG@$ouL3BWnyU$W6k3l2 z%SSKLbOl-Yx7n=CrpZD-B?n+xQAoPLiG6}h9986XAZ*hnmzi03@BS`&D?62;VvyDV zHmH3(Yt9B>RF7b^KTL16)MZ+|1g~z+25D9mC??{$KAg1p2$6JP{*y167Rdu8@7A^t zP=viEycVLoO-OL_S!X(`#=X!+8QFyJhTiEuok9W<#qPUObl`sRc}i|o7zL1L=L0Co z5mHfc)sTzZkMqFC2LcvW6pz_s&!^A*q~~x`R}NBcvdcwgxS+)=eyv`tZ|mND{4!?r zvy+KSE=X`qtgK~~vHQ!T*Vt2+uZe=Z_5?)WY-)`QplW|bOE80wUyDRx<s65wS_Oq{ zYMbN9NE1zmj0KRQj8s1j#$UidN(*P>do;w{M27sMX++BCYL87TNjmlQrta`Is>M#8 zO#0wThZMLFGWO#N*~q5-CU~F(*r4tpm3J&TMAUkBW%9J9*_FEKF=Fb?G9tLBqkeS) zeV|^@p&8RvjlNa~teSe~#wB6x)u+$pnZl&g@GF>epADF9g7#|i6&0Xb^m-RcvBb@N zX1sw|D)ege4(vhb36b^uW3n>i^Q-K-BwafK>O&m|Q^WP4BN|hGQX9UE6bo;*iVMF) zAiNCEK&3O7!@8-mBalf#oG9%o<BJ`*1P56c%$?Wps{2Zrn6%OrD_AdH^U;s7DdaJA zgwl3?MY7Njmccy3BlhW<Kj#Y4gv)tOHV9qHr$IYNfA9o?^FxYsL3feu(IZ0$Aou}s zF^A-{373it*{5E11Rcd90H4kMbxGDd0t@FcKQut`pK^R)QI?h3?38|shPq8|$Lug` zR@x18MgTpV>O33#Mw@%=#%0+3Q+#2~m{|gl5I7F64a7$SsK!^2X^V5~t!e6F#OUF> z=>)oTS7|pT)}Vr~4PSG{6hz4=VXxg}#A?fZXM}>EhxT30mfy<X4zhKxTZe3VQb1O> zH9Cn0`+Sd~aw((hd-ZA;2W;wgae2N_pgmSw8RC5^B1j|)$wWWDm?q>ET#L=$X*nK3 z^1etMjlT>*#6$te?Y{pc)b6$%{Kr6X>;M+YI05(t8z@jbkX(c@I&e00|8YjU+pkm@ zxEm)|q6K@I(Eva*vf=IqCU`$Tb#>I@E#rsGSy8AnVzi%px(`r-aFWASR!Fw-W{WbE zQ<-{v<G+!9nVml^PYLLaNmS8g@=hDyu5Q$Ko9i1oj8-@|E{!F#ia_GQigx{y(7oy~ z?t34b`w$(j5SUNsTNOj(Wvlv@x8n(QQ12miJPYr?%bW>CM;aFK4<RJLGWXti92@!O ztQY2N%*;}Dle(>J4dslm*yCAYpc1<M$_d#}$`D&E9-xHA6DX@`ua#or&bU{|mVJPi z-4t7%n)&CzHUzSY{1^Cum2#0Yu^qxP>GMPPK&?OihJ>}xLGx1#PswJ&OFZi(5ZC#8 zM}YW{du`K?%wjL(scA_(1}-42mU0sgWE6Hy5(^;hv~AU#ZN2XD`{Mo2d{*#7rw|7H z(~lClC8qob2xHoh^0y9%6dgnS@wBvB*VcI3mkO8lwvizXI~}?TiGz<dkK}1Sr0pf= zjCdVq&xL#qAb;%52<eF!X>u6o&H6qh;l{+rAkq|gzQ}fcVi=$y9fSJWMba}JC$lcn zOeu+V+^**1hiRYg-`QZ)dz(-AEObk8Pz|yqe_p%T3JoyRY%SRK`Ls;3PyvbhAwFtJ zC$3W;@tgS&q|Tse=q|n`$!FkXQb3r2=<xKvn*IPHUk3Tw*7R~a?mAXfR`rPG$*OhI zZ&rLH;pvwq0y<T?J;pxel#Hd5BCsq}G=}Px<hD9l+qTQ!epf+`Yk_yutvc=CDpT5M z8=+KXQ5{eJpibpm6liSm+>e*@JE(7{;+cvjcN)|gq&PUGfrC>+?gGJ<S+{=obj0q5 zoYFU717s)}74YrU<|zFvOn{ir08ZU|%nXY~?70S<RHI`E;?0HyIK6NDn}Gz#ei@er zmOKppHM78EZcTe(y3XI%GXIQ6$*A`MG4?jF=*sG1@2|LW?Df9g7t$)^_(G7p4AXhW zEE9Dwag{?V00SWdKK7Ur-!96fHZAzfi}4I_&FUHkoCaAo`E0VL3Xn7z5Y;Inpt0}Y z$@Co4vanhIr44_TMi<HqrXTew4R2*BH+0iz9i8CN&;VU@-RZeHHfz+S_(PcOA7IE1 zgf`o?MPWr<it^9AX(!zq-HZWYBMMoHB&4}!Cf32uw^s(E82=O00<Hjc8F5_5d=Oce zzjfaz-3O7%`s(E4KpkAlAlbbpF|EqMR@<?SKE6ZGt`bOZbbDqC!@Qa-ys9Wu%rh4! zg(qBbAg?D9Phf<Zizg87WjeH2y(lgD2NO%mPO)&8y{qlDmFUc;b?)&rArs{|0XV5P zZudPaRmYd8Fd!Gc>q`c-Yx%)b!G4t6!JlO|TPHt&(Up{@SI!WQpEBE&tKewqH%?0K zm**kR{oJiRmMj;91}^k;3tUZxY-w7^0>1G7=y606JpbU$MX|Q|AHsaN+H)rsZI%}* z=aj)qo4>Mcx=N3IZq{QlB${5x?J&%J>a|c3b^6)iGue8Q6XJS3RVrb_>og+vI0OJm zIC-TPy+TyzIxQwDCnYdO@^ItsV}nF1Piy(uxwa|o?!1{yELA5<jgO;MLcZ2VSS=2B zLE_Y{BKW1OGV0m>zY!)!BJh72LK$84+qAKbf6fNnyM0c80}?{I*|J}s@^^tu=+WIy zkwoKqy_K&SizNROgaL~21uc_Uz8isc`8NIcN3SbB8R`a;va=nT(9y)Ca6%}WmXwLj zKVaOKip}mR&kI2?t*YBoyb*8>l6q4qY1c%XqCv?EB<`E4tG?Xs;@zoS7=1+6LLz?t z(fz1+zUu`9Mt%uBHtdEB6_KS5lJK-&tKSrU-D3Yag&1x9XS->l+<NP>P_u?<Y9ErI zri4b`9N=Cb*s;SkaBS|*rgER#t(zI!jD(|Q6@_U3Xt+9&OJ$TP<-|Bb{h#PBu%FUa z?J}B4v#%)EZ|Lz@T#|N?oG()LbVp0ch%H?Q#x=^tM*T5G-f(rXM!nlJwd?M;BJ(KF zERxshlR~l@+)5`c`81TgFOfziQoH|GeYELfzX6`x3$t0x7LsXw2uE+hn@PhG0t@L0 zFr|ifU&s~GI=O~2{TNW@(L27j+;$TzIj|@U08!ip6q;~OvdM|ICFqslJ;y#VZu)mM zF){NE%fIE#v1%~Vg08$=%e`bF1>_!-zlBqzw6hVTbFdzh89oc<V`pc!DMg<)BUQ}M z>??!Gfxc;GOe2LlNI#c^8pzun#36|4>35!cJN7o!_c~f9I#O&TIwMFFk`>}x6|G|# zOay|}G&bkAX?q2$OFc(ko@^#}9|t`2cJDzisZq3JSxlnlm5E9M{V(Uxfd(Hc2iZVr zgcmCgB8mQI^~sTnE*6kv7pHMNcun77V7h$R@%(A0b2YMNpKq;PlweNys4+^Lo<3iG zP#!Y!l11P@d;);-+IPNL-hvj!+HHw?!&Ce6hs{9UutvrvJXOo@Md<PUFIJgXzsv5T zlX87d;TT`fYM%OZpY%UtfoU%tMw#%}D~eJ8EIsO4k$A3fvfSC-MK)<cbu^0naVHRQ zF68>KKSx5cu&IZFV=sxxF7AFBWq)na_0aSaE!T{ehO=EL0ks%(P{dNx=mA(p7`x@I zV}{HUhOo0vW@k)co+c1-tj`eVVceJdLlp-Kl#bhudy5m=qc8u}`~m7sf>=xT3cbGY z4ZBS|3HdBNS{`1c7ipPO-tGt*u|+vL`{oxL)_E-I31St~rf%M73;2pHy*@wR@(0|e zk?``x;W|`yRTBf70aP82jEh0*@($JahIRGhX6VtfGv~BTA>5mH`b7L(q$3M?Uyb4C zYZ7kuToGOl9iJ7O@}p3-@Kc`_Y@`d?9Xjp=<Pe<Wphy5z-EX>hqZ3QHFJYy6)bOe= z`nlAjK`Cw+)6OL9YA-=j@!!)G`2Ovx7>>NjClgF->UeS7^m9h@9^a%D#wMU*ksPfV zg>BpS*|^J*yPAITlO^%_t<Cr-e17vI6TS5(t+wi$u#YFPmbv>O>Yr!+R8kDmytv^4 zXr@yhb?wu6>yuzbem?fas%#HF_H~PL{Sw?&#nL&A)s~Qj;||p-Q~qm@Hk*p(-78!; zs8mJCJiiJt4D9!KDH3rMuww7eA3FoGuCopWxVbSD5bvormFR(xNA_HBN;}}t69q+0 z{wXhxl>Sk3mp>wW!|XQM;tscad25ZA+Jl!X@koL8w2(;P8$a<^gIx<&jwHe+Tf5aV zy-1$f-EW*-SV%I&&pP}pKF8&D-$zl}=7;*?u1jO2)y=<8Ef3#ih97C&qs|WNqMBBx zEPD8!*WtC@C5msRCUf6521=H?(XyN*)nQ<^$cBZ7mm$I*y~q6PQHf<R;LxTUi~&?K zYE5fcAm%~kHyi_S*XjwEURHJNms7(cb9I*Nl4_nly&sUC(zaNpEZ9&EDnmcUOkKBL zY@{PF;LNH)y@i4@Vhd`^4LFr-Y;0p_n-<91={{ZI#93-lm16nAo8$y1q3?ym7|q0; z7O+b<&?9a={zHPA0pnH@ry}w`hjV1pIowAxBK&iqO=#~S!Ee)Qev-8UE8%{;aBo9U zuZ2GpEIz*tBIvgsIXNH7|6YH}irDkz_#?^Tc7yV_-A$g3A{XXOaI7G_gW(%nd3Auy zg-_#TP0e$3JGnK3cY>r&q1~K>MCZ>?fR=4Oc`e<;mi2D>cDy(9NI!%1!B_i>eovCM zO64FKCP7|N0BXE>f<-U|-L^MYL9MJ8j_8JsjMd#GWb1t9hYY`X+?E*@UgMzs%%=iC z`3JlX+ZhVON*9)1EUxhI826W~@i}}<5$qa{)431CK0&waxAwvyrC6m(;$!ZkT1dXH z;;bi1N&eSUkQ4uL!?lNlfU9}7H1BsqoU9E}K|RwZoG9U0nA3jj;`R=+aCwuvLU{)I z{<<LBMR3-)Z6b+ze!AB{d3F3x#;aqw%sde|D7TU@cvV=d$|Vk8PvIIrTA^Q>mwUAg zG92$Fzwp!D&Q>vPEsAVC*@#Tyi!h$+tCxCKR-mUssX>|Y_~#2%89*6nOwh<z5>S@= zI{~)eu}eq{ef3Q?V^;tlF#q{|FQSXE8UQX7gXfMt8k;Ku$CDddQb0aL6J`3J4<UBm zZjB@{<l@i#p^$tX%fUinNlLYxzhENyLOlKo{`Amqf6{1fD2@0Uc+k7TpXwQ2)^b(> zmG_?UC}L-AdG{OS8@lWpRD>CI(5z1SyEnVF2Z*oq+w^p(5>19tF4eB0kvlL&`X7v3 z2R<oXOjr2Va;*dwA0zBPe1CE}B?X0T?9?9;I-j+yK7gR5B-~C1H3>8PFrzp>5Z+RM z@HFFZlW=T%Q3^Z5=sCt31U)FUNJvPm8wWD|?GKo@(XrYce}b(|%B3Wvy@Ls8tO8}o z6HxS0M6pI+&rS@)7H-jxt2~!%#=6k7tZ3fGS!5(S?Tzfi`_;>orUY&FSoGL^$PJ0X z=5ti~&vrs(r>?Qx;ePf=r0BK__I#Jxg9*`X5|sKrNJeB`Yi;s-Q%ju3l$(Z`DKAB_ zrCi|icb-}*oAWgQCT*t#5_ClDoi|GI0#oj`&rjWvi!WXsXYIDLuK;>0u=_I!5@8-F z$(R>(ur5UeF(L;Rk<{?NA8#paa%h#U`1_o6iy3uecqF<2*{uX&Buo=P#qv1*Sy-)^ zHshfGrE#aDd#8>dtcWpBr<g=%xj(E_|AjjyVx`<~8W0@&;3ZsvkkwX#&<Ee#i8s$Y z7|#vEipVVb5GTJ*iVw6to@!5hSdxkfF7##VcWsk8ZG=`Q<9FNGB1x1PWsc>Vl9CHf z<9zPX_=uG{;f`Yj07VHmlxKujlAx{7i#NsV343`45kG;BS(YLlfkJo|Uab_?zudc; z^goB8f)3o$!x?}(%wfP&;3YFF+JdG)4cvirWE<us-r(i?wtr{_qH4Y@>7YE{)VMun zXfD+BV_|lVfQJ^yj0-ee^L4zJfYgw$*qA9}#A=<Oh6d??0CL2ek&BCHZ*d$Hn(SvJ zDnB*ygxJJzAn5A!n0*o$lD*ueuU8HSmsua~t@-MZ#!X8=1_HIBa!o7WzQ>%YJAq*i zcv9~))%PQ;L!LDJl8dtSf<I<IOrWa`1!vTM)kFq43)cUg#V}Dj<Lj@<%<8lgyp|WR zX+0t>zz9mV;hhsy)@a_>QaJU(T@cpJoHkVuQSFhPL*IbsANYVj`^jw{;-;e2D5&qg zLIs$8z4->Np}BtxmLylG;Wh^d%#cnu5h*w*RuV({PCjPaOYhokN;o!FVMPcbO)p09 zllU6+1tF4cR|kGjF2f$RTMPLzVOcoza_0BU&+;~?-UiHHM#z_2X_=EhtT?eR=;NB{ zs{N+QRd4_Md4qRhDHWcMFu3<STy*$RnTPeR0?)aI5c_Vu^QuATL-(S4_R{trid$JI zdB^c=j}B%HfvTYJ@U|g<{@;K`4kjQOH(r3I)8c87!c`&&bL)ApQbGq4?u@)Qa{oU0 z87?l#F^GP*%Sc$S8v)tT;D={`d2#jnbRJohhSu{82L>IGnBxNXIv!S(a;k)^JxYZ1 zb=aAlu;caBe(n$B2mAK`ytJQFfBIB!g*F&2bjdfbSl}p#PBv2Auw*}gMI~M35O6md zSKtnz&tYNJ7h~sr$aYOcjlaP4lX83GTjY3mSRsz$Y;w4U(P7T0ROP7mb=g?emonhp zsc|%UD7HVfE5RV}{n3lY9jR2B9}@}|PBxx>_{^=N>7F?Pak5CGe<7oF97s+Di{<}# z#mj_&2Qcc}?VTBMrsFDb!A0n&jN&6qbsVU-Z?F4(FvM~l8g|=-b8Bs)hkA_o@(G8W zm)naO5Er|%23Ib7x8{5B9B$?Glqi`f#)6^d_nRP76I}61G`&0@nk(F<AnBs4f(YaK z(=4*|Emt@~gd(i=@*Sva5iRTa7E)HRRBbje!z>XZLAG*piT;4@d&x*G%7Grwqss1j z_#X3C`V9vIMC@{%n7{7n$`IiBJf{oEJj7%MNGunr!S0U@=}OcK(HIp>I-1|MH6<j} zKI$U=bDrsD2CE2Yk<gBU4LZ0=f<hA+nGDhNdZa4Dd=hF033l`&1&UuP83DIFN3S%$ zCr~F^cZN>lp65fnFA7(&O-KocqFV>ZcCT$|T>{I-6j4!w+GKz8*N_(UR9W~IXL04z zRR!2Jk`6N{&r>tJf`d?NBWc>(d#}Fdn+pH=9Td;?vbJgEa0dGGLGz?Uf5O_4_S~t? zzo?5QP>A2)R}vvyQ1=Cqs<E-}<RyogUf!C7xP+V9I|(RO@wGo@F2wPG+}1PNPM=*5 zVQE#T9Yj||<y@BhkDY#C9vav|>ZYxC6cQ3{X^SEM0nnpiF)2<QM3-9srmN?G7M4s} z?)0c}hDcZVtkD-}k+xQ>$o45S0;<Coym^Ju)dMcQ+dlWW*p1S+=X1*@V3Vni3nMTV zFy9*>BB1c8JY8N-f+IX)>pFm^X{+nTR-%*Hl(&(y$@nZ(N`WmFNEP$K%{REt42QjF zZxPu$l&P~?%Glvt?BHO<REAe9BPn}haWZ&5)GRKA-gooUbbw-C5w<*KASS#__z7V~ z8WXFTH(+N~>Ez7TFp~b_D8&3e@Tnu0<?!3*@FxP7n2Ct+BNqHTImlH9c?8LSBgYi@ zqt2Q`Woxm27V^3qVG3s%VI!Q9EmvSi!%V(_o93KcBXP{s!vX*jliYJ9<p7N&y``xO zCZ|IIz}uAo-9p`FPFmkyeVkNxISKvd-ne4=^fgT;QcP5j@>a9$z2G+La+`4P33I2n zCG*TVR2paAPkd7HNq-bM(M43+?Q3E>U*8<o*QTMDoFkvC!QBx!6t~77vIL2V0+CX> z+;#9N$^xQgCQ}7GHX_1fs6>VMehu4iJ@&UO9i5$k=TM`KT_oq^k4_1dN%)_WSd{~8 zaMgg_IS>pQ!1?lz&E|iMgT)YA-zyaEx^`U}hYQs#ib@R^68qZEklbx$Pu<y<di{Xn zWII=g-ACRfS?_j}eamb-sF`9qh>Ct9SOInmutmtj#f2wl%B)rox?MuSdx(%BP192S z8*;0{v;>t6n;gL_Rk`+SK}0_gdM7c)XyEC-UqyVZq=V(PTU#u0O{s=Q^Ju;N&brLU zy39~Ein2Q|{lm#kOv=g!XGzbAj?{|;%K=JD%eLo;nY`fjh<MMJL?d5W@BWO_d$sL} z15tB}>y+YUtw^b-8tPX24KxupmBY4Z-+ce!<M$T;IXM^}#x3G+vn>nLbE*zPC%(}Z zXAFF|8#Y#T!6WET!v+<d1zYNp3On$9tCa@8J(7{RmW%!HTM*uQ5%=ENRh+&0sYfTe z?Un51rez6y(AH_gi4Y{FX6zeSBa!+Z6LsTB8vEh7MS<Rc8uPZ<FY3ubSigx;0cmO< zhA!gjCkw_}yG!Pzb{o>l#__X8f*|nIh}-Cv9(a|^i6h57`)V0$(8%N#u`c5}Q^U2E zg~h~|g;xngN)BlTsz4NSUM1}G)7N+FRf!MOYZ_3JB=>IcgURjnI`}yhHQ^?>3`I&_ zu*1_Q^^f&ZFj*-B5*Z@J|I9S-`aaAav$>5sy=esuR+ex_jOus}jZg=XUcQtsyO1E< zl$&)gE=C0CzOh;Ox%1Kq-3I#K_b|4(-b1-Z$uiLx#GB16RCmk$ai73@8}^K~0;mZG zS4`&8>1me~>i&YweO4d>fXeqzL|?vin?G|S{ZQIa7FpQI^b{`De05@U`mOu~H*yy? z%l~Z`9Xv+nlq&XoES!Y|qO_Fn%2`t!8iAlnKdWL7HbS7CaNgF3or`5i9EBI~sM6`T zJ~kZMVHN-QVeTahZ6@>dLt6PZzB(_g)VD%6NEk%^zbq#gU$7opxXUi)St4QKbEYiK zXNmQO3Hyg%o!vu4l<3>c4*p**w6$xV?>$8%@-o7n3JKJAnu<9Xqh*+$F?mI*guR&G z?J(Axfz)9O5>hzw3+cnQz}nO$$6gX%FJCTx3MZ^vhBY$UYrSS_&Wp@~WD5$_yJ<;P zwCBt|ZdbJUJ+EGNWd;;-GgK(pio^d>e$z-e4i(5{yvRT<K|&_QRH?C91ep_idalsS zRpB~(!}VN=gR8Y(HPCn4{j9IjP0e>4zC89b0QoXGaZmzI=NBaJDd;o#-wpci`_?FO z$?#1^d3B%SJ}jlmRI4dLfKEHI=8F@fl;Jb-3ut!ec0--n*4DN?7G1g9q8LL)Yuu%$ z1*r+C0+-H7S_GL?s9e+6$dC%iiB}gsT4)ov71=;-c|ieoUyiI7eB#<cP+A23Ak#A{ zdBqq129o~4c1+uB=c9kP*{XA~(Yl^I(K~O}dnGF!@C_NidwV{)=YCQEGdUT@Vdx_! zW+(8xv}B_7oh!B%KC8nyH28pt&AxN>rQ7DrBl~u$LZ!U|ZpPpIcM&Go5m~VunzULj zZ*gj(E<i*=V&H$V;M2Eqxc;p$5}q-*JsV#QB5In57+=iCSn^jwm!-*A?(<%CVXdfg z+kl@JhELyKUDUJBt$x*D$R55*`ju6SL_bJY)7Ux;o1Nuos`)MQk<*2hi>i}B>p5?8 z^f=>Ke-mUj0gojdj4dc}pMxgXiEOk$M>J#44(OF)3vG67<qrd+_I#$troYyvv+klW z?h|>s@?Ohu;cB@YqAz<qvyij~H!(18BLR!KTY2Cqxc8pWahYXtc6jQ4MaRD{R~L^Y zHy=5jY8zy-t17d88jk&5Jx~a=*|?SIqviIshENMU|5~jKo9kq*Yq0O1EL!W53JiQ1 ziFKqNpbQKY#cQx`(bMr@cIytp3CnS47$hn(f2wNFSvYJtR~IoV46C4uIO3Sds9-v* zHWUo^=V%zmNOpTB%swwKZ}m9uZ;UYt^#&)39lXWg+|_e3H@N2&G95k(GHrK@o&=%! zUai{RM3Ph^tnd{oqP7tmPe6ZuQQ@Y7+JQEDQ2vYY=w}IH$5e5onH>inOMT=%H1>nn z|L`Md(f+H#ke_k-M%`<%)yHpcI(>p<fHAz(r&2(L$!nI4bI|_GJM~dEng8!lrPy*~ zKE7_3^CA+w;%CdbnaP48pjoJpI-+706mau=B|r!IjIFQR3TclE`z$0c-wiw=kmtC- zWp8tqMn$fS86ZHRr-6?7)<`HA%Le*hh5|-_2~rm!Z9Uhwln}MCGyQq-<h0Ed==h=} zIEHttN|Xvi`qf*!P{VH<v-72ex%4|5u^a_v{C81a3F*%0HvflIT=~m&%WZgW@`4Ri zM_-FIUyHUr`y~}Eb$pe^bK!3R4^x}qUdL)FX*t~$%cdC~n&oU1K<_jjn52O^I_Q@# zz6j8o%bb7$lF6WM%R!9zug8z9AHCe<%Y@A10l(4`CHfLuJBf-?x>?Xjn^AJD&G(~b z3F$-Y)`uG->T|8P_kaC<hq&vO=JF6~D%A{nHI&yGZA7rO)sq87`kKHd&)+UJB`7D& zdp$(k0(YXV3yTYET0OX$E(h|3XpOD=0^>wIcPBf4%}kdk+DO$W=N0O7HxcuE%e?T{ z=)QYERw1DlTG7!L6Hsl{j*v`@@xR4yKgd?q*Zk<vhXV0gFI-$H7ynmrz0UH$NKn~U zmvjplNBCKA+8;3xZoWt%V7Sc|D)Absec;5QK!_T&Zy6m%xEqxX3eT)*nC9T;fKVIX zpxXZP@$=N!(3dBN<RHuHbjG(Ewd`h2A^_fWgtsplF!}>wDO=K!f2M!VM`;5JDf8=U z+_lyUxUV~sfa!E<jqU8j!L2{byLCpB5ovm=v{DR!5DaS(3Ca;h4PBC2Di-|URVD!# zlJ@)iZA^(yT4S;}GBZa{`^oy!mfgNog+n<B>4}v?!rP7u!5@<)&8OB-DtL(RZ#{Qh z<mQ#sDF7Y&{WEF2_IB7VeWcFh1>AD#WU_Hph?Q;QK)PVgDb6Fq*9Xt9&X#g&6Q7&G zsOq({A+Fkts=^sQqgsglmOdW4ZsEPP81FGvxc?U>`jN|;QNC(1V}>k{7<`j#sa7OW zvzy6YW(==i67__lA%r`@71BU|>&W!rGM%fo@U?uAJCE7M@qUdcyc}Y;aXLt<OJlWX zpwdLgiqGoiSb$qE941Wj_;IY>UAws6mbPG(FSe5laKfnyh}6_u|E$Kv@hsK$eU?cn zFWoLQ!%OeV|LH>7801MT65}Z5xG5a}`?D_KqSGkD_jJRuag1_)e_}D1JN<|S=NrA< z_N%UcCn`zX4T@&BZL_us3M}PWyG(+dn)m^K1d^;vuM|FwNNuNaxBqLme-w%1n%9HS z590hONSc7qYAt+p9aZ|glX>T(h43DeKmLoEZ(3OILzij&$RM;yK_~b7Cyc<}@SS5z z!?}RA3tonrRsEug)SO$qU($J9=Lp~G5<(ND@<3j$75RbalL`o*Pf3(VZVbf<gkYn{ zSZW<|QVDVp6p*uN;WO@41%brPr$_#?)WnBj+h5p7)^0PgN9K!bm=^>U#YuX5K_c;C z;Yt(<<AI^Yu#8`IF8yNn!eo}N41@nY9dW%Kq)!gYmBXgn9hX-d>C|BTruH~qF>NHV z*WODv3Ae`TsqvwZY%TR}gbMK8x97dqECUW>2BsWVVruo+UfNx0qt`VsizoeziTL|) zQ*|R)<6v&o6Zc%oL<g#vQ&eMM^cDENMHp5F3S4-mwjEN+h}8FW9oB&fD=vEt4|<SN z=UW1WGB>*DWHN%Wlf!05fORPCCs5gFeyhVPZL9r@-14w3ZAaNxXBBjsS^tctKvsYr z*IjlE(e%4r>G1Y0&Z<si=zD7x?1buzmIzN@2}952evB0y<RHZ9*_DV3!B*|mN`EM; z3nL=Q;wd^7Uz*piGZfA*WQKV4Z=WSXx-3bJ*HYKp)5rSR+Ju5=*`&9?b4>%#t`VP& zp()ub6%T91)3(d1iI02gn;@&(|Dy%?TnkOUIQ8RQJG>fna>IvGX6<H7xs-*H%(i7u zA~*BAvBM$tt%7%j=+9ND<7H9?uo^+TfGjorhzQO?$T}uiUWPQEU;wW$3`W&OM5Z`= zf>2;Cp5j5`3#x(!-uzN(0S3OI{JLJl2^9r<{>*0yQG%2*gXUUg0B>4?zwN&V$nhZE zh!KkcYPzYJ>d}9@L3FBR&mfh7pH5K3#+Xs*6pA;<IrcN&?h#uJ+P`go>DA()`a(Y# z4dNe+0qqcQ;;ZsvTPhMo%_QTb3AtAmO%;+g(?>3jo8dc)<{zWuY0<d&v&A&@OLqbu z#?#0$>)J@ME)&zpk10yV#NyzWJ`c+q_4(ljhD$+pF&!;+rt;FDiJBo+u2_ktcz>F7 zE6})1y~qk(U0iG*)Z9JETEgm#5B}b$R02piS=j8ho1lM~E@t;Fxv{cW`WEFIQjRsF zkL%uIRw64>O;btdVj@<;s)Cp0a}kMm3l8JzIk&&vkNzGunty~WB;*M#rA~~{!mD5m z@<+u)y#liyBZtd29FVQo+7@($T>6EwFk$C;8S)eBw~N0WyrNoJJ0KHy^tC4Y!SdaG z7x>JEd5aA2y=k<;&;2S!fv(<HS)``3`^*!<+rL!zu^T<(Qf~X$N7e+gF0is})%BO7 zp-T7RZ+D}FQH>x^1wp7V(lqB@#Q7}c2(ZeK@m&%tkFgq@Vy<_G2s#vg0<XG~+Ij?k zM%ZU2eSevQ#05Bn!$0sOK@TL_H__e72MQiD`DXuybyD~|($dbzEWna4ue<B)w|(~l zyCLBPqV58%7ST+9on=U`tpZ~lETNUChApNWSBtTvYG!V~9DA*py7@0<J(fD8-7wT1 z?b46vFh+Otb!Furkv@U`@b2oPVdff7F|O_F8!@?H>_M4_E)+7t&WZLtXHXHc<bQ2F zl{$|1G~QNEyqNm_oPbI|PH58DH#0?!fpR%DNtz<$^_FnL?zR47t5SQ{Z1EdimA%!Z zK?|W_sqae}_4i7azDUOp(LL+kt1;;MT%QDESSFL0^tM0vW{00zK$VHbS#$;=xxhtP z-dC0{p>Mo>T*+AdgN4t8rmBterqtylC1W<FAT1#=Y=-6j0xdkK#P#jz)Q4*Cm+P{m zZ42kICvo|}*#{4(v+NnI0qiqZ45GewNp|tkgA0dK)e$kOQ<Bv3#Zbo*L)Cwz%(-R5 z$z|gl(6T59_s%?&z}@4!ILoFBv%If{kE)L;OGEC|36GQmwMcr(>`3fGvArYI(V!0N zq1__z=kY8qslcqU+wF#9<XKhjA8)+y4hA~gi;M}pv<nno65ecC{Zp#F|GFRfY3L7j z>nBrNA-7|B;BA1xtO9@LT)aO%v+GsDQCSpsI^IS)EMY$ZuGnG*MOxSJEgdwZK2+%5 z4h45!zOHT8%bewHK8P~(IHYM(M#l%WM~2T788H;wf4nR8TaYh9;<t2zEkr(qolS=i zJrE4!d_Sa8d|d;%mvgsnhT<MeN13!9?clu-T}<>r?(dNq5~$Ad4D`CaTH<zA7tCh( zsX;&Ra)apoYlSjk@0Vzo^o~%Q&?W1S@$n=ct=1hNG^P9p_IeZDSuToO=$dm;1Ghh+ zsEp&GyA_3ol`AEh>)n{m$0EjyMBl8W|BtD+42x@9x<+vlB)AhiKyZS)HSWP3f(N(Y z?ry;e9^56kdvFgfjcf3xvAfQ@zq8L>&(r^VuDNE_s8M6oOr>Nvdck4qEJm3tiB)pX zh5r7`MXrQLK}GDkPzbecO<D{uaDq{sHAOJA`%}Z1<A>M$()O;YUAJvgp2k<sX1&;N zrhX(yI@lxz*Ehz#+fB*sjS6b-*YX6KLe5~<Bf@*5XJhn?x2<LpJm^pN-E1dzPY;RZ zbg>LQ<NL4lh4$M}v27PRH)B0I&8{1M&Bbm*6_$KU1;XIL<O;Tn-8$auc`&>G-P@fZ z&GUouQh`Xi3=9pD96jS%z5_NM4Kg>@e_0M?LK#BA3Ua{`cHby(;Wii-dwtl_qdO2W zpoZvU@i22JI^vsqtjDob-4Eq$w}0vwjO&Uzhd0hz`D>-7w}eKsdRI$!7=Q1l!(6bA z6Z#X5kRKtME-uiD3@r7ozhl(Y7$IH2oM}j%EPRwJC0$+Zql(kX&tp2V=b-O_;)%g; zjH^P^X_{d-*EX<s`*s^bMlJ7GULGDwqSl`E7Tz%@QGW17$A14Sj$XfK?j|JIjfA+_ zu*IrAqV!_%gRhX<6_MN_J#Ly~WfO!&bb~qR?exk@U~X0UT(_?)$CaWTVki^81)g!L z14DG%rN4nsn1G$=j)i9L9}+6!`GrC&*Iz+nLCAz6oa(j?ym{Ta?Z5@;UL?Oxzs4bP zC;c#uVAQ8JfCosk2^i8^Kc*kq2nW$;)?6Ct>KuIzJlC*$wJ^?paUr2;a^?Z71_zdW zFT^x%+Ov!Jd>>`KpwA<I4uZqlrw>sdkRnC2POw8D7n}7B%eNSd3v`hZu9_28+5WTI zPc!3R$FunHOO#0%hX`NiX^(?j1`zpV(vvlr<1dN+-78j0n5P!r-z>Y*#|<U1DgLcy zsebz=<TS-sL$t^dr95dCP8r4zRLiGPNUIDKi^!{VsMbzw#-A=pkRS0+yD&t;8v38_ zUI>(`hhSIBMWxBcPKf(wz#_}F4I@r*nl2hC9*>vQY%Xgu+5Gkh7K%b-bac|+AIjGw zE+3L+L6P&1_pEQDTx5Uhi&m=|A3bn5_1EjZYIpsakB0W<25lW*aT1>ey4CFTNhbSt zv*@gHp!JXs=qoh$y@6r>v*9TEx-^y3@6K%x)RGOMjFYDmR1$k;+V9eg*c3Stl3PvH z)}?-uj&We2L*F9F)*r%YKiU=w*Pd%U-KQd@eQcIL$TwcAS&TQ>5e`Bx;l+I49#@@v z;H*Xw!BgaK4CNI?r1FH};~|qP?ot1<{&SYFl#(R^@hzUVD01&3IbIM8(TVqbM<Ha( zpx&IRn&YQ2vluFB(dbLusBU1<{nGhYF*^xVd%f4Bc5n+y=YFG8%hPGH<N4`jy3dY` ze^(X-K^0#ST~>=%>-YbqtB_DsT<2t=o$xUy+ng;2mLDwgerhETslQGGek5Ojo(mnn zRR3XDH~7|0ps>#{`<BzRo=5;3pV8V8R1?~xJQmRB=MDZKph~Ws9!8y|xO6X^tg%e7 zxfZ4|VF$oXI$!(dZE@vXmC(@Pct`2)itnSB)rO5f-^z6L`ikind%3SR*S?%RL|>O| zg_)DAyJe7~lNdRGgy@Z`MQE3~2seSj<)KnOtNttnT{@UZTNp!&1NU#$@y_hdAPWxP z4hhm6diM<!mt%#U9*xq=L`G$Xz!hZ!&)~i?KbM%$^0ygRpr7(?vLMcuwz#M!pz|Af zKzuo}FD2MkH52<`F#aRzV}t>BG=7XwKMn_Pnp}PW0aE7A=VjD`+*2q_X7s+Mb4J&v zhQrUY-%VnF1Ec!K_`l`xOt1S>3ZvJo!iw~*7#4TDnMFf$`h*cnm!5nIhiz^nV^8oB zH*;b7TpZEYvvH@i*6Bode)pCpOdWmh!!<29h;M<{e@2#S<S}_I=C!Uhi9GlJw<U?E zGI}V;8z|};?*@~}bwZjq+V~$4X=iBo+Zw~~@q86<|19qn-d$O~sd@IJT<>OGneZ+~ z++11*7mO|weB%a({+JLwn{>6mYe6v(%ts+mAdhz+uju7#s2GGW$rljUSJUw=VFek^ zE7!ImQ6UtGa|9X%a|pAM917QYeb@J%{0PW{(+o^)3#q@fa?3b0`qF=<bLVa{@s_Ai zDlfxz|71eUG%1e%14Y%N!*pL#QJ`HI*>Xgb)IY1-O=pA)1B9v|tC_xgIJ6rw(%<<a z8z2fHQ;ge@Oas$%{SF|=S=hwTPD_-+d%SbsNi1nTVO{DBY3JrLTMcSipYFe*BWx7? zxmd)|W=No-?|y`){l<CQK2#$V3)W><b$bIIg7c0>t+xJoq57v(|Ioe}xImmj_Cw7K zMna!UNV|=PHa9ZpK`!Vi$$6Vc`e!dNsg2V@cq&!(K0~p7le)c3^Z8oNgzsw4%d#JK zU8R{I-obWYMeA;7#;zUJ&y?J@LUmchmRv1PkmUpaBDm02;~kM^VDn@}DwV|5-$;{Z z`Jd`xDYqwixtkxKg1SZzroXsgTxL6oAz?D#HBkv2IR>dEis_1xZ>!9S`G7|WE@SD8 z5MGo+{e0}vS+e|5@L4lyJ|~Ri*%%3&yR`cyO1a=XYq)Uyw@nNUH^Ss~w{P+}Ix9I* zjJF$Q!o|c=ZC$!PBxar7hy)6Nx{hir4>O#+X%1TT?M#lLZ4ArYh{0%Dd9R%uNa!{v zV{ph@HFPo5d|9zN#N*zFHvgAQ&lZ3l8dmkT)h$yV)3!6fp^YI&G7SR-=EgKB%vlw~ zHe=puXnxN6NuCU48I>Y6Dy<HauQnpj&O#WMdAEqX0$q5um#9s;ryJc!K{yge(6oCq zi$11K_2SMr0@;I~_{BpyZ?4=OB+bLMW7#CokZ~LN`-NEQ`?HRO<MKiS-Iq0p9D6}P zamHoQp)3~X8x+~Z;u-QnMkkjoiPmS@=puprq~J2tH3r^6Dr*$=wNV<l&?woHtHTkT z3Vf-kAIb)V2)#&cr|pKStLQSBBT7Y9)(BfG9_;z!A;!3ytbvf&TLzWg^*eY~Z9FaR zg#u51<eVCt*;qI4y0a!t!Aob3oJyN<QZYqN`h6~O5y5psr`zw~<tH4h6!8zfweXud zuMAxccX(SOj5lo@bm001x@{mA^xZ|8J=T>X8jBnK7B_jKo{g0k^(Rg2`?tT{+}nT( zSF7#3$JDxaU-MPZg`{olg9Hd<P7^oJn7V~(J$;yJFwx><iSu_rbL-vVgPKwg*FkoO zNG8`i%WN<4q@s8DEXg!G6zlXFif=rq6{^W7qf27ufQ?2qbT8<-+#QnAZ?p<(e@e3X z(JL}T94A^8%5GmqS5@w_sIM4gQ(1%YA$fE1pb0*Ku_eG@y+qi?vZY!33iRrE^-?<J z%sS(np*v?e-=y+N=)QS3r1?DI5({y&gFpAU<Z|V1dO#*IS|VvC3b<uWdHp+2K9OmQ zb`{t*v~{t`^`39EeQRyHb4H<-20cnw_}b7io@L5h`B{;y#$HV_dk_~U=FL1bW*_@t zS<zprL$)uZa-W!(R5pkvc`i8GY<7VrFWJHHAx(%prXmw#m^&O|uLx&5=ls<e1&XPf z+wb7hh*{}ftx6enaGW{a*bRSTxDnln%wJpJr#xR0!SlQ~o9yBN#X~PYHkyq@rf&Jt zJ35}H3{uC&b3J5(2Sib;D_(2A&OfBLhaHK$^qTqHtk1FMdxa2+%xrW2{;>H4mMf$3 z0427>DUSGGM!Gxphe3T6sZ{K5liP3tlNsiUX9N*Cp2&#bnIKC+D2=P?Z#Eul;(Zl6 z+`|vr8qFjX$M-PhrGy;fBJTU3r$GUw!5C{(32?%Fpu-M4wm#f90&NQ<?}R)f!KdHe z`(GZID||UONO-&AN|DWNpBZbYYxoEwgC$x;(Tia9hG;Ca8DWy|oDkVmN_7bo!0{FM ze=wg8l2$V?$<xh#H_3|TK~AG7pY2P13h${pm3=!&Q?t}j;oR1#=HrIo+gj~0{PdP$ z_OeLooQDk$dwstDSS!Z!#{NEr*2bBzGF7CIbpy>X6e31FSd@7q6O5YRlBUd}uUz?x zB#GRd*Uo6r_4O7L6b2$0w%sQ*jy$$ndTwF~&`L%#Tn2j>+!@Sq$@{wE*3k5}qR>BG zKjhL{->{^3E+-dZ%CNY2MSw0Y;=+8PU%{~2Ew<w|+~@s^L+}CQ)Kwev0q>|i_C)Ep zFTUQH&yad1B-kb)z)Zjo75x+*9g*jB6u6(+H#PcGHMkR+tka5(_5S2Ci-I3^@Lne` zVBaKb)e#J4-5MG;>fvgjJucaFL&Be|!lzc<(4T-!k~VZ188pc9OW*uo!zkWN^|vKG zzvU$F!w&h6Vk7?@NsDcun0eDSc4)N&^GS?1>%A(z(yOPX8cEk3BpR}Uqi0esbx5$U zII#IV>Z(vqM3l4;q3e$3crzdTXzo5d&6=sje4s2OW>CvPC@AaeZW3+0{A+#WfnpAm zcL0XMowQXXj6X|<xAha(N_6VAn4c_#1`B#eXi+#DZJ>YVyp!-LBMmkI%mYm&qk0Fi zd9#{EBROw`rJ?PN5|%6JVNb)VVK`Tik=@sxF=T<iJCmul@AF@fi;o@>iW4K@+;+BD z?>5UShf56XVc>k8cQ{ba?{t(GLPXtv)dqJ0mzaEH1cgzozcDd3F-91vpi1L2=u0En zM6yb1VmxXnD_Z}8_-mfaTFr*;>g6La?|Wx&9eFyjnU{sG7R9x6XJP5S(C;3Wv=+q% zVMtd!qL)&0+Pq2vuiu5QN4H~kBl5tVn{q`q;k^ysqKzghw=zD++omI{-uRUEGL}a4 z4=BqeT`U(#1DSG7U(j4oDz0)1))9~gws~o0+0%TQDFRve$vNE*y>Iabzf+GPss{R% z@2cAzGcWe&^N^%apaRbU|5E9!Yd&2N4|vIUNId!+T3wf?-<lNdd;kFv()XZKxzU2^ z1<qC21f@y~{78e^AiI_L8j%O8u9w~DbVIeDJj}xA(F8d(8ijG!btU@mU0BmXRC;QR z*f9<^>iNAedSLjE&5>C;hqwW0-Ho;B2Xv`DuJp)GaW8>LH%Z<h{d`T><gtM%p5|}H z^1jLYctC$4s45mY0mmKTw*G*`cj!wrr7*9BNI=>uM!ugkPMc6LdzJ!ERKv_E>-t_= z8q0#m9Uqs_F+ruCRo;TzdH*zf|K-7fa!Q8~0v0^hWnelVId7Rked(-m=G@<lZV?8p z0dqbLEW+;5J{jB|o9o(qQdpbZ)t^*Bn+|s3V}b9qo3vZ^xJW-6dwY{*xpU&ZO$CYN z@|8`YLOny>xTB9m=^bYvBd)#<(Qbp4_{+V7cnr+r14b$q^Hk^vsil>&jlG}z&}Lw| zUc|e#oCbB0`^xZv#xv8ft*oPcZ+1we($9z>H-RjStz+`4{zvjZc_OXA?sOPO6+IJ5 zI>RLn_?{L1uhYSr6guwlY;0zZm;*heV(ReZG6Gug&YGMN6ey%Jvw<0q(vhGTg;6R; zQl@=6JsuuTa5>Oz^Lwc@<Z+-%)n`Yh`@x&Ucbde#*sU3DkxNnhHDsk29xbP^i^&)U zVaj$r_-JnE6EBb2ZL8N9s3|dIJW5o}X1J00R#DGrV>zU%rm65QrPE4qIxgJ(4F26W zi<4<i#g-ZZ#U<m_M$<Fu!1$Xk%8Bn<glowll;L3s+S^*(`GwGK(I--nxi_rMuNt^5 zk^`m7-dhP2vg2TOiD@D9eU=*N_<{YV4p~8U$0^WPT_w2(FSm96SzU?K$Rcr)L5R2a zt;#csu{E|UW`b@76jh<eM{_rZ*2rG==;Ker&LcC@BWG}Hx5s46ZhbHH38`$EAsqY4 zJ;eQ8G1=}h8HNxS0kz?|M9k^zfuE>{Jl7jLTm(2G9rkeoyR&W$Nw`OJ55sQU&D-VV zRl%Odg&S^1X!>q5)){fG{<b3ji*Bd{?wI66g=}!+xoXU>kh{4XoA~Y#g2;$ceK*;8 z8Uqs8k0X8R9{v`vI&H!=0B?-bT;=`tKR*Jc_a#Q{J}iLKeg6{?3~DH0aIO(Is@9X0 z5d2{&hJaHwTW4cCGY-apLXs?(dH%@ugPpgVgaHos{6()CE04)wb!xR(%MP`H`dpqi z^>P5w5p7#Jo3@tMU016HZTCE`<)S=(MG{n_ke>*#S+yvx`PXJ#5Dh;+fdlS5EeaY* z6ovu6MEx@D`e2eLJqnb8QzlbfOQeEfWp(9pd=Y<L`<_3?vz2J7`xge|u~E3*N?P?` zzs!<Cb5P^tlx-B7s<-N2LEWO4$wqd`6;uXroyIm{*~p*r_Io{4s%9<*Q!3f=11nN| z^P$+)Z>BI4CC_g(y*cTtyUlvQZ3qotrA(b~-vrj*(oymMdVfXbLOB@ZnoOe0#zPfg z#~)DP|0Lk!HW&?k#>kFEbSakvQ9e8J!~9EE7`5DnS{0F2F|Xg`H|*t1)Ew;_Oc)?9 zWxvo+G1x(+$h6ET`C5%Qn1`_ZHwst3foJqI!SN-rbF2o!1gHm^(TRs1^`&oRgBZ*L zxIb!EO#xGrr$S4jfX!Yh{uLzELU8dO{q7wpjPc+#x;B-IL0;JIZ}8`<rH*zfg{9;k ziJrRlZ6&`+i3EvKw)ybNkU=lWu@@!5XMj}DX-AFkUJIc+Hj?lfDsUyIsG0dO2xqfH zFM4Lz$v88`boI0@1YD+YKp*U49dKim1jE%k+ngIWL(Qn)nTNujq_dUsWr^TD_*iHi z;39P;=7+hUUhh$4gN%M|J#w4{h8UVfB;pybhe<uJFA8ZtKiNR`?r2>Hd@Ij?4<;V3 z6u8yjROa~iyK$%7LgY3@jYKgxUc?jGwJb<AX*jCGaNC$nIsYJu+H+)L`FLKshN!W~ zRXuBoN>ZY@hS(<hAV*py+$4GlO3%8LsGU{gGd=Ay=<|6e`CY7pe%9b?9HT@aj%9`x zyjcEM7?Kk5`1*~~!pGcmDe-o@J_r+QCa>A{#76tuiD`@3?@Q<c<9_HVGE2<|<0sW# z?52;~GG9hho;MvdOrGk7;X=j#HjM3W{U)!H4~|dD>pApjPLNGLV|=gF_^z(sGB^dZ z@v8}xa!jTMLX~4kJ;Swi62jXX)r8NN>>~F3mr@sw@J(vXa&`B{pMXbho`PTbgWbX} z^v+xv#`}&mTv#ct&zP)@U9Wv*)_JI4hcWQkHEc_@+<g{fA3Tk&*?rlsf^|LYHW}H@ zvy}+ns`nmW`)!~nv9a3MS7d2KJTB_hxY=kxcNyOK39Q`JvI_*Wg(j?@s<)4^G+pa1 zC7Fb1IB{nHlc(()mKbs}wb|e#aQ-kZ0qqpYh{Z7S3Zq!AEwM)$6{>f@7XDZKE!PJm zy*+Q>9xC$I`;40wAvRt>79Q90CJ!HD>8!WESuo5!=aZ(t&$=GF$rBs<m$jf2IFyrk zCKu_J;%J@E`~F=bwt84E)nlybR1I3TGqLTNg~kIx-N}I;=5cnaSw(A|v`}YllLI0? zJ{TG0AGzh2jocEsR52*fw#X-P_&rD>{6{S^lBspu?SIeUSMOwbQ*>mr732b*n#&!3 zVN}gf*;;uhF&4j-Y3@e;4H^67bs<h5?X0?fLNMn$<h~>^%RANTK%)P&5N7A?I=FJ? zVWtL8R_6acgY)nU%<i*POzlaqn;_Oq!24GkyO=HC1{*dnkR)%4wA{}3=G_C5?!@WX zQQEi~Gb9750%~-!Bn&72u1*}_g}iQ8Z+4Y;>pSPf5cA<uc@pmSEfeG0gTFca?*$Hp zvu06>ysUro?Kp4ZTs7iFNoOnq)UY5@8sx!a=n}j2s03to6_7w^O(iC#Nch4SWNIiH z>knnXCW!I8m2wIMonK(#`CPzTf~$CHe&<Z3l1`M#aP(lkFY}RHPS?G2`*Ks7|04gB zyq6Y}Jo_Z7Tlb{?2s&tsmy06_4BdacKe+s>R&&Ve*Z$sp>HKCXZ7PW*r;)<DAVPV} zptddsbr<w=(?6iSOT>LapWFjn03piOLvqN)=u(7pS}#tdm#>DS;?s7!^&9cudjtV| zzQ(Kf`nR=*KAT!a<N_DlL{7r$^JaWD+H+S69vmF38BrT!pKimymIv9VQ>9L(QJ>47 zKYVRb$HN)Yy6U8+;<p|AXl-POIPJr~L>;8z)~@RIECC%cni$@3p?maQvxj##vQ_@y z!TpY0Euvg5{Fty~Oa}ud7)s9%i->q9!9}8--vh84L$jOR<rrNTOn?|iR)0t#jRscq zj&QerA5L+t&jd=GE#Tdu&w1-%p!(Y8AG;NQq+m$>t7bmg230i!mb-hc@?f0wAo)N} z=LuS19VN-Gs(DsAsolD-(dqD9(E=#*6GipF4$|^h+w6X@Mk<(Vdo}EYsgwmt_TuQ( z02xE86_5G0q*=R^Fw7|R$vX}8nG6g5gy(%^k=P=oT3byfx#uxnr~mW2wK@~z>BWp+ z4jIB`*y-l86zd5e4GKejyAXk6+u(cY_EbyRauxKkz!6p##f{`y&ip$yzDaO3%<vv$ z5ew_K@<l;uoo%~%%b1Sk<$iN3x~b%NN!T^6WrD~aZF=>R^54``6ho#H*tFD%j%x3T zW*tV{#R4EWLIXHPG??HxKw#`M{JP~EuRJYKEubY8U-~zY^f>66jqNJ8RYd4HSf8n2 zXNYlfAj+Xy$tah%Hsml?U$3i3$A(h)cPFV_BE)uvC1BmW`?GfG?sQu>j=S*R4nJ!} zp?5%6_Ew5GFU?{<6@qrl`B&3!UO6RbOCJ>22~z)!en?QAeR3R`ptJd1GR%=%c^SHl z>)9Ri<{RK@S|wWx(#u(oo814^_)Zxb<1|>6gk<q{wjL9zEs1{_8DZ6Pi%t=AvafU% zZU%XRewL%_c!;HOsz^W3lLom$pq(SxR_WJ~O209Cm&iAxEDfy}bM;@jol0bGyIv0N z?EaDQG9+F)B`r+-M}O7&utVgxRS`oCxLwXe-RdDDCY!~jh<Om}Go@@us5x}r1-+b7 ztq;ap1U5qVwVBpG6O~1WtwgsvM~HHQjnwj)=Ge(J$Q~G9^^X<+R^p9#mBSx$sGTnD zZLmg~<dOz5zJQU<QvB;G@%!h?N7vE*Cf+};Fd09wHAJ1QJCoK*-YjLr-zamiq7-<A z4~CWMLosso9Y4`7sz;TMRo1*vS=icpb_5ca>${zOp6ym0i~_h$L?b_Sy7j+|KHx|K zK+BJ$-Tgq7{E_EaIt)c0m75#y$Qv-0z~mT>fG;-O_+w-mm8r9J)Wo~#`~HmYhJbyj z3dk0-BEYWwLqZ_B*pFo8tFe+i)$<dpnNYL9r2p1c>cst~vf<_UJxTYI$wyqKnBS@a zn;+iXp3D~ztn-k$gj!yer^trai78~!V5;o)!NMG-k(DKzW&)Br@D}>y*s@nMHTmnO zUjbhhQA(+$p{JdQ`oeI(O@=z=`Tg3%3T)@yuM)ReOY(v48vnP}zw|*%5;wB6B=)#5 z(S2UDUJBd3AobaW{)6gl_=*7NIJ6o)1sk;||9nIAZB{Y@Tr}W4x$H!4K1@&+%8Pb* z<<eX@8@2z%Cj97`{UB%$PcxC3azrPaMjHy0f{w4o`yqAdTxSRX@>YLfI{C>vADPK| zPC-e<|G86VIs>D`GTkcJP<Pn=>smOGyq4+Qug*>~#Q(+d5J=0LP%NH{)+^|Bz&74d zkS?~HdP_gxO9O#|v+#YGI+))Cwk@%)hIDs4ytT8on=%`oPY7my*3_eg?MNb>!EcHk zLQYetuKs?qpNn0yLW%H`?RSXRh9dkHKJI`KPqEQw1%^ueR{m$jdmUky<#w(V&f~9I zVAyBKnT^{lI>xrZiD48pR=4OpA&8E_=gX1q0d9qVL@DPn^Qhs9)8dKEL2eMBD;a>n zOmP&maqj#0{<`Z&pSjpYb#Tc}YO9{^>Ln}SHUnH|$I=(i{v$l^1r<bQNb|{wkk93o z?gDOwfFww`<oY0(>GE<cX&Dmhc|45!b5=wqQ?h~^8d?O|1a#8|jL$9p<niz{$FI~Y zweGbz4KIA?vkM-zS4jVRTS2+!A)$d9q4aEJ79o|bcXlSHr^0ex<Br**K<q9h3>-^M zCACJ|0$g-kYb07n6|s+8)_Nd=$DL0neGY^~Zy5EXYF=-3g1`)GHkh-g+K!0vaz8YB zATdj_0hJmjJ7y9JUXuiFsH!K`Mp&mdX9FTH2VOrKcPZEE&dqb*4&ti6198$rVMEh8 z;Bwo)DrI6SKW)t-Z!=beV|#4+<f3`L?(fYFI=|AMIh^%0pL;0{`|MM8zHIB}onadB z07`hBO$rxXq$dka*f5Q)9m(VmKIr%X;=YS_Nr#K2eG!38M;G4@j$8mGqkvzGL$mvr zJCPcxv&D74QY#aaxiw^=(jcP$x+H$GpWliR(2hb6wB!jUNm!c=KXLdP^A>z=C*zX^ zz(8YSB)pn|z~|NJpyVzH+gCuj8Un5|C=Th+6{Rs-V75W|55Q>dx_0eZIs9W`@+kY$ z{|I_juA)uP1OuO(-M%%}VuX$b9}$T1cm0v)=<tMmzDA^OL1d&D_2M!y6vSC;o&8a- ze;D}mVn!GGCAYc5%Bft|K2}5|S;4Li8FU8{WL}3;w%i{bFg9B+5RiQfY&{Ea%gF}R znyw*E^&})EbPl2juZ>$~G1a6|m`)$;Ir0KOMxqPa*F-_Lm0247C1RXNl7X_)9XzZM znzgYQ{3E^d#%bQ(=Cjp1DYStp*4rZAe|=6VlMt<fvtr?_!1BS(ZugvQ5p#Vp(NME^ zdRi(fhLsiwH}zYk*m(96-jL=09LB{Z4fVc(uaglD)<~iu;cwLO{QW0L*-aUrb!MD? zQxsscbU7xvl%s%C2VqsUQyjZ0ZnN5OMb8$6ye`wo7rHwyh_<%!$2nT_Zi<3Omr|`9 z)v0D?ie{XC^5}D6BxE}rESS$?45#luw57<rGV_h}gj61R+OD)|u|lroI-$}h##yVg z!UoxI69K4*_1-ftkUpi$LE;MX=VwC#@)|@uDOr$40Nnt^)MvLJxXlZnk2xeFVq+eH zb?D`6Ia1{PrU5XfouOBuKtLGNWK9^A`Tx&n;X2ek+M>mUW;19h`*`u;U^Icfe=e{N z1aFojCI<qA+vry!#$1ZEjSQ9ia{sc(LoRXlONf~E%XW}1vUota1}eEjOo?#)G%~&9 zGAQ!*4i&d5vWoEl;xPk)6dFvl|HDxO|KpH!U4cDD8`3sy^f|Zgz&@iq=T?~oa;A#U z*O!mHz!{~<Xfe3+L0@h|<m<BkpnA)ghtB|~5xo!CzpqP3-0rlrj5XHJZ+sQGFT-eq z=n#PFX&Z_pGmMhqRJW74oXlS56|zec?`ok7etVKcL|%4LQ=|qaT>}*0Is#Y+-1KXh ze-;CyyKZebo4?^VGKc@`?qi5`s)5l&L<x)#-QpmK9P{9=uZNrR-GA=~%d#^1)l-2T zc;CN5#UfPD#k^i}Y2NVg7b`sPWQ&?0_h2PT#W?5%BDxHXaW&8t*96zX{`^c=TWe2A zon4(U0oUoPRWS+aLwP=>&f0MpL$d8{dj<JyCYtA3ZSlNjPGn;shG7gU`n#lt$o1v^ zp_-B4{l%2BktIrl3|srNTJrU8@q$->e^*YLS+b;l&7(tODhXRe#NnHy*ml~9de$K2 z?i1HdayCqVY(>Fv6_f``nw*_CrqmP;%Yi^<VQ8}Vi7Fx2vtL<=iQjzrF6S|xh)nUX zzZsk8_$%@E3YeX7$(=YN5%Bk!tLtw4E#!V~pIB6Y4|Q$9r!^ZD!*$Feb<Z^$=lc^0 zoCOm#gJk&}MmSTXo}04rF@*~PGKc4rhCq|n(#{VIdsnCtggp+saJW>~-`4hQ3>QX? z{1CF-xqrgm2VBs}wIF?xUcx8SkpaOsKE%WE3>w_<bc0=Eh}m&P$)+Xp<LXohN*O;< za37$3e}JX`+xeKgL}X+T7b}qE`}|%~rfhWa<ZFi5e`-Kpp@ij@lVlNv8lu=x7bRTu zNXmj(VHhUcBTiPo!l;EC?OQM-BV+@x3Tl26@#rNk0%i3w`vFFb=9ioMmAUt%|9cVJ z9J@4N9XIJ1TAX}_0Ic2=0;Ob|Dd9nLKAG+m;C(wP#@J{lq47<hvYX3Fh5S;=eyCB- zI}@cVpe-GL{dT$Rwnpx=1KD;y5h!U;Q1LYAqSqeB+>(EN(Cgfddxd>RCKp`aht)_c zbSH>l!_JmwHO)TS^O>@r;cuOMNpuCgvkK7;ygu&G>(rS!`&!RuI9*+V%a^R&>G+qO z3|pgjNd}zC^%`Xt2cd<(fpZ%b!EqwLV$@=Nc@#h&6Y*LvqCqD(@EwF=5R1eqHQ>Mk zH_7W(Sqm=#nwJk<@bQ6u7K}e#q7`}kYXJmAO>>}<{J)1`SgbZA{xhchHd0%&@0Ub< zPP>lRpiweO;-PW;j8RQ0D&p+Mt?r^a8GCu$O2(f2;$V-H*a}=KN_>zi<k`IO=I433 zRjxRJRKOHKeitvP|Ab`;ea+wEz9g25Q$k0@hFkF2G%5_$N(Yhr@?qa-?#9t#_7w*N z@6j{&8JvF%F|OBE)~BcoV0GMKDTD9sH-u0NrQf+_>?N9Iy96@JW)XZ?{rPg3YvmOb zr-A-lb<o^ZjcTu7CbHbpVB^aYdfR69`0Y1O0#J}qn;9rK9A?h+JMD#*gvnYh5wMv& z#aIz<r@ul&6@S2C@3Z`Q0m_)KPaZ|DMaG?~0iK&)a6okrOK&T9kE=+}_^+VOoJ06q zh0}4c{l(*{=a=#@YMhXY8LMUGqOenIfa8#q<#al>_?)}E5Toqlt(ciDbzO^?B`i+W zob-B~Btp%PuNy$_x5aGW|Elm8H6B6>3S6!Jo6Bd;q@MKU`$_aWGWB_fidlM>ri*J> zOd|^oyej0Cy1$H!H#sXmd>kSUM{d*PBcr1LDn4Jn<gt|GT=Zk)WhV?K&aoGDz#*kz z_nF%d&uh~^9Th;^w`t@&6WC3!<jS*IWynMB#HE;q`Si#@x8)lIQ?LwZ-amM}MNxHE zZ{=@nuANFLghKyTZDLeEHT2&mhB}LcQS2-U16#TC8*aa2LE}FOuHv&aW$`F;B#s41 z5fNUqe`Kt<?TxhJ_mn$#lIM2y!#Zh_OQ)_Dlc~q$3ehDw`6_G6wb`0=yKe60*5G$= zF`VScxN}2FNj~(HVo6AhSKq0^s&+?E!f9)38EQ~6)MlnmFuN)8?~`jD77zI@&*1=e z$BK@Dre&a%W)7g3|JZkT_UB%4iw7eVs_!`UJI!r>A|BT62cph%A=6Pz4J}oHA&=<M z{u*Ure82Z(?tb{=-b|0xCn@aEsJ7Oq@t#;9Nc@J(YV;kI2v0yoMCuSpn$O%OBBD0s zxA%<z_c8sy^{PTxx3KX@tdjv!4?yORTy-0!8|00V@+Gg0;tBr8#h*JkfmkjVVbuvi zKB;SP>ejW=Mo>#URB!lXWu)FGo3;ZV9s8ydMc8{mKP`46{Zu!{invlCxC1`bAb^mg zp6WYZVprQ!5(R%?=~z-}{!^<$Ta(`Xam>#OlY6qQHV&-LK-i+*2esktolv^gRD%Ms z4=GXv3TqZI-dYPs8Y23rq^Am-<Ti6ozJK2LNd*8q!Uxe3c_G*;@#p7>c^xx{kH-QZ z&<%WOoOZl>vuQ|GP{`x>He;#Xo|wRAKfD{YU**zNDS3QY{NIm!Pn-j`IZ6<OK){^M z<lc3F@o9OT0#V1MH4M<eO50jo`R#LNnhQ<Gb+`GVqajGqDAczp<m!^4$3VI#UJc*^ z%lqE2d8s3ky+k+6853anXQ6tBG%A3|EtN=cG^-zJq~!F=8p~CL5ZEQel`%#n5{CDo z7C$;~*z>BW(I<Cc--71**>~;81sP8}u_)FbWQYBHE<~QbnEx<*crKaaraSsVG<T~P zLi7T_I*cLS^3qb`I7Zg&<0*=%v|%=FpI~}>{hASpLG&4xOfSJrJ*omf;vusk=5lSr zZj$@TN|*4eG7&7!(PGqpD}&z>BcBf^!{18xi{g^E+P3*zWhWPkIb~af69J$3Asa4> zOEskI^TPC^D8ksuH?Rm9FhV6)a;c;c&)-&u@5z%2X<OUsR@#^$L2IiZG<nyzfexlt z=9R6W8nLY4D{tk3YhXTb%MyyQvA82k-iyaF=`UNGnT$>Cw~g+_BGV92=NwgKP&m2h z4$if5Z%kR?T$lhS*!Dy&-ye>i+kUk|Yvb|J*3q7~tlfCd?ywM;9?|*mA~u`;w5xmo z=LcUQQyrr_U1S4x{v<~z#{Luyj5N^d4ssP{@HrpKyy$-A>$do)ngy?|u{iyY*+-og zY&7v`jE*{U<Ke_Jsqu6|H<c1yoSpEVa5&fmU>|mvV=y4sxpLnnwU{Y-q{&ty7U6$v zTYW;Gi42!}slf?#5ZQ){c~+gpq&QgpEl{mTgJ;U1$|4(B){UC@_;<1{g>C5O5(}K~ z8fMIVJ3RKQ@!Qr^_hX~Lxgb<1Pxdv=SCEQ7#sm+tg1kxP)Ds&<sKWhixXT*Lb_4Jf z+Z&=cx=CfR6bznQxg^R5W*Zy=7~HF&DxvH@yUnXJ?_k_iZVps|!*|5Db|8fCKivSf zSy^ycYMo2ig*~*g@9(TQ#w#D`N8Cq&p-%mmK>*f0+RD}LIKW%5r57mbG?gThG)Jp0 z32(|a4S0;>=6i74=a7R432>cjad<X6dz<KY@c-)9+8kLf&tSr2xM#Q|T1>l%jRXO< z1dko+=z0?UKVhHskq}xOrQEdL17y6~#4cDwyD@WwvtX>2Hv^kD8s&J-Y$q)=6v%p+ zqCl<)?p@yaQt^WCV2p27c(p^fpMRPd*&x3>DRsZ4zLAY;6p=MjB+3TN?7jyF{@lna zVCk{rtLfB!NZ)Im)S5o;7S9et0(eypG%rH)dkZsnx}eAV!v9@BkElr>*!f=s<4g=` z^DjF20fPW!&q17}Tx3!ngbe!lT~qgpI{jU0VA#aYIC91+HXIgZkD_u%z!~}@*IP_> zs=Y)bIs}RX@j|-LGin4tEI1~T<F5P51lQG0dHLJBuC6pVm1vQ4e%j>e+M4Qa+o?$d zclnp83s-RU{>~CT;FrZC*_6zk;&<W{_F9fn=_DljtYTOD?kN5|Wufs(bE5yNZkhkh zU5VRV^*$#UcdOx0?*6&)OD+yT=5SxqqH)4#`{$DXp?4hpj^p@%IEO&>VxNmvK&oVt zTq>siwq#r^K;B~h?=#Q?%Y@HnxgJj1xRc26aUof>vr=zv*6;8CH=w~=gfPJXqA<#) zT#-%0BU)(+n_ieUHkC9~9{|ikXpvO5axaz-gQZbi{8Ast50VpEJTC+@3^|BZNP<2| zY{gKKp#4m}R17|X!wl9@8*VYK=sM+jh?y95sz=!pA@ecpZh!gEbqaFb{YB(x+7<NJ z{TkQ+fs&f;G+;r&$P{0Uw}QTPd%xm$wtthp*`jH{6#!b-^E{^aH$|k$r^HV8L|cqn z<C5EEb>G3ewd7ghXtCK_v{Vd{-wqdzgf7DQc8U{w|0~NPwkkA&wNN6VR`%Ty<hlHM zeU#SkWB$p+`XLDmYX&PTwFte{&Q8eC`cKU-dG4vJmuvMk+O!#JG{1-DXc%_CI@Skz zYZd$1xTtODrZFWPhZisHVhlFUZ}H8J2Tz;z!99-8OZMv(<gFJ(Nd7pg7{|qpaVU1* z;c|5yQ6@9g`gM1;?^)-mDy5`-iwS_M=}qsSt37D-i70+B0!4D*OQ6GN5Jx2O1`im- zl&!{$eIb0S<2qJ=K3n=jLxe>Q6*0jQM-Jo~vr4Xo^;-Fj4iIuc-&5H8{>$-kvX#Ot z?#*b})LAJttv#k4w7?Xw1e=Q-Wg?IPanFtJt<+7lfxLegtQ11fQ-GBOXl_9cFE~SO zc*NiE0e|z?SE%ats(Nfa)=bZZQ7eYOx0f3|vSwkII_q8x>J5IA)jDt{pDyU;L>>Rb zI;vKSaU^WxL5_hq)JHLeeQ3NpYmW<q2TKz_cA*d7EchN#q0B))>Dmau*j}q5Dm@=8 z5)}MRjyAL5W3jolHQePQAbCrl(sNbl5%>V^W8gM${)_H}OxHco8jsRwmO2XO7+X9K zXhNYt)-eBX=MNo?0fms9&D=Qv=7R54{bBiWDyp7gFxsyV1`{B9#Ngq3-caCUZruR` z8y>4QHPT^mUT~7o9(u;Qz3z|dJ$~~RMQ0>+;oFKJ6XZVsRVGmQ#@@OU=kGR}X-jTk zjDpw8bFq>4W5VuepJ8YTYbLQgK4|f@i}4kvP#QgyZKQz{iqD{OtNOVd5|3;+zw(3m zuzs2D$Y$^dHW2*{<4pd(F1KIPx5r)SL#EV9l&6xJ%Gy6HC$*Wk|4cOt=4$FmwjdJR z4Wd)9jhL_+4Z&2Ft&PnHLZ1vk5Ba$1e$h6Hm<3EtNG9odM~Oq2719Lvi~WIxu+~%% zp*Gg?<n;cru>7vtx6Qn%DAkL1%7MA8WUgva_)&d9?{-m-J{Rf?j>F@1_Cp5KVy8b$ zG&|WSKRqctID~c0kKb2F-+mO+0-62hrKR(LOIyDT_VJ2VM>P0ns!|5m7i`rJ>PPH^ zUwPe6*w>o&OR2EA85!XAvFfXV0UD>B-j~l|V~m$ifb0fS_{T)lYwjMNv+wJX%+p{B z9Tu}<e*Ab8C{tT@Y2KfE62j0wq~QzPwU%?|NO4NTWUTjx({1UVtQq5}|254|>^?2x zwB3L5(aQL7wiUvv7cMiM`<Yp73{C3VH;gF9@9sm#ZOz5oDZSDPlH}qM=k^+OVk#=< zX?6u{ZA_~p>%rA2-CneeO~-Vdjn{M{LaOAW&2Fg2xN#orJEU1HxW&KHAhWOFT)|Yz zziT*C+xgPDx4E1Q!2191u|O`4_Q>xeKZ<{B+cO|(wOLOp`V_w)qzM9<u^z|k6>pad zkpD$B&VHDyz>mAWArG0Chv#2mY<V=G`|!54sg6L(*GgjTm7r2Tq&m)Gn(F}(S!v(J z!2`NXPzUDNWTLaMcGCgT&WjKT-%s9dy9kd;74wTKpAZVH{SCb!HvE$;=<ftpUK6Yk z28cOYYae5J+Nl2h+1KYGu0wm9phEbbzt-fa$!HpzHXM2WvFl9NimXU|GbSF^HC`%M ziPrOmn|}8ao?GPz|J^{m7<vu4FQs1(59zcWmW6&BoTP=Y)~DCvVPSdl)rlMVkb~|9 z8XzmpWI1?<(5JQ>qqT<G@DIVTmB#Dk!hYwc;C^_6^`<;*E8^W3|GAIBwJIqeYl_B4 ziKJ#ClwbBRPRmLRVJsvhzhd!qJiGh>xy;4w@qW#V7S&vG8v8zYur2#LVcRlZ#FQKw zPL6L>yK7A~OnbnfM1YkTOho>DgWZ-aJG|<I06Xr%f-E49T|EaqOVhFkX^m+>!9p`T z1jp4~^A><%3OcVG-wIBrx}McG$!CU?r@7RCy!(F-2h)q>I;riaGC56Six%@G`pw!e zc~6SMm`d1jl~3?ZU5r$-e}>epcmm$}Kb#?BH7GFg4UNw_WMW-cGIdLLw|?k)C9xzO zLzTkEUFyAawllN9$Qz3B7O%IJ$6J+(r^1R;M&C5U>Fj1!FRq_OrFs3kJ)B!t(dBG( ziBaKP5b=Gbgs>zQr!aKUY%qwd;~)rpq(=f*dbFZgI1?J&AKvwMz0R&Z_FCE$6$>jP z2J&Ncb&=uaq*}Elop`V)4W*9tirx~6OvN(po;+T0h=09}pj$EcC(;}JSrW9X;wFxe z@Q}BEBJzOfcY6~JQ%@zvqxjox@?l8-pAXk8mBKeAQ2AnGB=O~(O(!e$LhO^Q&E9We zDyrF@_c9)Oa-{4&J2~OoIC#%}=|8iCu0Z`6n~}WyPovf7`mK2-=i(y(3@1z(q|r5E ze^^0}PHuuHP@9$TTSGW^SiB-g+^ZOFdNRN26|`oQ?P^eH&WQLfu&r&rkc7^bpZh$! zx(JW2ON(6_#j@&pXxQg+J3q&|gL5w|_)Q-e_UB9wc8AvW<#v4o5Kwc2Dl~Tv|J$Pn z1K$J4w<cl)cc2EwxaV2Kb2dOOF^>et`TFzWKO0Nc5Q#O(=lV_EX~|8GcWv`MzE|tL z=t}N2GZhv3y8pb^nTucV$wQjsV>1~8?PnczydMUVTWCLiFhh3qmSC9|c1E}-D5u^X z^)aJ4GM&4@Z$MY}B;ojBP^HV2AP>!Q5Y>EWHPI*P2;%d{ZPrt@SLhs#Sc^TS1ZW`1 zU5>=)X_dsivS*~8n(&)xkfxTCR&llW+o@j57btSr!Tt9~bgpY)d8MWv@KQ)^m-`%X zCW-W1kHg5`I~HTm$y8#p$OzJ_KPhgP?*jcH=hU^+pW^3?KFa<#-Vi}gF@g?l9fsDI zY%fz>Ct%D5b;j5Ol;Q<(uo98ZMUuKGXp3io85l1)xq<n_R=VjH-)_keOtf2VS-PDs zp<nuRWWP5^`0gD*_~18M?cc_cT3u5YsC3RIb~&Gea$i+ie_s(`_OsXH`9S3FzrQ}u zUgY1t#cEO}Tovx6+X)H-6S#t-P~%XKT9EkRVzS=MODjfSCc|p^U&Fq3aH%+dkBCsX zh4kJFyk4K3z_vXJ#!IE|uXlBHw_sY(|G+IFln3qpy^)Ay-Fzjq0@EBOjaM8+{WBM9 zJf|l;0E=r3hPX{2%juv=&*LV@5O<q>3~%iVsOmxf|5mugxIc7G$@k?kzUz_Wd$Bfi zj=Dv|>FdSg;8`JXAB2rmlud#4ZU$?o0W%}^4(a8FixymI(E&<`I}>ha)7uyLE;a|~ zAu_q|%FF3SF5au((Y>f@nGT4!1LIfSkECm-b%G6U6pE>(P#ttpL{Y`(xkiuUPfuqC z7&>QV2UoG=o&^aj?pRoS-!IVvvc545|DD$V^p>|C=}!;%OE#HlIn(uJ2a0M$1ZmjI z@K8vNk^io2_qLGcZ^dNilso{Z{pV?56}?NrW|+*!*K}$ZD2Gfo>G29qtGz3dAI{)V z-^9a896A*VaQ*>5R?#DLzw6@hcgE7rVUvf%LI+G-9E#Y<IH@<fsoy-Hg{67Vi<+~= zIn(y1*7Yc}u(q~4n*N83y-CCX8)(O`D<LZDh}x)wE~ZsmX%-Jl7TnyiF8YzS-Q)m; z$%vcI%u9EJ1xSDz^FoT@CGmJqgX<Uzw|sl&KsGVE0+Rq~)e};M8do@zOO`X3U5Z3V zncd=*w|2ols7FN=Uh(>Iux4Ar`{je+(_zgx-+{43tr<c2k;gw^04u}o5Nrg4$3HM$ zR(;2C-t`S9-e_74C0kxcnx9GoROB?+I{RezY58l9!M&jFD|)&eqY=?p3N%g%_{-i+ z-oXCn^_8Aaj4cJ_CeEub8=k`lc+PXTaOVd@KV5x;_Kk#<g`VMrA8JG-{l+Ul#8=l8 zGg6_iy$*%JOD^!hYreYyCjZ10Dz{voecmq=G&9Z#r&1I0`Q!uL2$zTi|0U(u+EtGR zwhE<65#s;N4((YHonqT6z}!h->U5~C&VY{>I93vb2q`=?VGoVDf_J3)E-oBjlByXF z{`qD{nBwAk9cy(InAkC;^4c2^fiBd(xo48Sb2bmmd?jrDf3*Nrf1@HeKh>9(zM~no zdu-l(zGS`X=!1&CZ7_k2LE_cK<oSguDs9Qp<$H#&>Am9SKVJMONYiWJa>cIwXK7M< zi<@>_x24xk<RTZMxIdLQT=D|lta2UqymI*7t)m<rvGSpKn{--tP;2A*>%iALmZBA2 zY|;Jp<H}+i9`rS*`+ke5&ckHq>w{_W;XE`--~;Bg7rIXoPNfuU!;Du?NKqQh=v=Hh zwiI>`yjlz0VZ=)8$LuejaDYI%ko{nn)XR1Swlw(u8;G1-1^1s_Ic$_Ifw_OK6Bco3 zu1mhTDHSh{Yve!xZ%A2qj*N`Shlix)3d5SJ?oPoNm05Bdh9^WSj7`tX#Q1yP%ZlnX z9im2d-lu)Km7wSv&xPEk(&{^HFbqi;6TMnM+0KXUaFi|z1GfeI?<bLeYj|7}D6NZ! zr80tOgqA~k4wT4y3tm|EjTi>aC;bl@+U&z!BFvB)bn6%O;n5%m-ehl4XEpDA>a|<& zf#pIdxH@cjE%)HE8{A6uohW^FiD`wo@|tvW+S%T-QcyWV+I|*Ac^($~z1+w<b{Q0x z|Gzz!k)RH!p0w~eSz#9R%VU%!HTjgEVP-V=HLBr)#sv#&8N<kL>ws;{xN+JI)686f z{VrooY-nwC98IcEly{L$kT?9^pvl@+{3nW-LJh1Ezh)Wv6ycLp(N+b4gQ%q?2kjZ! zRqdVeHo?PPXT09sfQx9bdM$Qhu(36h1+Rk{EDN8@pBjryxZ0!HK?v8roYe{JEM@RE z>&tW9mFO4l|NMC>wbh4#-I8=LD38D7eeNn(IV@ZR^Rt0zw0!9!9u^-dEK}6PL27gN z>)jUX_S2*kNpfDr*S3G65n#COGtsi-csXjbBR#*6wB~N;>eJUZr}-X1Lp3{%7BBpg z&93>gPIn}{QK!K_*d%E=(XlZBe6*Ed@?gyB;61m}hA0Y`dbF5M)_jou`~9H!H%Q2} zX`YMLjp^fIViA#5vf7uZQrOz3T&Vx+x%6ICIu#Y`YS_cCf>z+)E_WufQ8ftdF|2(u zUzhi(@l$-zn(BynBzw?!NF=?_k_3U?QH+#k)o^WXZunBQ31qt2p=k?uGalJA?C_f( z2S|e6$#1GJt-b6l6Kpd~Qqmr!b}MK7zk!5Bb!L>#=U*NAo_S7ptGR$HaHVdgSxLqg zTqQw8?1?~VEit({F(|tBl#qgH%6NT6ea`)$q2((~XR=>W*yVTqdBbbFjmqRVjEZ!O za{MEQC)u2$<O4f+oA1o7|KM9UL#jx2$Ikctr%r6Y4Z4em_`jaa@1jQrR%`tI9_iaw zvy2f)8O!qo403X&Q#owM*~g5D{<7W++ItG*s>d;i)B(GIOfSEqL@4Zk$5{L2@J)I2 zr9@GFtDS84SyZdtUI2gz`j7}mcq9k7d0e$H1e=ko%T{j2IzNCJ{)-HVKL*^fH&Eio zwm%ru>;N~R?NMZz1Y+rY*3i0ah>)Rv48IUU2^-KzSC--=hT*w>bz#Ehui`YyerOUV z96^~}<{z+864sQ~R-R*z^Z#909hAQp*?!;oNaO0N{v3Rr&5#x1&wnjJ$Fb(O)DJ+J z5VNY$vS~)D2GT$hAPcT&_{QX?TL<rQ9_gY<rFwZwcVB`9M4*z+(3l)10K@L~1~NiZ z4Q$eOcqU1UbrdPB{+2JGit7`wMo6qhd<2q7eYCTrky!-JAf&gjJEWrJx8)tNzBNJn zKj47#jp>Nkr+^_r+AaXEyH^>(u~ikJ8WE|OG(<!Ys$BjEH-e`YooCal50CO$MH7CH z4D&`BnNVzCm$d(pRXFfMyIK2wz|{x;Z8uxbE<%8c*!^PkqNzu1T9JrikIJ=dQ?fH^ zyUJk_WcWe|8(H-wevuqxM$XOpBOKs7bMisHyaS-o4|9R!utkOM3A{*m?)?1)Yrdvq z&}u_1u&@&0<L%G_h@|lEcKRKJ17qk~R4x%!`**tH3i3iIKeFYYP*XV{5*y=}gb#@5 z;IDk)A(7+#XK4|nf(>YSBIT>%FDT<$bDf^|NPbW^x&avhKj}-U>ntj&*l1u*krzX* z%k7C_<q3y{GcwT&T_wbfbW?2q;m7DCo|$HU3Crq;!3jZyf3`hOS?n|Jn^VJf!UJ2P zqD0D%OM#U=Z_G5aD*fLReeyYN$N11suNIUV(a`}^6<1NoRyUy$#;F%vD##pFVQ(JN zd(a#?pVnD(nCXzts#pP;7vD5YVHJ`4(_-Y|@z=ZD&*V7jY|~3(jhsujivXS-DJ*Q6 zTOTLjA93%p+(R(X7ze6F;7OF)+q!D`(~bVN9bkByf4DI@v^!SiBD_l>_HmB>VvUs; zX3=9h)d6#mWSTRoqm~!;S7VRaVomqS_Tkmi!m%2Tqo28*+xfojgIrIxrn1?Zwz{D8 zK|IsIM7uN*BgKJodWOI7jO*W5+tNReBjBlJRAoVtUr_}SBZg~k%aMnNw(s0lI1)e> z8CMF$3xvJmT)y3I;glbFymvBg#L8FbsHl?ZuAfKO+l^uopWmDDGSlR&<UhRa&ahq$ zI-f@7c<lh-!O9(v|5)u9XEp*nf6Lw7uZlq4z~k>l|A09TJ$;C5Jl0!(!eoYP?NLsi z4?n%bO=f2kVHiww(>!l;8=9HHb_CV%x)r16T5+A5D)*Y#{XmNJImO!G3fZO19r>D# zN7P1<99((t1menog|Y9l{oelnG4+-~ac$4n@Bj&fU<m|wC%6UI;2y!<-CbvJcXtTx z5(qN5y9al7cYn{l_xFG5-BncaX{P3!-Mv?@UaR*E18y5ry4c&m!jWecJeR-AE?0<( zJ!CMpju13~8VfiBR_-o`!yvvZgI`kaVB{~Jn;uaCSxNhi*fGscIGmBb>oq2Au!kzw zEKz;m5baXwXln-l3i>5t7MkFL$WNMg?XrsT>GlgDAf-8=v<`{-_zio}-+zipyOzj8 z<$8i1E?nRh@jz$e%iwU;c~R!YHS^RpuoIA%RX*>KUf#^Y==mnJqQe$v18fJdjDHFl zx-r*gx8<tx!G>-Ye&MFXQ0_XcM?GIDm4B<A+Ph?MkJ1AT)=bkA6E!|pg=^UC6I9sI z4PicBAOY?h@ij5V^_CXsh8o?{xKwIrUd3EXK@W(jPpO6{&m~-gs*fPCmKN>(LY%D* z$5hVF9K;10dA^W_+wZTfrJxjA-B8I%aa>P)tc3uV3Y}1yQGyx$?W<EaAw^x~%f_F2 zUX3~M+Q3P|*i0Wv_5lnb4!b+&oMq@})JQ}J5qKqdVc!Pq#n*U>>rb!o#rsz9aeVq1 zQ@jQu8T!q~qJsF}S;=a!&3ic2y+}r?*U@}q|C!mUJn32ATglrJO+1mX<5cGl?g+mX zjS~31lHbK+C?f^&=NYVzDbLHIDB>cNM3qvX(tM1)UiV(x7)Mz&5~HesS4|EiGgb~M z&Y@WID|_Z7V#oecOkb%DhacRWp61)WM4pGK3`a+nh<&}pfuvBFtcSKJ%&{hio(3t= zPu*~KI!Ma&dmSi1&Kaysff>_8cG&+KwYj+gd08PhUj^8JwT(1BFzLmS257fZ(_av3 z$u9ViYn+fn%!;HTf&cvQk)q1Isuag0W&aKA$C%GM3kwTt>2wPgz#U%y#&C+c&3ZU) zJ2GZ!l-n@q@0v^e&k!hU$0ObFE0oGGaeeNWw!qE$v1X&LJgc4Mwm&@^C2>eFyC|_9 z39a}2g#fZtX+(6E#ro;+?~T8*(5fpHzYg2W3Y4Wk)>0Fkc%HEZvJ1~D1Zc#Zh`+cv z$ey@83_&j1H7Qzz)%J{NLns%eyEh~r7xT|J&0&%vA?H6eFiu>@r1p+18Hr68rmoy- z&aNha$xj|OWC^bT!Gplb*uR;|MbvNW3E>oIv4ESh?(flmQocNunX61$pX+cF)%fBW zsaNq;RJ0%z&htkFx&r_)fPzQ43QF#<d2$xM?p;{r4H#2zRQN&{Jp+Vd_f9N(I4kFm z=-^-tsQE4j^p<Ub2!=w0=r=IXoFj=f{4_y<tt`%70(#g*-lQ`3i9_OU`wKnWxnF>( zYa2Lkx21o&B~XA;)+e20><*_3t4eFsiE;=6SC2D^Upfcd@I&q5f+bDyPM`qGd2~vG z5;|)Fg6mrNy*=%SxRx)g0C1<Wy>r=Ih=%t<OaM|VKRU65r?*6<eBSvGIP!aeFg9q; zA5M?UEV~d#u{sB&DQfth8&ss6)^11DRfNd;Z$3^jyZKQbU^Vhf+gftch{Z06dNR0~ z0FJe)=#wF6czpVM2Sby@y$3b17DZ;&lNYoN2<ykYu73h3Xr9R5FB8Auc`SN++qdSM z*j&eb=Z7nmF5SCsBmDawq*+oXo4gY{du}ZJ&{)yAvGhynrDh8)F4oK{+t}`PTmjtH z*G-+ozP)O)#F-#53idZy{JRONZRP@({7mXu>4+j(XUGpY+{%An2ipWIZnOYC(<EF7 zWTo`fvnVk!{e47%*1>QtR~1g!(5){Ql?JUrGF^aAkb);o-VNhpiax1uz1tEkw4~&J zd09qMyuYjn4@=;WwJ=)$R{!doFK*NrjZJ%(+Vl$6EYVj3E5>(gl+<T3HtH&ht{(t; zq4V1x1ltP46gBYQ%d*!j{I#_U3N3655kwNjFJxMo{SGIIq~QHofGCpt7Q`*3AQT_z z)1`l-m1NVYG0K&QT7g5A8=FOMx2J>K9!2B@eF{kyq9=R5Dy#`LMq~sZv%Fz#XKmvs zKG8FF6n67f<SKsG9cK0xpc7)?@QB|qC@pzxQ-#wXqG$+*5<*_cA-*Un^swwt!~R)a zRLE({*O=AVm|%d~q(lHEgbu-d77A(n7sIoP^boE`Zc|9XMG7e^y0Ykek*x*<M#tMW znbAx7zwjIwDnGr0tz6{mKh<d>G%bBVPQHssCC2(_792?y$v{9TWD&k2sGL}MIc=Zf zi5f^x;AKT$veOD4`f%Fh&Zemlbdo03cph5~|J-hHIoarXQ83kL?L;iq*_m>V>MbI< z#ZMrj2iN+%hH-yhI}nziu1QaZGVd92<+7RR5;5tcN1k{2WfoI#Bp!ro{AK(d8=Ri$ zYy$AR{Z4d1b&7Vc(`i-uMM?19$^zBlq?y@j0w$$<Il+y{?a*mBQCaO7csw9CZG*BK z7d%DM`68vDJOcmCY&Irf^G2;2h7d%JQI1co!~%XSWe{_S$EVl+H!&nn-_2j@iv20* z{XO2R0;XYN_g7S8rXxn`)(-}8P9jdi%f4h}Y;BNWn-Oyq<&;1-VWL;+<D*c4xO>|X zYHbv>n~VJ@%S|&shr@?nXfCJPY*bE1pw0QKR$DcFq{HT;-IGONR3?XSrB++Oa>mHO zwgJnIE)K%w+0#qC;Dw^A_S6)8t)En$u<up%vFlxpeKvxNc2mCTJJoZ{)!33l*5fQK z9d6Ef;+7zKj#7YC2#<-#AUC@6e5%SvTy3()2t?TRPf-nDUc%;}!m4ig=@_Fknqz)) zlYbd%k$<8lx;5U{dJO@w-`4fKhbD}10US*KZ)6H3DL^X<EaOa7VeE>cNldDJc`ozF ziYS7EGkkb5wyvBPXYgZc`O+WofcD9B8JD{3d3|vIaMFE`Xlg)&khfaFb){X91-Mxp zoxzIXuJqPwoA`u4xSB*J%Tm2f*MbHj(7H;qf%wr)Dvu(D+wzA4zg5Gn7jVtReJPg} zmTpA50}~l!<0|KaS*<eUsl7NqbaAB>W?vjO*{A6K3EyaLINBuX?2-xV!Nphk(kn4I zxc|;aE*Mc&(FsNAD)&_D4=%X`aR)us<%5BGHeMqJQrj>qNjgb`k?V_gkRcfv>p*p7 z1jZve*L^VR>d>EB_E#D~@CdgS+kd%kg5}%3!n@#9c0|gchZ#0vJ6?2STqsYf-Q@|& zQ`{_}&YMl{BrryNIq*qc2*kh8&K?;zq>M^H4P&JEh!ShdyOmpBr;8ywD|HtnjMn-g z33tiES~bEu)iql@s<D5RA6_vaRStlSxnDjK`5OJ|OWg0g_tT1Qchx#-F}f%W$YJdI zmYHgwIV3DFZ?&D?D<faC)*uTpT&0oD|E!(}*S%j&smw{U;d63-FD7cZYVc+#mbRg1 zr>m{OlwUj$`ds9_^N9Umnnr8S>?31ALQ6uZ+x@u|-tjvCV`Shgd-j$0)2Y0r6YnvF zRf@MdY!WH+H;d>0m+JNOVI|C3N2~0MY4-;8f;%=xB(SL>L+Z2sq`T;}BAQxA+YIEW zznQEDe*R`M%&5(%5SKTbOk{k#-NR7cMQMO^6&<|C{oQF+?<%hwjntO@gj}!K(iM~w zHi>94l>n0%zG*RWw5R2C(P!1Y%kF5;G>~#&1odZD_tRSLSOSK_pCZOdR|2nmw+D{3 znM>`E7$XNnU^?`kr(SdODaEik)S68nd27m>{z|~RqqdG7-~{lIcZBu!WLR}>{>-mG z&Yrd(*3nabM_iYu?2i1>hAYY|M8z(sR|KP{t>1MZkdu#?44=jcz)25FMau$(oePkq z8Vkt87?|hCxUuz3I7!xp_dlX;*dO!`e9m;zUVkT*Q&^)mD}h>!oT8J+o|XO<D@5&3 z`SzR|_&PdxXcxo4My6b;R7h}tIHBJMOdT3##h+t~Zu4}pw%JVRGC8HWp=jE_16_2g zaT79c_)>;$(*m1mvq)v#IoscI(7mK7FWFiFv2fk#)bRXJuF3LOBr8rsrh=hB%(p=S ziWJs?3`zOyrj-|??+AKl5mgTWZW9|^!{U1?uO2rz)|wBD`?X`Z6M_M)ORwi++cE>Q zKpbm3dw$?Fs#CH%J+<t(=+K^-Uh?jEGA3g4#?)%^>eWFte4C=y%5oDSaSKyWoe<nl z+S9!G)oh(f)~9ifMx|8F?X4E&e~eatI3@;%zAT1*CQ9iJEs7B8X9=oCs+YMx!=ZkH z*l3PtyqxL1E@fJ<s^#zIF4usA*q8#g5P4*%^uA%d^)c_KR;IppqG$Xl|CDFUoT}GY zFoyV!{n&`fMIa%a_sq`5*P0U(j?TA{n2ww9Su?cOJXUX_JYA{B=6OVunaa|7a%C?E zyILpzDmK0Pyo&BOIOOyb&7k{Bid@A^cqj<q?OGBV4o{Co?;M`O;Lsfy9|)Or{*>{5 z@3rk7NT^Jw6b4kJ#Ypf&J@3^^8%|5)R9WUSh_m#s?DY9k0!gv*?31aOuPzGzav6i& z{M##A?0+$a0}teMHTu(z)O#ryE+eI^%4{Ui$h7h5H{KxnpKbt+2dosI$@f}PXMTxP z$5lyP_HYmB$s4Mds=_SKk3W+lE@W&LKAgy4C4hinHD(o=_I%3?Nzbb+I0?-ZJ{at& zVYH*xW?QAiqZJs!RnfL3AbwdxZ8kXGxQGfBtoV2V`3jG}SkhqE_nz+>!Q`xdRA=O5 z)R=@q97doR<yy(X>Y%SJieHNkT<AD#kitO|!Y)aSICM7pN9N2YOd-2xvv}m<83Clr zqCF-%?O-zgQ$~3WqcD_zvX3FN@E^FOO~sBZB?B5?@PDja@!uA4=x4^#ojZDOFxQWW z!ysE<;+G<MB=;dObd}Gty;P@KC<&+zs@_Ps{nWg2c?18z6ZRg;P|i?)?>$KUzn;u+ z|60(muSpK~hO0YoTe6QQu46<Zi(u|^9QG;9As(q&is0oP%I4F95gejDV8G7~@R7#0 zn+hLNDpTbHY4@vXqw(%)lL#Ppy-z=S?hn=Nm*F24?u)f@n|Hl<&r<Up!g4q8wkHEa z8x@uuc`6&$xSX9DqLGO%Ryw)Jh&@zMsw@{2ZLPm5Q~a!Xf_{I2O2T#Tk~o*+cT+Rr z=T}}?xuxj_<FkWO1?Q(Uxz>L!?;_*8bT6|imtZ-GYQ!-{0+Iv2t_dV}+tukb7J!N^ zE7krcTsBG6i+I-L4&)$53>>gp83%!W=iAH027O_)Pyf(ugCNB1#!ADMhoTqf9Zbj4 z>4QeMTq}-(P+*J*u=>Nll@#nypNnIU!DNe(aTDnOK?w9O-%zH1e~2#nmM+l!{@9|< zem1pd8$_hWog6hUy-9iT`=lHI@dIlHj~71QGJ1uSFZ{`KvD$BpELFr6lffCx5@nhT zL$40c$}3LWROy1hi!>9+2;bSK6B9&Aig^m)AVd_&5R}WjH+W{^8lCm2jyvnV6ZBZ> zi@bEh)3m`Ca2cgLJ0flgJQaXoHt{?oy4sbk2jL}bW$C|gk8e*G6sU`<FlG;*_a2e4 zvf<le;s4P0z>2fz+GSL21l4PDNVlErfyi+tZ7+gY>dXYd_5dvBc3`@X!_ESWh@k*f z2y8RE^Tr&PuAv^&%XR9ArT{y2NMbBPZ$km&O0Il=n$WAJB7Pkgu~oNCo4eVZtifhq zsp2gI8LOKe`bA?^xyYq%;{AK5ap26%%nyBQ*`@z@q7;@%@+boeQQe|S5e!*Y{*y5h zzsi%PiSIoOK-|qB&BByVN0<E&)>?npHlATLFjjqWzVd!uOthfZ$K@PH{x>`PFL)A! zF;>X1SwjWDd7MKu-Oyh*4GIlrQz?aHFudm^(EAS_`kV8-w0dUPVdx?BaqnB`Z`Tv! zJ!Ru$r(BTNUG&a*yR(u6sTAY?*p<-Z+phG(F1?ImRPSz@T*OWV%}>st)9#cM1qRD< zs!gD((@gAyI-3IzLZHziKK~mH#rY4+9g~h4n|y2bqwhUZrPwq=m><pd?if&VCS3<1 z=e`L@XA!HsPHHM9Usg+t_D7`BGv47B4V$}FzZ<V|=!zkQFAwuGIKr1F1DFTDqt}D4 z%hwVkFly(Nd6GGe>H!WF@yYmcF8|i5qQ>H&PbL|x?V4c66FV7qy?dBJvY##xb#2VS z?GO(5wR8qQPt$A9Mf)kvGe3z;njF`mCl)T|cG46{BfuYrr2!~-THKW&MR&XSMtE_w z<#-T+PdtXkwtCkyyTY?oRh1dQjtE5)xZD^gbb0PW6LfrhzN?qWq{Sk*96AY=XQhDd zNL3S1FD4@E)Z6tY-!r{srr79Z6NSl2P7F95p_fub5{x^)9e7$CuZ#lf0If=*&i&l5 zs-nucFa9MG{X#rWmt?G3_<Q<reliQ{aLSB(9h|F8AzB$q5P~msx_l-nXHw+fFq>0` zeeR9pxMpKhirWAu>shwsQ!NDtd6mU7`qFQY+^G1jyY>rLL~vQQTnNH|?#`wpsA^aU zHtd0?(O$T6`LTw&YmOnph@ra>>JHEY^KWJ`Q9$x|`*7drMqMdGc6N-L&pMHMZa@F8 zyJZ~DwZHq-iB<69A7iIB;~T?4Ba&p5AvV=ynt*8#5B<^M7SK!R{sVcayzzlNwdwu% zi+Srzv@}bJ_}K!`3x(plil}%v*z=@NPOBC_E%_Pk#ATs?HaiLvqCXk#9b3LkaHk=- z-R$Hyy!ucB0+kn$r<b;8<oUR<PZ@@0_Iz?{a<n@IA;xy!xhlaO8<&CKw1RuiPX=0| z1$(QnAT+JBZ4gZeHuy5nXs%B0W8}eU_Nw#_MjEX+j`^>WR!B3@y6V5O$YPPVuh4VN z#$IhU#%SVAi^KRzUt24nCLy6X7I?=&vEM6w{YEnAy7W=s1yJ}#(5@z%-s_RoYt^Dw zuJVZ1e3;s<mJc5<+FFvr&6?2BxQk$8q}aeip0y(GZG1gGu`k0HEQ<00PQzEYEzg(V zs<j@|2lwoXp>MR<L@Z=v{*j6Ovkb+hqR>$XqUaFZh5iba(g=$e#FrwC<N7*hVSl2N z!mVh#dvl@*$;)_{Z#tWd8_Q|1W7A29Dw7$M16KeUQw%N&fR4!lq6$=Lw2B?CYq()w z>&4LNE@`i-i7A3H{T%K(I{w^&%>Q|u$M~xr$o1e|;idCU9g<4*Gy%d*%C+Ct7_!d@ zX0bL)u71!g?wwVVRF8$T#N5X!HzVS@2%?^o8!E%9Z%TsB+rtpPa&%gR!<UaS`*@Hj z{y_u7e@nJT$<dLv)NQ4Uch^xh`ga(a5F{zVmv(Hp{ck`YNJfFLFzlahnUChqY8~h1 z4QF}ZOoRk$REsW+vxBL;Lo5?tXJS#6Ni94QViT`;6vfNovT~@?2($5K2|zJRdTUbb z21Y#7VO{;xMmAQi$X;BS87u@})BW7m{12TBuzc|L)IW9V8@-)&`?S;li4EP@V{Puu z&<&^pksU5B;J_85&0I+k^72@?PFTNW1_7^j>0K<`i=8F=XR2_Hi`E7AEAoJ|5xfIv z?dca>li!2n2FDpML&{8HVGL6g)c-W^&<p<sDR%Cse~HGVC+6{`gO38P8)87vYj|vm znqOVL#A&@;V>)jm0>d&1oNKxr$CzQZJO1FOTBmApTCgijINsb<FX6J%L*pRiC9cHb zfhG6jSN*#xMfWWG%2C;Dsa6y_#K$sA*{1vb7cS1D4Dfz^s!mDq_D_2=X041|JTQ&F zL^CQh>&=CO@L2sgh=)T#vz-n|<DOYNo#%7A^anjzbil^S^LczneA^5h*e{P7GX`6G z<WDz)Rc;ffGoR%@z%Z<a7vt>e!kJ<%7KQ^vJRHr$vUU$IK=&55KF57{Wc|cl9OehW zAJC$1y!;N&<DA<str1}3f=sQ>)tdh6i?S)Z)3YE`M_&DMl#T0G?Ab~5F@@F5zFc?3 zIuO6#T=tw6@biHO#75^PDw+M9tIuqUFNLeHnX7)xxp-9HrpzJZZ%P2Q68CvOH@VYm z^8aZ8g3a>$k*u0K=%+re#Ie>n0EQ+tlu@PVcpAn?iHK>Ot}iBg*oZm}`pb6Dnh;H$ zqlB20b)8eUCGh!GSi>oGn>X(HHZdQ3;Qe{!^98q|0v}2{W#1HxY4KWofWx>RZsxD9 z5Q&?O;7DVFFKuu#4-3rAmP8&4UV=7;Zl|hztqJ}qm6`ZWHn~Vyr5&VC#1UdAm9Y+D zhEThnf`D~Z?)sL4ILorw`VKcZ9CdSvF9tO^9+A(9J#uV9#-Q(AsXZ-smmZLUfA)Jc zp(y<L`VuDG-O@?K(Sd0sp~T0$ZOZGETVnZ5-+{)b^~nN+wr)|=*t>|IL1)E~dnw5k zu{qng?ZS_t!Tm5LQ4S-vFU3Qhe>3T*_v&hE+qsFq^$^}m&;5%GVsObBpL&>kxx*_? zZe_%NrKa}BFJ~Gi2QeN9H&p4%Q6O@;u|{@;|C0u@G~M7wANK?oRKQP{XBoJ<6`Jb` zxBzeeQ-36OB|2JP>euwQkltFUJzXQoN$A(<`->8TqgT}{e`7IhL@JAj9<GTP)p}?Y zsLEh7rhoWMqk7>R4yXEs&7(o{6m4Bkn+CF2*ruqS@{_nYGrhZUVn<B=VrLnA4m#L5 zUsZ1Tusqj8TC^Z40m=Pr#Db%`sRp3Bl9etxp>Cx(crDFZc?-W&B89%g2=Hy9!W+D$ zuD}DeK6z;Ym+J%`kq}rfar@G(RHgQqQM?;y{KYKnd3bp6F!-?0%x3oN5H9Bx5mZ&3 z0FFC=PJ5L(*8d|%itR`R-kT_@`e$xz+ZI9`HI5*=OfDNUgCEus61>0ZhXjEJ7qD0j zs-9jZyq5P)$^s4FQ|=Bbu4WQAz&dAYbywe3E6`jJJGyXe4xKIz0*4W%ki{R*n!*7o zS%D;Z->~5RjtHiU8z;*y9%zZ6O+7=+w|&0aNAqB`)S=RGEC^e%Y?^?uY%7ubWVK&+ z3m*gHeTv;uKXkNFv&Z=eP5+{-Z<X|Pw=1VG7ypsBhSkCbGb!@>!7P653kmDUW1HQ= z=#_%8>PNa==Q{t^$_-A*JiD<5tHOuAd55fqNq!N~p~|h@@K3@`<sS-d0Q3%l7%cM3 zV+*VRlE_xK`{D*Zie2OC^z8fc@E$~cA?`sxj#Jr(ss3i2NV_s}pRzy&OTr3|+JqGV zw+p`ufwp-pb)L13^)Z+uM3aO7K-5Z63E{sC8xyM}1h>M>x2i(_Gn~9;<A$Sodsy$K z@6lzgw!=-ViukoXR111;$u;yfr@~kjc=D>2CNk6NU5{3BI7I0peR#<J0VV8izm!pg zMRPB=zT{yC_J_wBt#9L*r<iPSMXYMJeY#z#^2<1$Zq8zVFt>UyXt+4pnE%*A>?Ti~ zrCxwULB?9XxoUYtrG&q0CuRQ+&v(`>SGm1+0A^K2%G)j+j8`C!`MgQ%+Lb7rlmFQb zwfHL<fNDxBP+D|{KKz~=N8f%A1&z-vJk&$Y|9ku7+e!^j{*(9|C@^|H-wyp)H*HSO zW_@2!U$PGC&+5Wve5|G~KCarKw^wuJg!7QgiyHpu!@DQT>v9vhT#xP;4#?#mQOOs! z53iSm^SD0n(GUM2?O1O|_am&IeIxnS<t2PnU*zZns8l7AA|^Xy1_UZ|i;}I1_8-19 zT+R?F)jn32c)nCeP6EBKI(=TN{oZs#KD6-pX7{PlkDm9?pL0|5usit548#)2(`(sv z5a`~CX|D$-JwxVdL&^_;?n-CEL<8Xfhs4>WHni${28kweGOlxZZCzc?#$WD#Ii7yx zPZ*dZ-icIYIO!roHKy?t<TdN?Xs5V#H;KXm=hahgEB(IF%sag+2gV>eu|IS`GxKbR zvm7K1QVVpLq4&kr%O2BsAEp5wO~3<7b}jyVg|g6<>>XT_vbLx_q%r^!>@N}<JIlFm zJV&iZJa<i)$30CXl^vh)mTs=YLJcb@+&qT)0rk^V*(+1Y%Fd~VmL;-aZ>3}XdIg<) zj|ULjj+pJpYNk(9R9R)FcY+atE+l7lQ$byqrc#(%TEsvX09!tj)ONYfU~TQv)?jsC zU%%p1<oPipBZHQO>ED;h76;?qmET7gf(+zv8UKK<F)4JT2@eA&ctY7trMM9Aw$xLa zOXj=TDP?)^0LEafxeCyrUyHC+XL$!AsJ3&`nIryAFm3rOHv3he+*Zm!V_{Y~TxP?Z zIc_#SSa!2Ds>g!EQs{m|?C@-0NE`Fg*2@KlM>>hvryRQ;BysIxyDc;}*G*i`9~L|u z{vsIS(TCrl19fHr-^WZffQ<w#j7fsSUleh>QA$|`u!W2Z)?Xbza3~W_uMTKgL=8&V z=QkPxPu}~5t+udS>1eKDPC_Vrw=~7ZYD!cy*3`lx*P((d@;`3hkV-Og>EX|pu(dT$ z`-+P2;lxFJJN}vti|;sVx?EP9F`gSDylx|(he8qZ!?F_hVMBunEa5acbN<;WLOR%b z{<(19WTCyzDmA5(dssIv2@;!l$zj9UFHCY3oSyq~7IvdEq`tVi@Z`FQKBSB+<Fga_ z3Y{_H5}NhLdpYY0oV>+MA3mnMoZGmg!^cWP%auI0Gb($joox(NBrvmoq3;kA;?Np# zB~N=!jd4MW-<MD20Iouq{$bne`#x-i20$7TBNdz#g0H}h2eb#=Cg5ScS*(L-4);t| z>;Z5KtYJRz3|d7KiiSA$17Rq9@-+JZ1>5V5e5|ERhiCGe)1#7&=cKajmRakroqUI` zJRwglE-fLTLi`TlV+(d^b7y9v`h?*i<*RE~TVJ3m#zYv7?D&}HM3pt{*xlG49$X2N zT^`z0u@pXQqb9zJ9cWO(0H=2T*1=4dFJ;PH?2DG!8Y)SbS*5yct@2O?>=z;Qk103L z5VN0R=OLHMjO{-;Ge!w>B_{Ph5u`c_zFITmu?`8{C39IXu$1(_Tm_FI*CJEc8tNc0 zX*D%00b0a<n47FO>I5rxJNA>FeI_(Bg)(%GET8Lt6lb@zXkjb-TNM}+!L4{ab$%OQ zv|KO|yOd$Qv^nM*n8D7;4H!5cUcCcnOfmnqL~XliWoW*ZJM^h5cyb~I5?zsFj!7AT zA(z+YcQ;JZUWCAdukd~W1_EMu58DRq2aSXvO-V;I9b2BAuZC1bH?`|4beww6C5`tV zGX!qlO>f5O3noI!bI62Xb45%%*ci1MtAeFcP%D5s1-Qpil6D^-P*EN?$#-K{@T6oA zCj3atB;E*+Cc@x_^6|-Y9v59_!Jp&m2N=AbpQgJI%uVJYk(03^TJv42Iyx(RNerq= zt=OpAnMDuhIUF7BsVcv^O(yXaI=B9pq!fb_lrJJ4H|ZZH&TiOL+B-L&NYi?LO_8xZ z+*CgLGev4B{_gM8Ah#Rc5f*Tp!fn3EGwR_iL^R$%403`nk7@v-8e_dBVOWY$jXxid z9v1cmD{RUPFtsR2LcQA;dK`L*Elgb*?f2k<L!NM%R^Y3Ej??S?dIo_SM`6+JPo1aK zVa{S^#2>YhH0RC_EtgSr0>7MfL=EvG&?YhTzk#!Q5SnI~I^rN_>ed=<!2&8p=+MWF zj)5*218+y2KymmfQ)@V}(b*WU<EOa-gWfiT4F@Su{}n~3q~C3p@~rqw%c^=0?<m12 zxuNP?vk%7yep|^^i_6Q`xesGKTbh*rQH%ZY%%8qT!Fc1xi8grcd(x+`cCb?>?Zb&0 zvmksz+-G-mVc&$x%$&U()*0-sX_9y;sV*Ni=slt7|40S&Y*B(wk-^PwPZ4nlPFkW= zcd+XGT!lCqs%~6>l8ii1UXaKp&f>xy*=za4N#-9kR@0Qr{rXWapE+-xMj$#V2^VAt z2y1&+HJchVg;naK0Gys<lQ-qo!G$H+doaDi;dyxR(+-d+9G#d7LqjBtFQ#-#52His zGpp0(_{+CDQO~W)a%8c2T>!E6u^_`SQ~BR?@X41hK$mb{{h@O|2}}9V)NaTkd?>72 zW0wHR!`lbYBT-I#fDIm4vSLp^W#6+1D)X$4ShX+86NzF`#U$^-&;Y~xb?=wlJ<V{Q z5huGuTAnVhHCzt^4%gim!)AY;mv7s=8H!>VX%Cak<*ZhdG-qYMt<~!b6l15P2|0Sq zH^9~YQ&Oq=Z1Ve{@(X-S7lud@`evAPgPUds)p(cfW~APd=RCZ#3otdk69LI?vor#c zO0?G=^t%e#Yul~wvHBCcBM|?<wZGxqh*Xh7T?CJEyb@<m#919ErH@{e?Y61m_Ws6Q zmpW1p24q95j!qn#NG9ddy<t*5@mva)XK}-1WIq&f>yept0r85a=ZrM5R$4~@4^);% z1L4y^-St2NA>nb^si6}8fAl~>BBqam_I@9Tjs3cI!$~7>FWJZLHfK6(@iS|f4k2mB zOyBXFGWf7*`v@+R!w-=AM_xDJXJqH69$m=AE+3ZS?QfHlnQO%zG<IiYG|~!AF8-Aa zZKnV2TM<c1yKF^6dlwYp?EV}qE0>kX^jIy~&jJGU-Uqxo5p*lAd~D?2>Y3?Cpu}V0 zK-nOR{x`g!tiCv-zyPmfpf}1K!sLVz5-e-<$VbJUBmm>EI7xmsE};{4o8FenNU>#H z#awS{>j(w2c~RhS%1(YoPw|6sUEU$J#!r8|xCLVVVcZ^>@S$hy`2jK8NG~L!2R`V` z)z@~Da;Z0ODKnEukv5?P46ygW+NzRvu`I-NTo-&fD-G1GL#TSs`aw;0LkXE2g_U>h zs}j=CjsFG~=7%pjN<8%b&h?z@p-9>tK>}59NfjEgqx5$!Y%<QE!)tP~9~2m{rltCQ zz2qq=m1C6@lrdfrt6l-GGC_}FD9)Qo$LKL4xK#0U`{>(KW<rYY3un)(^S;OUSRZw1 zqLl|Yb5!dP3^54y6^g#UQa>tQ)@NPXZ7c0oz^bQx)yYN`5;c@I(i8fyv!JEGd(vu; zVGUVTW;{4F6tE^)i+zCb<XdxeoAiKUuKFsv%t=DVba>v^aZpOs1laT&aPq&B<#4d; za3W=FIu#Q6O(=Q2A$%u-6}B<1yZ%=OXDvBCM}clX^_~!;g`dCPNUb0Y=nVpEisC_v zIo^;3#DLknIlN7grpwF)i#mEL|MyKSyKkBDaCs9INUh<N&h}k(+ea)aCG6`zmx;@V z_s<sfdb?{&`r;jwl#T{D6~U5SXo8-LZkwMaa%*zuZGx*(Sslf0C>7HLypD4WKZ+P2 z#dOUEsd2|w2r|HRbCV;T4@Dhqo#`?~Y?nZh5%I)#ANg`i`i9;pg>Kf2*eXJ(1)o!u z&VriEp8x=#e_oDMIQ8etW^V@Fx5rJk25Ti9S<0{J7+3f|EtpF?B*)p|lkeA4R`a(l zSpN!rU~dbwSA-x4UM?un9Otpigy!wtW5>Xs3Vx3)RYAU5<KHdQuMQ!-w6dIgC&P?Z zsWtHq+r~giD|T;xUtpFyp#=M%@+HQMgz=y-=GzXPotNVjGtXk$V1VFd$*;c;QN!Sh z9|YJ|@a-KNh9HJ!WOLH**aF|NQHPQUJK7q-bZvG$RF)cek*st|(tzlzeSB&vkZ#3R zGg<OlX^`zt9NDAiF^+dc=|gf9i;&VDHg`IU<BP!HDZcI0=yt<(N!;A@1afC*D+UBF z;+~vaSMRb^P1XAE&ZiXJN3_e^c%%?r8(xcKa=2x0^kzVHRp$k7JMy`2V<1hti;j^i zl7%5DIN<_u2sskf8;ROc_&%j(2kV^yx3Z^nodFITx()ZGY9<FeQ{~G$9{y7@vTC$p z&gO@&^*Zj0?m*=lbgu_n6dx9;G2An<)*Ce&hE=Cto>N{fhpql^Toq`82~2|3HqIN$ zm70&k*U92p1T%14sErea*`!z>bpRQQOtPp^(T^mxrAiGSB(^tTfnSo^km(YE6)@0^ zabD-Cy{^NKLoG;(3TAJpLciZ<Q%PLxYL;#bZeBX`C;3NJure6%OFb#}Q54mKK<gDO zgSiUbP;3UAeKNSsfvF1plpn|HBN4gZtb=s;6`r$>F6+ocl}s;*@ogV%vfkBl?85?S zCT96Caf6z(8SAud>y5Ju`y*Bwa=-<{)vJ@(%W!QFgo9N0Z|9YrXRpDt;f6z!^&9mP zu!x-ddp~Q~k7joy)JTU$sP)eec;U!|!s8cy+Lx){NrXh;{W0bUs1)&BR+h+Bb&Tp? zy#6hBW4f^4{Bq<wi6|t901OUWrT#td$s`|^U*78&)*0B1v03k;SnNjbTaZ6zKI#4H ztXMx{5b?Z;8r#BVQb(9wJkhaK=5w~(W)P`n!0EYJyQ+474(YG878KD)tmK$3=Sk5! z9Op}~cM5(dHUQ)Ik!RzlA=zf!8IQ*@VpuFo7`l@f>dUp!Cc=;%L1y1bJ}TN`(r8!Z z%bBCK>hf4M)4X(bwyIz>F%!{;dAcFsy5<nAH(1v$=QEe`IQS|Dz#yrP73f+{x$N$0 z*%CPNmfFmq9&Mxt&}>AeG2w4-_{d`!T<bT>-~FtUxeQphGtV(elV0}1iqhu<;KpdB zc5`b{4)197iNS--^(Gl>+QWKFh1EU#BA`-VyIzc>GVSj)hL7Cu0w$m9(zQAe1Iow? zS|}FPh~&;GU>gD!L0vnImM%MpLC&==W$2IBH$zr!eQ_MG$@xZ&pgZ99hz_O}Gk#4Q z_urAzSrb3yt3v21H<b>612%HlQ)$do?>BfNu3<X|!*jd-tV$JAQS|0ZU9iRbz$p$Q zv09FM>~BkJ<YWjFkZL{->L-?NAvZrQPr)JEO*6Xl?OQ8-2@j=N1ys978#hej_6{FX zdiL}hqv%uBrUt&9!QW>Q-+X}$>-wra3&GyL^VBdK;366AQ;QW<OX{j|vL!lc_QYs) zUskTbNzKJl)=p%)(47--r>NvRH{D8ESm(NZ+NyJ{?5$6sf`}P%ykU{@s84!vdtBpN zYW9HB`=ZKaM3pA_$TP932kb0QuuU@i&;J!QvRdAXitq0B3Jd^MVSt+4toT-Tw|R6A zkI-9O?KZb)4*@V$o8tseLuTEED;xBp6Y_i*-!nE1TN*r^%pz`Ce-R+Rk;^Obk9)?> zik)CG{Z!&ZOv~jEra$iZ{Di+&X)G;NUH?OhKR8UR)1wSNE8yHEm1aV{Cqu=$7jw5# zUz<>2E83p4koq!BNblFXthQSLr+M+nD;G>J9|sTqVIk4H^@m#)%(IUiiM<Mx`499+ z_^V}CUTI0AJ)BId{=6&o0lB5SHFK6s7p!H;IIZjD77a!NOJv|MrSvI}@n{=MfX!G( z(cPn3p4(vi6@q_q+F_;AoJw&y*dVlXC~(Bfv!L>L_&Qxz$5C5fPsj2<xWgwNiXi~h zdp3dw+-xL>fudXO+8P7zg~}`ucH^A&T%UJ@X9Ql<R~`zki*D*DqvUkb?hU`5J0y6M zlTB%9N=nmx3>YKi91mCpchNrhrC9WTDDCJWgI^$_xUi?qBi3)HHq)v#Gd)rj7DdfL zgOkQwV-RWO!CA?yHz&=!o3r48LYcZp%?hdQX-?(fz9SA8^v5}}u_fc4G+QGDAwc_X z5C_lyDKj=}{qBv^RY&3nHaCn3+gS83C+`~$FXZkP59{r(8t&<zg`8f0kG-TZf55U% ze0AC$0PI8Ox8D*K&Bc>Be_`I{2lrbB>m~Qji}f`EOg&(3Gj?{Vd*GM^siFw{a#<xj z62Ner(yFZv{jU`6kEc0SXMY;OR}cdHNCd&dtXjk|er|3P3UeAot{Q`XzL3GeDB6xD z3b)>!v;BjL$Nx_8$irHzexjk=KX?f3XUC#LW;Lr}1=RL;7u$utShOhWZ$+`*)Bf%B zEa!L^aumi?w520*s64tG`j&s&U_@*Sgm9+jmaV08T=)ku%We7mt`n2Gy0G+Zpsi(f zfFN1W#f|^{TZ>K`>-SR77sfBqqAC(>tv8F*a8@G&-+wQxeI|<#a2229in2$yHWmt& z=<BW|S*bQ=Icam|ZFPRe0xp?fEmTX5QV(k>I(RkGd3Nb<4Cp8e1XAwPSiKEMJvCHL z_dKw~$W6cD!TMv${j<&RupI5Ae`D#o52NQ{OWNG@eE9I!-QjOsp&Y+nrjN%?Cue2? zZ|XSs0pAR;SjAv|ybDF1t1CkTI!lIp<_l)N-?y@LbcbKzk=1C(q;Sk_uP`vMs7L^x zPk)jC7z+qJbs+S%RBN`9m(z{S#0>Eq?5d|?#pE|iu`9cL@2%K7ZQkTm!tO4L?`m+M z2#QjXAd$mBo=yPcG+`hD9&s?i(%CYmR0N9;^%J+1EhG5hCByYFWhf<pi4`|)mR%sJ z>w}K3+<glk-M%rip)JTf8wTje-aVIc!j&_S77VkuqQ~@N?asuy*%H?WwhH$Cg3taF z`j0`VBPt_OL9@=MYiP%RO6SR#fOts#<Bs_g!z1*0cr1*IE6dfmJ=CbB`SyT8K#Frj z$00m{Fw{du)R5}7&8=;SZ-xk<f7&#g5|-_zEcWq-nF93CY4>&_Y+ajlJG?u|{v&&N zuKK9GUXCp;q=<WSTYxCkQKzBO^Fp;QdvB)qH4*$H%U^AT*hRbxGSAn)Fk*6cGQ_F3 zxVE$rbZ;Yej{(3@SI>`hb!vgD+}k*o`24ZRi&zANAS!B3*4nf$TD&nyddhU@h-*S1 z6B~_QX_vHK1TutYSdp0aIEn+$7pK1U%F4yT+y`DyIsQN<yvskmq1q68oQ<KUJo3d& zPM&JmB<irHrxik?qiru0o39!Qi(J&T!NKgha0dvJJv%Py=Wo#yPB@kt01YB^-*Lrr zo(B8cX*>Ysl6~i%-~Zm9WC#Hj+IsO@vzVA;6@p)_Uj;Z3TX0RwvFd;DoR(_Hh#HH$ z;y-F%Vs-{Sde{P%`MLQC<o1h`IZhvBF=y^yFHT<(p~!@SQtV&804ctab1&sT<WOwi z1xyGr&!&!lWKX6o3zqd&7dRjD{6Q@B@eSR~Th((NxUPNU?uBWur-N$^w^ygdDv#q> z=8%pJRRN%{N^6xnT;=inLBR7I(XfasULf)pfB0cq-qbaQ8?ND7tWxJ5F-`K9r!pnH zwlIP#q_U+DE8_GZ1i>mo?5sb&jHp{?B*<!WdK+<6w|m#rL10%Scx-tBX60xb|F6mf zvysW02C6LVLI0@Ef*zZk&P7EDJ;7g<OgTl;8XfjEm)zIYkM8eMnm2qm=cd&nrZxqn zM|O|(uQl5{2ULwy4mA2j-Op6Lxd}Ei5u8;8=7u~fm)_JW^*wV$Fo_u!a6)>Dqr2V6 z;qGp}q|MJy5bXHkn)r)6sw$#o^<Q9H`5GNDC=S4QtCt663EXA3+-=BUysQkkr_1Tj zKMy?ITE<4fCJ!HO6LU^@SmmIlr>@$(R{kN3&1z~>xP4h6b|#^lMX*Ja@3pc(aYpV1 z^K&veSl!&@KOAzeToYdMQbb7+XQ~JUMLfGXt^RzS+pu#I94dQC-a0(D*uO2v8Y51c z=UUx_d}I?zG!hHKBE}$2!XyrpMX;DD>!6F&;Wy|SX*zWq=J32aG=MW{={78}vl0G& z)D>K?qTGDdXTl;fXV?FLuO?a`T~;LnLKD0x^LnT}>3TeU`F!>y(*t6cw^x0(5G3j_ z*)EY%e5D|Z<7$0}`C-sXcH*Q=b=<G1a(VdXhE}r(XS6w|A^50%u7#ZcVyuluMe7=~ z={APC3m9@2tk(li9C4ce@qt<<GN9T{o6qU_(*Z{$2((yo_hcb)w!@Y*MZFn#U_!=L zlpCzoQJLulQ`vT&brebb+DyRt`)QJ<*NI+Uk*v4)fSQc;?eRh~xCywg#iEqHyGZ#3 zuM_8=l+wr0nO}%v(DR%7VBKi&c}=3NcANMf@65BDPkH3=xQt6I-*GHWUiedt*$2q1 z(sSJpHBC_aX{J50fa?IFAzmrLmZ0D|I+`r>K|0^p=LOt5CPz^$`)_Gs*oO1O@d_>4 z#kX0+(T}Hi8SjqluXP>ZL1%~iCi42^tPMF=2Y9^wW<U;VdV(mSwi|}_4ic(0aG%no ze7i6!qbZ77=QCK792+p!e1Cq5j0Q~dvf$VrXnc{89>q+FpUqa|dWq^E)>ZB@VbYAF zAp1+X`=c*Un!K4qpH(DQGgvjmBz;Sh;w?_62nX6|mk9A(2xnF!UvXiY;w3;``_=N9 zAiRMtq}e@QYuvBIMcp7aT%VInX)GngIbiaJ_B%#rQ7P54@iTn=F5O+8hJa*4w_JWV z%uT&EAjlV2e?+w1KTc2rN!r(SwM9K`b4Qv}FE70zI9cU7jdi|Nq-G$SBDo^zUA{`q zqMujqvBECz3SxAlG*dn*%<w<C^&Zo;u&@xZu^D4}K2?+dyR5PCzr)_&H;+$0gtz=T zXG^ZIy!`>70X8SJzI^H<5AFZk>b%JU^-mFb3o-@FH@(~dobK!!Tgy<%^yLgkCecX_ zUj50#YGos+A-bizP-NRm9j&-4nz_cZv>MU0(v+f=F#@)p0@bL$FaYfjCjN0D=CLlP zH^J{YDpLD6E7X%M2TK=gb7!;IrJrOjLxQXEXyPXMWd{R$4YkotOE)52EW2kbR)^nu z9q%XBR}F{?{~nH(C!?6_<<rR3(Rpd_v2g9Hi1V3|#_6giz~33LRBjHOoCSop@i)hM z;}$r)g$Xn55nhm|)<mj*teCf2^@ITG#agw;R!AoJKP|um3(z!wFJV^dlC*CJ!AI#5 zad15aybw8nyE!)|Tr%#lrM6LA)R49j8b_EihEa*L*Ku3H_ZAT7NY)?+v#I@B=2cBM zMK2F9pgnxvDnwhj920!~9krYVF<>QPTW>XpeQ6nx7tI_#d@JioI7PKUE<bTv|2n&X zIxx1pTIc~eMdOW*8Gu>xi?dtgP)C3Hf5|39k(~ISRP)(NlnwvVRff7E_OuvMmLC?s zKgLQYNOkZ2r2f#dzkAtd#4&n%r_((gZ3ISVK;o5=i5d!x5-afgVllIZ*;koaeM#!F zdYNo>w>KL$%X{1O_=%f+(%}6jxRcq3jc?rV(PnAD^{*rNFwljSjd1fb>o&QuU`mJU zox=0EkRI9Qx<qF6>&rFqdP&<WFo!A3AnMZ~@faK;kk)TlM|D*}C~)D-E2`CiPDiT- z(2tD_=;pzz=JNqZ4IDl(&PDg_Re$?1E8p`l(Us<lO5m=xbX32jb`8{blH{CeDD7t- zn8+<;;x^Nhy@JaHvk9smDlM=XQ8?{0P<uic8drgPqE<tnuKle$5y*t$T2BK_wvSP- z7zU$><!!Hr54eC)@OZUvKa|0ZT56cz#SmmtsS%!mk5ye$gDZ>SGPNb)bj;erid4$+ z3*&W~jcH?6;34Y91?|Z*{oHhp=J)`^70@#NhR8pxjTikh^TG9%(&F8au46U~E;3_< zmE2eA;Sj3qSOQL|+W>6sb_MW5c0Qu!b<}s?ldV_n$J>Sw_%7-3jHA_Cp%XO9J$W7J zaV6ghNol~g7{n@6!aFkrss*Iu35EKGd+)GVq7xoPd9(y$J}b(OV^u1&6{*9mJy~y7 zsiu<p`N6$gy7_}}RP%Z#vUJ`)He@B7nQd{91sDnYu+L4;*rh%Maz@g3XB`n4d3azN z7M<Z@MJLP8h4%Z%U=&Et`@cLdw%!=<-nK1k(XY^UNaIyR4Tk1=H{Q;+n~6BsO^I1l zd77e*uyR48d;6IY@K+6nw=q+8&T~m?_-)GqMYY;K$p2RTRM=K3_}ccmyz(%+3YWS1 zb7{$g*DL?U)Cw3(v0NX;2`|r?gJ0#Yhqm&^4$=AL^=R26onTjM_wlsSU3^9}4|my^ zLM@S<T+QV(X`NAu5P{{qayyGhyR)Qsx)ug3=|HB|JJKU`Rg$W1n43S*hH5AD>*&<! zHEG)f8{Hueq<82+DjQ8A^z(^^%cq=&lh?eEzdw}}oNgt_-6*byJy)29*rv3Wr>3-& z#x51T4sVyLz9H>gC6^K92+jOW7|r59ITo~aTeMZ#D31U8b>h=LIpo>D?X_l1)XJfY zJF_{W!0-Lq@5q)gcqM7s3@@#RK9{oD2PcP-ZPxk^!y~<)%ntN&W>wlwe_tX|)uFBu zaoa2MI-gv{BvNMc-c%kwCE{<N0{`w*-hQ1ygM}W4c{9Rjk%$XnHzdPRFtr8l^9tS@ z%<i9P1eWvd7wM~ibU^C!P#=4MS^MpjO-GvEoMY|0F<qkfMrzT8@Urb?!}xhnM8k1o zEySG0CmPjTWx4I!R7j4CPQ4_t*C{+*$yv~|GT6?im<nCK9mfe#@vjKIf&Z^pZI}Jy zTX4_o!#?2%+8Zhnd`hLR#)J}gMkl!mFPHKuE&L>Zc}J}isUq3sZ(b^lXzQZAeK^<= zBC0Mm%+^0F;l#dihEr}=5PHbp@e@NNZ*ArmHTjcn;Di>BR&&Be@fIEp-ID~)7T&tg zqR~%1br8vf>SLPI#HVE`$ko^t4_4Eb^D;s(h$=(0pI)o`Tpk~yo(-H?<N%*yAnpuk z%|5cl&%;KeI194K6Q-d}XKaZg*XW_<x-<RqfP}*HCG%;e#boT|`4Mf{RLLyK`(&=I z;!?x<3T0nafD~pKNkj16UY(1H1O19FEcA^d3(JS`w~QAgpVgUG9gfMKS3EdXJ$<X~ zi3)I-zYBvJmVPkNZSLS(lqed9&>uLt69tAv4MRVV9fMzDj$Z_c=S!j>n_>&pAcMbc zMank!SBsTXuXa<>DHp}@lxV+}1_!7{!LSA-hgF4{*NBS4b4dv6`Q#D`X1z?{nZqE3 zt&GqeT{vdazE+g!1^)NUG`wbaQ!e!ND=Tz^gC`SjDJN1Is^;^g`9lge-Yonv>YrJ2 zPc2EL(A$W2pJ1X}Ktm&!8cI~)pH3oLUax<e7Np~MEyFYB4A}k|aIXbgyQn>l$*a_O z)m!#_-W%ysuWMjxx*{<j+XUOEm<-<pp<rG#+`%8S)D0mOY$a(Ya_;v}{Co(B;@`+} zf7sp$Dj5FpX6?e`u%r=sn`!Y!H@ojbjkLxqxik}Mo){ls(px1IA7M0ZwmYf?-aA|0 z(PD>LW`St!)-UZLbQ#?Hzj0);d?v|W99@?C=W+X>!)UFMnZ4U(%vdb6dAX3AnVM2- zso@I2MTO(0CidajV-Cs|0)snf#T+j&O2pQv7Bcw>mik%WI}Mn#HbxTgmyZejUKVtH zb#S-dC0#K9VXw5kgFZm7=Gq>$%kd8C`L^PNgfIMl--l3HFt#AAc{U;ZT95?)&gILp zn7EzCx;@%~YdsKLt{nWk9sZr=oOirLaTo=>vk>smzI^C7EflqV+xP3{ua<H7<1$LX zowu_!MUDu+SWEvAPSkHZea~NoO3K!=#9lj#FH?}$yvaC|9J3m=M;J|T>5klN+w+Ou za)YtZP|_8)N6nxZM@5->!(@(EWqkhGU04v(V)3sqj=dK5znp*6^Sz~sgkG1r7N6<_ zy%gQI9i0idoO)eAjHPlSHCLrB6;ppKj5W|1iI@~P`;IG;`pP=XhzwXdacaD+U-+0> zYo`@5`Q{xxUc5@*H<c&y&z|BA&3b-L#66sK0uM#hu>c8W=Km7P(mF-9j1V@>$MLt? zBQ$yE!SY?V_wIAk#U?ASUh36(t3T?=nBjEo-Q8wcUQ3zyD$)3!awh%ya=oOJ7j7-5 z8J`IrGYh;F=Wu&|B2S6KCbgZ8e^WY3Uv%uUKW%i55pW#)!qLKuhz<K;9kd|qtk3!V zpyG8GN#kks^<4Fj+$buMQvGXhHJmN?B28PnfGJV;x&7d3L|4tVg<!2XXBi;{1TH-1 znai`RLhyc=?ZrXIU3<_E$}wogc&ejL_L;%AGxu@3`L(^lEG?~MT1IR@p*VevC-e76 zE_Lu@y0X-WGI(rJd1R^$YV5O8W&N#Y_eyo-AeOo(;LH55O}G$?8-akcdfOTG>Y1SH zQBTa{h}dFUpcU(awwZ;`z$`fG@2oZ7$zm-rp!4^b52OaN_>qQAp@y}pts1^A{$YD* z(_w!3;?v*apA3GAZbB}3eNj6u;oFBTibLVohdgcD;=G9z|G!86|8ltN7dU$Sb$_Y9 z%4#`dEr-`oqb^vwQtR)epyZ>A(xj|K&vwD{HRI=98*7#4al0=WOZ|nvZFm}{$c7Im zB8%QVhWd2~;h(^SS~cx&nRm5wWge(f$sPYSIaRCFsBB|B3`v#(i(3=2%16UmRlD^G z+)+o}2em$A*e?!8iEKZ5cfZ@q@#?LY>r=#ANKhWC<w{XaTPY6$oBLI0uti5iru5=* zNi4=pXAE<&O~n`#UJWo=pSyUysAX_pNjnkjp<rwEJ`X4hdk<QXU-6qkyw4}ZWypiv zFJ6pN1A)J{H)#u(GggoBFN`ga<%EaKX+P+7;1Q0qegRY_WP7?@soe5Z-~kE7+m5I9 z|D)==!{Kbc_eqmPkVry85Q&ng5iPnzMD*TP@4fd`(+Gk@@1n=DE6OUX6NJ@Si`7|e zbyi#D_sIKs-*0~N57))@%*;76=RWs2b7t5P4eQal;N1@Y(<WsJSg*sRo<o$LLw;C$ z0Ncf#JIX{XMg(ZBK_u6RxZaegINB_9vfMi_;4owucop%=nCW$`ntLzv!F4bwrh+=o zea=}sKr&NP1u*r8VhqF+{d{L;XSIOcnM6#T(#id2bu`I;Zr|n7Ok6SSFW(;s0U%_* z!66N+{@J_a9?7$J9ULO{lzDq(>65N~XA4amOM(sf(t!`GLw9DwDP}<}vT?`r^6DQ( zX1}mIF!hQ1fBvSlQ2yg50cJ<NJn3s_RVS7f#*Oa?&MJr&O{JLLhOaxeYBU@!9H&qD z{+8H_pw_&$tfkcK98KjgDWLnKQ&+jn174DL9jUOk(a$<rD<@IwGSXv6byX6M{|$-& zuRxNJP?k?SeHmcmva@AvL0lR4Ds3j&{mio^&ZC65QO#dG8ph-0-4X49L$zt`ns8FG z_R#S#GkF2Hx)*m6l%al)%|VA(hV+VW(KvIWf=9LOa};xN+{B1CQzt$%@ls2Ty?y?p zob=AP#NDOazQ@55V5XG&4msf_po&(A7W~Sy63nJwFllj!fKWPdb_tQjomn!%w|&D( z9f_l0MyQcUyTY)a(vs_mjoDpy+uCG7MfJLJkCY5iA2plg&aN=RPKKUXyLCWsBAo1! zd&-rvzwls^#IJ3ZjOE-U-M$E5g60hvNFWkRx1rmh({PrKlTv+$=-Pg0Xb|?whlnME zPvh~o+En_VSC?{*_DDlcxEl^?0|<J0_|B#nG7`^MQeG7o>s>5@+X_o<9>3dLlH$|i zXCv=nv!5DmL)bbaPLJ2nO9+0qqJp>ItfFM&Iyq+UP&n&i_B2A7XO7=9^;UGh4xK#d z4>_KTs?&(PAGSAwT$>nu-%swKejtumDz`3+eT|G~rLyx^#|uhSDS1tZnxkBtnA<KI zU)u6n=C~C5X=Z1womp((Phh9hN%SboecRn53>;;pX_MG#NMnFiBwCviN7AynydfSp zt%>|_&_BHuMm`}VDpLui8S*Ml&(@SbQh;c>zKW}LQVkWXy^4%-kXM7QZVYsqWmWcP z7IeR_E>J6es%j0Mz&B=d6Y9=3i|9vcMXvuU#Pi$QyjX8huxgyQY3PMRD|KMQ=v?0h z-?vWHHagnmdpZ*aaM5g<qoWQB$AEUG?-*N1+Odz3-xhNqGbG2i;;GNorSz$tTYYqj zgA#ka@{;?rP{P_&(tn`QX8c{Vz%l7<y6xe(xc`Z^V}*@anlv-?_?eX_EaqZjV-6L> z7P;N`YJ86DuA;eX%&7%3;H>ku?{19|Cd<n6f$a-7%4W(4b@ECYHG%Y>mz{l%$hIo( zD@%?2obcT9TE6XMm|NqdYa5Z`?jt3}R@B%k(P-f`F7<mdd*!VqO9HNr!T*=U-cmTW zD$_cp_0F7ijEh6{q*lvCRjcQ!0={2LJy(j?b+T&&$n}O<yV-VfP3kI#u%UM`#6e}1 zj95G^)!lCUC*PI_{3-1BdXIMmPEhLHg|+v1$ya<z#MnOir?h>7wuKXo`QBK*9^w3> zQG2w4HWKgdu_BYu)vw4-Qf`8>hk~9Lmg<E{RgZ4vBh2YKMM|-+UADxZ#QCb#eGgJ5 ziOKPg*X?IY&@FKmeUlfGF^)T%1B^+7zZvfL;?vv6R|q1Oml(RWtH}_~a_iUXXy0M( zfi<*2E=EBAK4{uc;U=4p@;p%d&rT)vbtN~U;)tD9xw9)auOOPqMpyb@Bj<J|O+Dvx zZOO3KBk+McbNl>XTj`a|Loyu5z1|!(?JjnV6x4H4wtB%>Tv{p#u|ICSrC>~nj1e&u zFmkcbv$Gy})zGgnRzj!>#BUiK)wEZv)aQG>A!M|zR84{*z84UZzPpTUsBShJ@zEir zlO9E+NADW&dZCqE^&wU3&lX0Ix{F`*{a^1YtS4Gn)>`*K8XXkCBMTG+nTFH%Z;BkR z>aSOH6#3*je(hQso~rkOuaCX3_lX!U(nJQR9T-Nhz_P|Df^LmbIQ`(Cu$A-0E{btz zY|DG>j@+L(`|WvF<77X`ngJF9zrDJ!@Zq;syL^(#<$E$~ZY}GLv~0_r<@P_dopgD$ z?WmQ|WVi*JCdtZA>hW^3x^ZE{!lZ}h$`)8W5rhh>ROgcy|46=N^LC6$kX8RLN)rsy zw-yG3_qod)7H^$lNR0Xd{j9^4=!AKi1(5e{CTci%TP);M1+IgUkV6D+?DCj<i{>yY z?un|Rqv0x>8h0UfVKH&1f>3&DV@BugfG5edff&?y5i+Gh*cm7KKlX!8B1`=05^R%7 z0?s{RYYc!!W+z~7^FJQ(iR}Mj(+${c@Dqmnifes?3{|?wkRuMBnDKeTglLfWy%28V zCmK}jUQeht<YP&|YSp&=O_QQO?4*}wPD3gQ65??A27I@Ju-ieLE$xW+Bi3TbYuao2 zlc!RuAD_U$v2q6LyWa%421NpmlN3{i8OuP!AwNO7*e4KAjW4<_*M{vorH}44VrN}- z`P|;Dq@x7gI->0rj3LWn4E`e$dn58}?2&DZ{?pGZmA7;%O_soOefB3InE2&*GSXL0 ze5o>S-0W+uW$nLSJ{)76F5-N9|MVKI8J~w=J#!lLI=VkQe;3Z`c{CMh79xJSW*|qA z*7q6DdF?9kT%kXg=S^J<!hMqOr15<csO*OkF4zhvig4q|c-N6d`m%1sBBwJ-wGcJV zA&qh<NY8`l4m_JvKNT%sOtgo(O+vfdy|5MYE}sZ;pC(EH3V6Hbgq!}D+W)w~V1PY; zE+UlFJgDP&eGhjn5;M&%ybFVCuPkU@M0m7ZNTIsUYrgn?mdB^QS2i{euae4Gj(2d5 z9OZh`XOk1zwl3zow}Gh)d{gM`cv{sjy025;BM<M=`NJp6BbbRNN&@PrO9O89IV_Sh z6B__~B{Ya@lZ`~@aR2#oSaSMlqauiBC?g|378yIwp35K6Mf80@YH#V6Jwzik+V%%y za@4c95V<F#y?R~@c$tiGsIpjvV#au_jIc|di4k_x{&T7dF;|)ObyHb&0<16NY}#%& zJ|zUCB$8Yp50SoHRri8;{>}o)Snktawr_VmZX%aeb~>)@?2rZSHl%NPoleYsG3pPP z)3YPT9sh<L9*u4o!EnP}9ZDp@G4BmEmWtwVej2hxr8b-77p<JcbMmGg<~}iuKH@6V z*ai(P#L~UmM|4q&?H|89TT!pUPxIF7qI);ul+s~68r=O?i02y5naa^8UbwYV<uFHj z0S--;SbL97YyaX_uz`(Vwp_Jgf-cnLEG9#blkju<_(F;wgGuWKTOcW?C`$l=qu9#I zt0<KxYebyJQkpHQ`xl9ADRaZ=0r}aKQK0UAfSs?FZbAih;w7_Hd#!N2U`w09uxf<E z$pxt4^On*#LJg;Fouk?Yu4Qt9Vl|vyS^aM=+Sd%d%$EwGuxpP@i!)kTmy3Rl2cM*B z-@MgV_Z9mFqeIz8heP`^;z)=mJl9ny`<TCz#$H{zU`1=e2a_k$7Hrq+xtj)FpmrMA zZuK`Awjo!!P^EuzvU=9*D86Lm>zZ)7K#SRJrQR!0*ej@h4jR;UqMLVspRv=&gpez4 zgGY?C^3@)csNKGs+85~%XrX7Vb2z9W7v1k5GTA3froDAM<RNtwD#$hLVMoG|{P0^Z zQR4K9iB^5DSb4YL$>`&O4qnc&q2MduuFK!kB%u1P@WXhe4?J@OxWVbLr{MiDpQBGT z!^@B+N3P4nZHGi#%iSc$nfYG05>5hsx<U$I#!U+qxvmQQD-8lly&?l&I2Fy_u=mc) zQx}CuHh<Ri3uiN9%O|qj|Ikl=wPYz}HtRNAoO}RsV(;PD)Z??s435mvZ%6gPDun4N zPyBGRqafiLJ?-9g6b^mE*7>_0DT%Kx;oVlf9@~3wEsgf^ip4~U?E@wMnIy5J@I}w% zgKyfPb!yOhxZlT$DhoZ>wzpQHnU>AL<m_H`>*-BvoTtQTy$SGsp9lCOzRpHryec9$ zI=XG%K76guW3cam1BmClAdGH^zi?5<v|z<ho%8xy)P6TE`jR^>`${_CU~<<UM7Qr_ zGmH8~(K_|8|J#?CM}P0jy|D8*+V|Iz)c0&Y-txblq4MK_HGKAAyT6lBag8I$ymfc$ zK_ii~kI0E`??`8uT$Fe<reS-YYvOF&QEYRYcsUNd6VRItv7rjF)1+^tTmI-Ej?aQu z)osBe?wQYLONrQvYOSejRgg$yr1%yT6d?Ki!fU!gl~tU+lRc+gCr#Z*_eI4P0e_H{ zS^mYw*Hblo<?nhO#HS^8Nhom31|fwGMM-R|k=BoSlDF)Tqza(j!P%HN$Z2ZVQa{7E zJA4x1G6Jp<VUoW$dEs`>-A?6COe}Qbu5!u_LQ7}6yYvo|ZaPL|o^O>mL^ZCExksLa zs&&LHh`S9`>6eoT*}W~{=^{;?+Jst26g;iU{uVVFnO7pBr((dC|MDAzy7i;Sab7F0 zW{f*B>}B`r^3d2!5(r*31@_I4<>m1f&{m6<;Ng8pJQqNssnKqKZ^WY84subZ$Nu;z zrbgndo09|&g_7(x7>ehZkwgl9I!%t$Y$bf}|7bsVl3P=1!vH;Ob~CPppFzhC%4c-e zb-AK#*u-5c9P&+QYdx$hU`8Xw@Ni3O{H6kwCfyPs0dop85Okpl!!zOvxV+&@LGpP= zO#MU@gM{k1_*i=s)~@<Lx-Hf<^jA<1;50lwAFeG?_O<?!{72#Z&*Ru$cauo1`w~15 zc5{#1l$+g60($QA6HU+V9b_+m4U2gj?VD_n?GRdDhYbqEhE9N|lMIfA_M`xmx=N_} z_P*?~Mx0HpYwgqBTWMeE3cw1(TU-?Hi4)3BoZ$6@x9xV#;FRIqoNPvg1TmQbbgmJ2 z?ZU}#+K_V7Dv7YoH|msyC{JSJR~7x~@#>^CxZfp%i2WGlgOK`dKm7N5W_tQ>2`Km3 zpEFr(x_r2oK40*hg^ReUz%y5a2G56gj!G9iZZ&?i3CUSK&=l4Ch}`YkAptJ-Zr`1c zKLNX(x%m6`s`>}Cn=Hqv+sd((C!4T2c$nw~)VL4F=D^3Sh!^#93vtSYa@!GicXGa2 ziFXuE3&2t$qHJ#I2M*5a3O`-0q3-G1g(*R4(+lp4sh6922P<v}RC_!rUQJ*SB-fno z%n%c~o%EBA=(g$E{IIRIS}=Yb_q<TEht*;#AG{mt&jq|{d!STTd-gGX(*L!Qw~3M4 zlu@UpPgo)F5Uo%6rU|E?!`15xM%`KWv+sR2eNcV|RnpKgt1(1>{uH-u)(Eq&E7nNW zDp8zx&L>}1BaAm7wOZnD0Wjse3^K$@NB?I-?F&}i<2x9STOw=(a*aO!xV?3Z*VJSk zVLhyHDShpiC=l4ybsTDukHFrh?5q2U{}AM;$MF7sj9}vV{#UpGL>}ED__jURBti@1 zoEPgE8kD>o9#qtBD8Ha?#BOXXs{fEC`B>Uh!0}YM9yIx_V%2ZC!l3<ll$v6>pqsFJ zCRQm!VL!?1s#0l#7_?5#&kM`$KP@YX5XbE1HDbr!&&I%79c1|qG~mLCG-wlar_Tw( zZS=wUN`Tu|^_JRRlO5qJJ$-fPyYgKA*QmDf^HtLoxo{N?gHn*H{hAwv!;WI$>F3?f zB-^hY*0emGE`=d0Yc`Nu7aa`+3}pkOfP`A>QGZGZf8h6ajihU$BA!WiUK)-)F&2%Y zxEu1W89HqHZ1~=@tCc7$c(tI8s~D%JN4~ODGI+EIC4tY4JYDm{YH0auKmO?d<_HW+ zqq*zhGRcmhiIlaTf9PY%$@M}@y-{!(H_(<O=9&xQw@O~<UDYzpLvtj<Yz7g0+4<`7 zA(lFdnQIXjHsZRUeBA7uGBW(RY~o+}<XJ*zoU`BkL?S|7dE&Q6IK6fUm-_I{rPI}T zggm@<+wzBNiuR1C>uP!WWbKsEnExw1Pr6}Jg3?l}fBWv?NxS>e^p<tQB5KQAyhgoB zC4c$AaSTE!{!EELtowmBa<T1h9;$X-eyrR(J`%ATEX~VbSR)m_uxmYI92L)*Y%-W{ zbW7kC#RLgE0;vm)7L|^L;|fv~ppkg+(v|tSRTsa58MP~EG|GrY2?mJ(eIWI+9mA@e zzLWFM$|=Xt|9_|f_;LTCM&__KE%gV1!Tf+@&_uP%NGZfe_C>Hs^h&gCZ3q#UdZ5Hu zM1g2y%3A-5E2@;pX{14u>)BU!%`Bz|jbKmY%fMq1U;Mm$2!2zZfIs9UfG&w;Ij>ts zP77!;F{g%C*q!y3I!5v-+G^)d3W(|n!XEUk(ZV|4D;>HAtNG0G-!MjIv1mDF>(5_Q z*xVDs(CSF(Eid2KRf|Eo&;Nc}N0_5HWKEw`)j~&pU~c^M#e{t-Wzu8q)ycF6sXGR* z4Z6>y=CW<1$UEyAOn-0x;_JdIm$ISaW6iXduR|T9nRa-iQCZf-$SmvxPB`EZDrRbQ zu|NU-`e<OT#ynbB0iu`XR9B_UO((%Ai+FS#hESkbfAJ&`tDteH3}w%{@EA5{abPKD zlmJWV&!(5<k5NM4$`$Gs0HUl-YPJ7l3o&jhH-R6^yq`Sm`$<?qI8LtENW^#`NyVmA zzg=B9TT*e<7%Z-*TJ?}O^eA9hqoer2K2~#IzrW(XL9OnIKT+FaeSx$`?^4zayCpwu zHb>An-(r(^T)X##6s?1*iV7s(!+)-z=xDtuJ0Cw3?+-z0@S=BWqL!;q+T*I+Swt6i zSbLUQ(@0AF(^J<a+WH0J_wOqvk7Y*e9Pzi}z|#C4Z{-w0;$?dBSHK!x>WVOwRN2rJ z=BX@5XvnE<BF*G&DyrDYz9u}odeT%tGS}oF&B%Mrq|5=9rI+;5;li#1x6kE?Z(kQb zWdC~>fIPXTrlO&?CF+4tG@Y?>^zaPd1qAg^fCCEue;n}TzZ}pw=T>l7*cC;qCk99J zKoV&}kRl}oIT8CrL+~qq6pCnCZU3-EHjPgMSKj$DQ$tPBW<`#&P|G!xW{BgbUEIZ{ zXd4{N>=ejufM-9QfLB{D9_=DSfQ=REI(1*$U^`gu29@@tLy<;j`t7v=66?3Dt#NO* z70qq)1-esUDcUzy$m~eq0eH#Ztg+O~8iJoz4){x~Ke)uOYYfa!kgzynI5d?~!Q!nh zx57L3F0RAc)5qonk7rusDCnYIvDSvXXg`1#)UmZ7kR*g%TqW0F9vNv-Wj?QdDr$s; zLtCrT6`}+=02~QtogPS5@H5A%raCTlPSQ&(veki~o9ldx;F{h~rcBI3`kS4eQ3zUz z#G0~%&RST^NI7kRIU%-hc0$UEr+mJ{^@}@y+Ig@o=h@5THaqau)y}ru(;dlMD#lW? z)R@NylYU2OJgpoNt)-7F)M2K~IJ(cg^0~Po6UqrOk3@{~1qm=*q;e=;G^=MyRd%f& zFwMB7UAe!imXIaZ-5#;EKib2}p8QpNJ`x5AEe#(wm7s>hRT~;L6Pmwpmp53S%{YxJ z#jp7d>sXnLQsDx=v9giAp<aBcV3GoXi^dO@vIXd5iN=jTn*-%a;Nrqf+wp`crI)N; z=#sg1xIY1DSd7*Sb_aqtzg@E(maZ;E;&F9f&ml|1>&m(Na#`*iuD)!S(t(BWNjb_5 zC!mwfHfGdeKr-y}l_2Es3~+iYEE3AUG1aVLx7G1oE6#Z?Wv8&Ii~(7YLhoyu&``Bl zWjNxdK>?UkqX{p48H$W95tO33w3d;Ki+lc&@H=D)vF59{EV%_*-MB&8;uSQ1xRq_o z%1bECdgX!2PZ`FVV-x8E7~>cA9n&}bv<01vL7|mip-NP7hhJ1i>-B$JRZYs7I!R$Y zUaUW+TmJR5t?J&y2*2EW<&BL28An4H#!2V<;l&9pts^AFaA9y>K-tMCD(}Kw>hBlk z>b>-|kljOAxv<j$X$*Lh5#D(KeY+ftBPzPOituIrqSDg?gjYgask7h@3L&YERaY-r zs5@8IekQUmIf|W0dEu@F)k?ZNT>4C}-hPFvEJyUtj7K$xe&WEr1w2({f#||5ODfx< z_jd7o43?o4JWlxJ`wSOun@;6C+GXW8@KB?-hL%V8G=1zmk^ZFosbZj|KJRfdb9Z4w zJ{H#3QZfzN;p(0vZ675z5q)4(k~ar%biB&th6iYY48U|3Bw)fqI17$aeRBQ6j|vxb z^|<9@6REjnv<$;09)vg@b<b^VwqUOcr`fGk1BnVc5wF9UmXMVA$KQP!k!iigZma2E zgVsMm87{eFPJ+4$1OGp_HFM!MiMq({a!rH$*-Bn(yv`%HUKmh5L~(2Avhyf`&<|r@ zjT|r)&Rua8XrAMQypNU86U7(EXy+%W3rK6mWyy%w90oCn1%QkKOcTf%B%sB0<wi!6 zf%^CsRt;If&Y@l7X*Jx+P@9iG;uIoI)|-^aA5L&z8>^0gl5zn)PLmVgaiP*QY>-L8 zaZH1_fU+^1;kLFD(X(5a#U(x^_tJ_7zZO~-pg+cDh5hEs#a*XvpJs9gh6vtTe9*vh zGI11zTfjjD$?RI41N8+}T&7tyf9UH9mFOxBrs=2^gmoNH-P<5j2{$$wDGw)d;t`O? z#@|_s)m{kz>*hM;jJ#A&D&fen(<;0~U8qg;#d)hn`HM}E%a*TB93J5+$wbJkdQ#nb zz$s!$+2-`v+-zrz?D3*iOZ;^A;PB#H6GsvHrVe-HyIA6ytn1H065d@KJO!_mGSw&M zYMvp4G-(CH5Bo=Kb0kQwwmDcKSE{z=dR$J!3@F;BRO7cz%MaeC)kZ``wQ3yYn+$fe zwdJkS(8qjgbg0)C*9KM9*no55^&H*faMiB4bK8KP$%P|!^V(4EbCOhl{Lu0g;Gn_( z#fI|!;h=o5iwG{UqanwJ(@By-?F?SOUq9a5T<j;~l?9YNPjDJonYk~p(teQ$w4v9n z={2}6*6xQ{HybP6`7E#@p0`Gb#8ubHz}Mn<!Itfr_KrVxISAu&hiZlEmEm0Pq%~P+ zjz~S5TAcK|_NsY)`q!8F3cx5L)+*$kXwsp}25I1l<^ay5!NS6YJ=??C030r@*^1~p zXI(8W@vO~13U{9QaJbkz%pyQ#W>@>{4cQutp)|olmmgvc+Pfuj+sS%o_VzBlSb}bg z)!oae@fKMr^gy-$Q4+cf?LZ3~fMnip{go=4ctKD^@HY_^(Rr&C9*%sO@5&a%@fm)C zr3=_y>hC-;!~1ffo|~N@dYr0NPYnS)JpErxwEpV3`7@oXd%rFfwXwZ%y2gF?F8v)g zQNB;lgYs^DWK&<#L>L@~_W2>JvZQ*Cn-xLzIa4o6t`V8>TnT4q<)`qUyUsf`>DRc= zAeQ^MUHRMze!C73B_4n#D|p1DOL&5MH^lY*)7uUU*an+)-F(0QV0eeDbJf6L<I5h$ z4j%E#<#{c~>xv0u3mkP`$h(1shX(njalw|Iieo=Ll?2R+i+<P-A)=Xy$}#IacC?in z!V70>8yWpT(kI$|R^!g`mkU_}%>n$5$H`oVGh*~RJeGx|(%Zc)Ky1LLW8Ss~eQ%y~ zOq5$3r$^m8FoD)DP(*Y0#eER#x8KF)ly`=AI@9s~k>0(F!?2h6ZJmhrC<b(7TFvo% zN6aWG1@Yvuoge0HZ~uzdmj#b6t<M(;l~HT1*~fL4+}n@whQE(qN>=*cIuC69YIBoB z*TIS<s(Xviet&?n7nUT=q-I}DgCo+Jn0XQSp@tKB=)H6kMRkpfL|oRdT`Qui;(}xa zDm4V+V)+x=p$dAr8r#YBC(SP<oabX#Ob``xHIXZ=V(sqFJrtp`u7fsSVw>ZRX|Y3Q z1G0jO{L6Q}PzOO=ZiDu6io%=)XxtI(QyE`&jk;wXugQZ7^Y41v-Dxl&E1VCiH;>2T z-OXRFb_y?8d@oQ-dPa%`^K=)4Y^8t{e6JHZ3<m^rheV|f_#2JPZUjsVr3t$~x<0Fw zuWk<x^B$jj{3YCZ#!Q}erp|HoLM!zZ?2cvS%A-#h+rgUMK_rQLJDk+LC3$ohBf_5? zIf>OeopoISwZZ;~)_AqtKvIx=Vqs?Nn82q9x7rY&Y6uJ*bPae(EPVkHhXr8y@PDvO zcyyko{2Z}=9bpvcT6r!=?4Gz9{Qh^FOFU|y3S3Wg`MnVIr`VLD%KhsWWgp^E`7c_5 zHOVKurD4gRoB7^GcWF3B#RhE=wo`5MB3O+oyAT=o<eH`zlu`-8VlKKncN^K<K(Bl> zUfTJPYmKH~IEASgsX;n3_FTbkW+x$fHBs;C1Q;LVpqeQZr$Op7q2YMVK_tkf<iid0 z{f{NGo+d3P6iz!5gl$Xz?E<=f@BFQ;!!Nx3CxE|tOMm*HG!yylO`I!j6mbPYrQC+) zA$p>40T-`%5qy$N41JJp)A~u_d9IvA{Evazh?|X`cGkCv|Hz3;Qbwfq^NTN-1Nc@& z(>oyn|1rL`F*q_R;|0&k;$<Qt$pXVQep$I+Nzz|RcMQddlUd($ka|qK5Y@}@nc5#I zpCqpqCH=t6Slhz4M6_w^*=XyLBt@wvqYE2mt{%4?<@x6P?)8dpjzCA*YabP~En{qo zgoodjbo%>_b-qt?ypFcDZ_RSvf2eY&$%c>SYekJstk#3dgRmY^;n%AS%Tc;+PH_)Y zsxAE6M6r2Hpg^6AMCG^<!MJLRPg<Oq1Z)Cis$xbC<9!l$lx>#pF-0v%2s|9K6oc=) zt$xfo)>5Ur`{cK59ExXS>P}i5U+o4}#7nV{xr43>ws{d!WpJBOd;blD52(RXiK;N- zJ<8F7H_qErHLRoa3tSU3Xgf{)M^Mu!oA4k<v)1u9*wF0N(*pJ4zS-7r`;AHe{WVO( z84O%!C>q6-YXj1y2maq>QBDr03b&W<?Bq)|{^jGfpqX0h*Xt3!OW2sWDaR?W*OA8N zOSB0|-l(GVxhls-8dp^leN(N2Et3thx+wiwn~Yl8cU<VR6ha!_wB$v#&l*R&Bvg*P zZd&SG@+GVjA3AU0E?5{ud%61#WC_Hn0qS{$*?zuaCw&>)b~p~zkvTXfE-wSQsD|F{ zPOarCU`f)5;e&dG1<ZCM*V0Ae?QlJ2r`0kQ%asik(!Fb<`gKH%j;z;QBXtR=(o24) zlWnN5?pS>jgq?T20E}h`F%tka5>pBIX=qp!9UQN0X(4|%ojp`)7=nD|tLs;uS;q&H zyzoa<X5X_741bR{mq+YlC3@4vaO?H;%V3{&B?-^fdxPm0iHN=obWQg3m8iile0|aM z+0A2o2hXIzd7V}4Y(Atxet*24k8LhdlU=UmshV4M6+Kby*o4!u8+`@-g@^{lR>#d! z4#;H)<p`%~y-CJ8)%C1}mj<6UXje+8Ds$5BS_0=f9!!KFYXjypEa=%f(KN`%HWsnN zbzEhyr5{$hTrSktzfGS)l2FT42Kt?6fx4!iEBE@7AJH1-eVapU4SNYw&3ESdB}o<^ z1JcF4F_CqhOt0}01&kNNejwPi@^l?Y4|H_<=4kiu8TGyAxj8vBBz1YBl%mwdJ5oR& zRV-LUKeUo5PDZX!_G{MeQ>~v4-?T#5^%}-62D@&hy<<{3Xt9oXGHOvxE)gCssego4 zoDO&Ufw$N6pxuygo&VvvI=*bxlX@Rzwqx;Tho;RmY3HP--4npm$$om(T7}|`<0-p_ zC%wM)4Eu*Lh5$wxPi|wn2jM8s(oeI!xH2K6FYkas#D-Pje&sU%Yvix+#i)pceL0V= zZA_a55=)bgtV1Zc2L>1&j~wioRuAckviLHt!}z-Misj3wwG6m81FwuV@uT&#(e;+l z2(%bzC2#EPP}WJe;K~c!)kh#@g@L<t2;eA(2kwZS6aM_8p3;ND=R=Q`oGvu#z_HlK zs#@kS%}zCorkF?0(IMbEgarBWc$K<wL<4if-lJW{9FD6oU<i})N@<7_kOIutl^(yv z_F%CcNz<^vnBO_@*uO}czs38_74bkoHKw2;`vuN)Wb#<$udEaEk!#8FHrD&}{;rjQ z%Ufwj1C{$r3<4X_$cRl_amIo|DT!yrMou~c-!tEFLFtln@5&#AQ&ymM#OPtXk?i9L zwPJQvnZZPU$6JGbc?q?`utJcDxb5-M#Ge%$RMOYq!@aIgj5&DSTy9ghvQA%WP~%Bx zk_zcL)FC1Y>gcqPD`Hep)#z7bX8Yb0#vAuI;~QVWu%KqtnbB0Cro5$POuBE&1-5W` z+0^k%K|JHC8F;FgyWKwbyP)HkO-Z}zs7TV)MPED<=o#rEAc1^*){oD$l`U~Blb`@7 z--vK~JE%yRZ<DA^Hr%Eg`aPnr{w|^YQO<Jfru9j(kmuS8ah-(5y}*M|gVSH}AC9(x z++8Jx;;EQ>?E@)(14f>(6P$HINpNxY`t$j_<|w}z3%8l$;f7+=NoI0Dwf%0{9oX)* zwf4JoV=o$vaK*`)qZ4%Cld)=0ebv+vSePkEEh*Yr|IsPGqW^unQ>oiH>qD=0PSbv` zlBy^(&Z%d~f`3Hyj7pfLlVNrpg0fAP2u#QC@7oZNBFDSSgWY#uW?^?Q0M4+)n6ka4 z*pUR+B`$n(=6ZF1cXi%o(!Xc%MugHd>_K8)@!1Ne0KAYlFqZA|m-EjW*G6S<79*11 zrUyTC($e*68GBh{()}HHRZ`8r`8J(U0I1h~a)UywTBdhh4A$*Sf!opB3n{diWlTt* z7V+jIM*<IG$*gm}s!=r^?lmJ?m@&#KBY9WHXrDsjxWgbyW;DlR#^02pu-4bTa|HME zEDpBvvO8ThB<o)5cwaRr+>BGo3h_R0D=Io!|HAnPD;s}3TfYcgyBH<v4&0CfEll7l z0W!$q6;>OQb~G*3hub#EYBm5^C<u@8p{Xu&#Vj$=#k^1gA6^@-Qd2XHi}`(ijxu1Q zj<#z&eEH{u!L@4!=X1TSko9^UuaY}1rD+iJDam^Lc89_sLd4?)m~%k)xb<7?7y?(d z0nmMA(LhO=$c$mZO8P!|8RcapiSiRMZ_zI`VU+b&6n)8>4Uy{)C9e*?=`|?Oqx|$9 znkkHsX+RnvuMqf#c%`idG^QF{VLjfE%%)|~i+mZtx>-9bRVI~6x_N$P?4A_V7V<1# zt$Iy)>PQh7<+Cfp3%hhaLZaKR+g~4<(Xh|=B=Hi)YzDz_H?*UK%j|3QhY8MHL_~>S zx^jjFS0bdj&^=<(EGz;}{7yF2j^q1#ICpd#BeL*GwW#p7>wi9F?VVGrVh^p#L%l+w z`D%9g@6>l+sC7x#G)ySUE4%_;g*4Gajd&kw>sm7vQ~Ayx+!s4MrZ28uZY<$FT8O{6 za^pjhjFIpUv3BLcJPi+KNQY*^a<~YEEUQw6$Zwi9Thc`(^lU-e$~CDP-gQ^`SVXz4 zXB1V>N<0&)i?0mhj^7LtZgDGqkZdA0L1$7=r#_*Mq9m<0vJ?L~4d2X0YQ{86H`Bw2 zx+i(rElpIb1SwY7zVOK||FP3Sp~kN+x$9~E?p90_)(ofSEUzQ%O;kEfoz|@25#zEq z&y7QuIZIu@7KgtBvc6Q#cDRI+wMj)uolUl2KGgO^9e>bJqskt9q&PEQAdOQJ$d)$9 zquF2pgcEd)mrrgYPRB#*mJba}E>G_AeP-DZ{r)ffYE&c8)S91<QfYG4`Jsh*w8LGz zNk}milolpx=km?=odH9uk&5_0IJ)0-HDl4Pg<^R3Kq30%uC$8KnO>MghsH<OxhXS~ zn@M%7hfw<b?=1w@4z<t{=5v)0B@#u4Zp!d!^>jPA?awZbmRU~JnR}1qDW=35q$%O` ziGVj+k`&Um%D?&aMT=90*(%d3NwOj=tmDa#7gFr8eZVy+nys<Hw+mt57o*9Wr|0`6 z@rCFmH7WQA2T;b)CZ2whsuL1x$s5jO$rwu0qo{LBs=G&fUO9zCx25%)BmH&*+*!}N zHb2wVX^-E7+qNIXd<%1wA-_Geqng^qiFhVBPT!N6;}azK(N4WLzQc05BOzjCVxeKG z)5Uymtn;g@I4(>E`6L6Ce}J+;jWazc{)&E5{tvdYe2fg;Bf&Odv@|_Lgl$32SU(Z) zZldS<7&c!yW8onMFk1K005wRDTyEO&M>=Bpc{<!{SG0@(bbv64XoKM6whLqjS98iy zv1yVlb7a8uj4woF>`WIV#JMZ-=cWhmP_UFC%;A3N-#CnI$>4SqQmqD2Z5mr{@lBJ* zv$~{r!JJ=u6-I@k9vRwY1AH7e>dhJWwSZBSJ;|bhw<G^;$u_<ddH~9MAI_?#>sfgN zi$Gh%$3A`=1-r&InYp^bIftCVzYhG$Qv;0lT)adq8W$c@U@ERJw#9k)`ug&TmXBC= zEm@rpE=Eb~aLB!-`M%G628;X-%22z6hZeY|*kpR2sR;0t9vWnb`n~g@5}m!G6guD> z*nCan{F}FJjvx4Ed~_~SkmGpzK3|QKgVq)a7SjlUvNM>onuuDY2X<$uw?20zrIrN! zNKcWm-eE2}KC^CL*Fpy9Zas{;;*Z5Wp)5ai;tQv2w74forWpkNamBt>zV}02UNVz9 z4dfK$UBq8oGO4ju*+rD{Li8UN!V-K<^Q9mK78G7;u;pNx2ZHALxGj!-ISp_K^a*L$ z?qqL0fnKOTA7Ti5$!q_KG>g%++TEvCjVzM+RR@WBXXD-}aX9IEu5ms-y|bOgDdRzK z-W{aXqQy>39=x+yp=ieEyes2JWF<vDzXy*Vyb^DD+fwxuqOS+NVFzu1uRKJ8YM;=q z*=ZLNr$ijI>lR7~jDMXkM$(*xEx7T9GF#C-853$Nzrp<v7`%SAy!b3#*aH$ALWP-b zY|M{l@)ZeVANp{-*mjP2ZMn~^%-Lc@IhB7`yIrww_G|Nz8J7Aqf4t~y<u=2FwesGW zD3>!jKt&8=Qa-trL6i@}R2S<2#`SMAz9Z~ST1vFOI$E~Aj!S_hc&+X}mWg~K8~x}D zZHQYz5h>71;36ww`v~=6z$&BXLaGn5CQKR_@U+8$N_a27#_tG1S-PBw?Ql+mypiwX z72v$^*EqF3jnd?CyHQR5b=SggGgtoY50K6s%E|X?GBP1loVA@)och*2{1f_xE7c!8 zh>02xu$hl_l$4YFGq#5nE>VdOt{fL`wHw_hueHF7(j9jz#(#3#G3|tB9XT3GCronx z-)D)kd6(Ij+B98uiU;%XD=WG3_Gs8d!1VOXTpKno?Pw;sK@Ce5UiNwtBBFanbPr{p zLk$O<wuj2t3NsOGXs3w4ystkUmh$ro?ihVs_@`2-P7BEIKKFWxw<mihk4^t={@jOZ zn4c&6AH4df?`*#1i-^aUZ`i_tTxW)rzrX)jg?~*3pfk#WxEv<gWXK9&AIe1p6ZBV> z*E!f15uL`Y9%`(wSOp=`wBl-{Gvk}L8Z3c;-hOXDF^pza;FD-^HL|-?5~jbvBG@s& zt2WT&3uxir*7!u_5$C4q(WLEkMSi{>5@u)%l<1L+*ZrW0*X{#Ud(Wx#t>bWpu27}& z_R()mZ60!wikS>iKbQ^PGe*4BCa(T)MzO;9XZtuax40Mk>?jo*XN@Q!aNwmo?Z2G> zFrk`tDZaA++$&(Q(U>a4Yqh&?N7zd^St>D;8;o7{KUdZ&;p5FbUxS@I&!zkFubc;e zd>2toWTMb?kJ(PH#k%F=&Q1&PAR*Dg?Uky-_O!s=h3F!#f_O2_rJZC^UnQ-7jLbiM z_Jm$XguNnJygKgb?ryy`D=px(K2G7~>6wn-`shVWB#GJcZ$4AtcK`|LXz6ioNY?}g z4IjMALt#MkMH1d~YGQ;L!BGfvSyxwSVntkrkEh<LnWAmyEM?E%%e@>J<8>Dg121$} z60dk48omDx2&^A9eIQ{+&d*}?g!JHsz~tqduprTz{2Mk4nM#XwHX9UNaYgZQ2t1z# zT(Ok0YFLF_TMam;5i;olJdsVyxAGX^oBuXvo11-fxi50qW$EbnIjdajyHk0jFcnVw z>iJ6imwm1+ULXqEi*4mo9LRc?&N1Kd>-yZ=X#Zds$5$MqK3zx=C*kyiAQ!5)!2+s? zTf5=k_Y)`%{;yU20D?+t4<OwQg1q=$ce{?wpKB8}=>63Ry=n=HB>}AgX5j8RA}*)) zw%A~%#UqaoEX<jM&3e3CcQhlj!Btu(JV1V4qTcKS3`n5LmRql=H80-y@AE{B(lQ0* zs$o*_t^IXaWMuLc5)%7SlsvSsu&_$ZkcE6-U=mQ9vyF&=nrYszoFN1DMSR?hKH|w* zFLM&LrYmhrbwiC!ZqG4V5Ca^gH78A!kN3~q`AgM}xlKYxZZEXI3Q$ZYC&8*_uXEm~ zFFo8@@UPM;1i;PP2T%YK-ChvV^L@FEolq8(FQVz*-c4eCNRl-5y>M|4S721Fd3FlL zHOHCg-o%K-&AXz)L;kVye`XRC9v-wVl<M?#xQowjxQl|r;JJNWomd>EARUm+*t;5e zEmFn_4Kzpkt*H)LJ}zOP-l7|_q_j4~Fm(v>C$v<KLNWu8?}zg=@I^misQKqfsGOT! ze_1giYHbpyrlo4aj|(;Hu&3&I*4A65B7O&-D;%cQ@!+(TY9b&ko~TPTuAx|v;}K4f z!s;X0mQ5eHE2wu+PLz7bpRQU7Sf3gfKgG{(i@0@!!RnFf33^$-s>J`2RgnC<pmm>n z4nGA99glWxK*Rp<|7qKIxE)J8eQc-i0k8q%Rqv~_$zA%u$;o7<UiM<jfjW&e<Z8Cc zq{ps?np)k29tUejo>KqG*#dZ?)a0FXTHlJBj096C9P!t}CDLb#?L%A=7Pd_m@#>4e zK`|QpRGq27Vp9P2Q~m|ejXsADdFA;tT_Djyn$2IWcNZ<h$cV?8&R#UH83w!UU?%WQ zg8ERY2DciA@t=)q%5h+}eS})>BZG5);eSoi_xt;G=Gpa?_4VOx3vCQ+!q;zqec~~f zl_g-JWutEn0Q=Rfr|8CVa%ot##7|Qdqw&%x!Nq7lBHJHdFgLp*s5u6P1|Zdg_;!f^ zsG|;Vd+h!#&TrN7a$&RWzl#1^235yDzWaviXnb>YHjd;p@`U4eclj<m?{rpcoEu8& z5-ZAAsa*RA^MO1(X{kBua*zD>sl1I;38qTJk?W&d@lqed*{0p@P{@?IU{R7;fnb}n zSYbM@;LG~sf2RZdbO3Y&Oen5#4UpHlhXeq@egO!orK<!~Dgv9u<t|ps&Q+E@*eVgW z^mQpvKP=Kji(io9wJ*)27yDFT0@Gkku|dv<Gb}kFR75K=gviO%CaD(>h4`ucdlmp; z9!kj^&Fo5v_^apg%fNX6-3L_;9#ch0yc>q~tG2*}g<y+nKE*gDKT#s0>8xFqW;Dl5 z8ZZMGJ;pA5Z9@LwR*ucVy{w;(OQf&|sW6$TGykI{pkUR=E5Fp)k$$@S6^biCS5ZxD z#c2ERFJbnPzYQ`pcX?J>!Ujv~=+Y=em0Qnf3W)NVtLG`$RC5p!HQw7(3FG!*oB)o5 zfP@<L++;tBr!$XM`ebl>*x2T;*E!^-Blfjw9Pz1}FLR{>v}bmr(H7}vDm`sqRbB$? z>)#esAt|{}X{RYGh#nk-=E?^<>=o(Os-910XHz0(o@K(b<w9q%VKTkRP83(2O~(TV z0$dMYUkT+^hyKV*@#o~8e4fx{>xzn_?!v1`qs6dme}TYvGT^lJ#dX6=T+vMZ$A>$s zfU|IJ-*i~W_Yef#5A~zZg%_U#yGm_eGAyjfM;dK2p}q^mbzaFl0u9Y#uLeaf)Io#o zWWW+FX!g9N(+r=w(<vjLYy+V_JM1E*#KR4Yt}fB2Ep|``x_$TGSph%w4S|xfGEw`K z5S#AO6>9?nbr1XivnTfWkO79Wg`knoz9c<W91L#%vF#t7I1u|Z5&%BjX^1&vf}QT6 zzE|}Mm=GbQ7Tqph_hTKzA;0f(CrbsEulp7)7F*vvh3w+?-%z7Fn!v0LlaVTD*|EX? zavX@-SShIzbj>Wr+c1{h$%pUGgA4WbHi}V5wv7eGscoUs8*hC87eF$XfsuWug0avJ zFnjK};6ep;ksWdw@7Ku^Dsk>l-+({l4z>8=M)!U2n9YFVbWDCo;AzAWKBKBF5ARO3 z!M*{o_5T`BnKdC``k2X9L_~zY+`EJmRNf~nEX;<CFJo<gIaMYBkkX)<kgqW6eig3- z9|#4^=nm(T4$8azsz=n>K3-*Pzo-xx;IX;{KDbmvnN1x18B}lW2>xL~E7*(k&gfr? zC7J_D_XNIa_c|O46@E;)Y;u&Rj1I#h?R!#3<p#?s8x;p#t3jMk*>HeM#>exNhy8k; zWo1%Vjz(Tat-sGCV<==b*lEe|%Q{)lRKrl&ez!s;dG~OI(Ns=`KaNJeD;9wa%QbN1 zVm<pCF+cV->GjcXJ3G+-<}Z_bA(+4vy3n0wH<+)8me;F1Dp1dFo<mAHQcYsTfWa<K z7vwNS#dOA9_M*PAJE9nFbx3VALfu>q;}BY5YtDaxB!JvEON$NC5NAe4g?a+|7M3%P z$`*22`@EzIJ5+xe>}NbGFDtu$z0((w?>zSf*|j+;t3P~bb-2@Y-qGmR6YiC*o43e} z&UOrNuY$C7U!a-p8?^7>!vzfiEA3x10d8sTgClJhl2Ktq#nhpb!gt;O+VY7He|*Q} zfi!y^JTTMKLEVY{#Xz|vp+8&3XAaoz)r9-oD#fT$cE7GLwrX7}w8z?tP=$+kBg06o zATpLJ&fw{maI%;8;dsCaHmX4h4VchSU2imp?}pU$=s4EWXH8$0e^U3qr2+);u6BNh z7igi}WFS98EIRL;dj{;qsb_#S9iDX=MVAT#>oala<OUov;&d1otq__NFxLa$`Vbq3 zhIedU`P3lDS@zpAGVt)Z0o_rWAauBF-?0=od_zag{ntu#h;eyb8s7x~oBwMH3YXkj zuX>?Zb<5Tb>uhuJc>LYUlq9v@_tnxU0rf3l`x<}j`7~UdWCpB-9>^+qI3@88%5BFk znZrHK;Ul3AJeSv6R=$Q7Shku%4C_ayFeyvn$2rEkF02373lOj)2m1M3dz6-Bvz7I! z!o1_BV$ySIn-vtBPpLf%ZWHL|`!`=I7HIxJ$hv-ERyj<5+nv(ANP}z!kt|hR5Q5c5 zWJ&Ee5PWwj&TIfvGh&7%BzAIM6Dx^az3}wN=<mL+1AX1}>b<}p4Mx<!0sAKK;zfRK z1_YS6F<%#xavW10Zn&o;1L62BjNR9sQnQb9GHR)<_OtV&4)v3P2yNWvM*XN`b-+8H z@>CzTGNwze297hFIlO;)K#e()l3o{nOH~7`Dy9Z`4hVc+&VBLRHDd@wo)%;wnhaP< zk9oWbt|la}p9mK7dU(ji6r34rL6hwmO=uy@uyjmuAb6_#2>++_6~0+-v5}Bd>gs6t z9F3D>%l$*9|2M71*KdH{em-$X2?5^N1v;=jEG=AvT-FY#(vml4$yIs*kg_ko%I+0d zyc=4sQ{Np8^!L}5_G<Qm-8t0)l(`kBXpnX^Ct{S%8i*69F_{SJP=JYkNfG;1$F;*d zy8pa7|9PQ>rn~OnizD&Q)g`58J}=OEm#i&&Qn%h=k+6!%bo!(xnSfz^v#Mh5A6hFh zGXSMs81;qeiONm}-R#jc<QMd1m@Hk8qdQE)0BJC-k1!1?W2K@4Ek`c(N4g>7qBY)f z@YPZM-KM{kmdFG!ahANQFh~2&*rzn~^rbB_kxM}F9=I-j+me_ls4e}qmK3_^cYz%L zNt+mYgu0S`GvA9oeI&46?^x@}GHzH(qS_FLCf9Kxi`7f7>ZU5)bU0|kj!sYw)aa6M zk`ibb|HOiUN(DYDZ=T41mZx*S%1bZG4vNymq&(%6JWY1(k;c?f?1_)G;C?)6f}{8m zz?fMC5^OD{ucFie13kH}<bRYe_|_oJh2&+NqZB<z4AUS#eAp3~A=sd0=Uo>Tj}%rI z7$WyKA7o2Atiw0}L1wokb1ie%-o17mor>d*&hw-%(5ilopA?<_`L%K6@plo~q$B{6 zYkl0-&iQ+1Y){cZN-1Wrd~!FD4~qPvd4(t_bV~KAs%DIuS9Owp-mevqIA2S;-x)3P zXQ2$rgjT9Bg4OGIpe~>TIhD{L5VgMF*-X}CfCftXQNt7t=Yh82uAT5${kCiDf4Y4Z z`HOL!Pf_pm@sB@H+1UDW%$1UtHz^4WM!;>c*HZ*vJlW?<@e%6Kim0-6j2>bNy~qb_ z=iq=>Z-25_%5`C*$8R&s!NDC0g!w1~^((GrBDs9Kx56IUtDUYQ+)-`@s>Ux6P|C50 z0fb>dgYCMz*b%89j(h4%tio6+DmUGdqVnt8ybJ$e<~`Oo*B6Fy9w;3C)`x#wJ!5<K zO)AMw@`0{25$iI`?xApQ2mE81s9?<CqtCMugW_&q0l8co<M}-X_TqjH3zaRfGSTM+ zu6c>qF%6x<Q%A|kW<7sL+c}8Hy1B|c%qEpWVlT#NWMxP^Lg}%mh%%ZgdE@2ypkl~C zwn{?v5m2plyIQRp_4@TcF4-4q=qrTJRly7gp0k9he=I=T72*lmo{4ZdMD$R9f9AQ1 zwx2FW@LC_|&rZ*auHn#VbgSl&oww<HNdv4NHc}J47=0FYu1;Bt&`+z-<(>$jgl*i= z=*-s$C<N>9rM8e1U{mw85qVL-c3XP><+!N9gAn(8&!xvxl?oC*1k|vggKb3>wl2N) ztuv>n6D1qzAjv;**ELRxg@u`MKsRQRm0HM1e<oSA>VGIytuSB*tB;A~9}IbTkpYC? zZMdr_c|Efwr0jE;uc}bOMc{~xg1+=6lzK<>X4z97(pDES9OZBKiDaR@dG7J~VnVSI zs^9}FMEPdeGL^)le`xq*lPt~Y*W-P?t7NQd+JIB*QV?(yd3PA29;2%mZ6##L&VHFX zP?GH_<2ls?T3eJB@dUW;RLP4Wo{1NuUx+$==4X`pc=iDh#s`|&hafH{&Ek(e6pcf+ z{A3iI71`~P%dON#+k^SNA3?5w$$o_-U0R4U3lA%0;eC3oL(eTC#ReaJzhYm|X|UIC z)#U8gph)4hVbPovkLO%7Q(xb_oKR6k>&qHNtrMD12<#EN19;<(rrIw<bGMxa0aARj z)ny;C@irm0KO^XCn+0Aol@$EwK9!WW+{ULUD5n<9MDaE{>BJ;CPx`U}Wa*Enp9ugr zK;#~Lmv>T*(&8|(tnpmiGw|KpTmVA%{RHApuHmPpKOCcz!rqs%<gNqJ-BQRPxVX=# z{_G8*M5f{}54fO2*arb>+Ea^9_pq25uQe@ZMtE%5pNyx(<A!n6I&8fVVi{_B?2Oq{ z<XmT|N-_0@j6q(qS~cbWXpeEK^;H~sNYMHh=lwUlm<QbdctdUE#0FpFpjv}~>2O%+ zx<9tv9Ddr_5u>{#eLZ)f^rB!q6LyWQaI1|AwK@#Yhzq(@auI=!$3P{^pn&Ll1sUmT zUo!E@ey=EQ<7~hyM_Z}jX_8(6MC6q#I@`5klnmPoebo>#g^b(v!X*rMqeUib)wIc! z;6rvZaJ?1=OO&>8v<5puXcWDv)BHDr7y}40n>ua)faD->=Lg)i)fH1_wP7aWwT4&# zR^&Dx=ejbkAUfv;ET=&5lgoK@=vfJV&wa(;NzY2czy112lNFHg3_LUfjskoP_kJZT zSZs_Neo%_nq6=PHl)ER`4Z#L4;#P43B!;|365Iar=d~h07@Ui$b7cmR^O54(A1y0f zKRis?baFe_?AQ}o*=SK?%al2bKYwey7l}-QU0Hlgfs-5PP|q*-zzImW?pog(;Eb20 z^hp*F73g|S2U(%|v~_$OaOT6|ubRH^Cz!M|(WW23$k3JR{k!lK({^&i%@8B#ol}!s zs7R<bk}6lI^*$Z(KAb(Ip&zWWuhwsItJY2kUGLopXP})j<VXOAxBvLjoECiYCb{nC zitE$CqRcvdw{Cv$n%%JL@T`6J&p1LT3H{`H;87gs5oXa#p0!s)gv6!HVJ48ixjg=@ zVM441>DrrKpbTkrtlU)6$*@6^J-+MbaXq5O)>3Un%~Wou6On5FkEyt=A5hD$sE)#U zqzSpb!GjHen$EO!aSmC_ifXOG6BDSGIuMrzBDv8_s?kj60coJ!yLicc3sO}>PA4o{ z>w&3Q>`fIKbPuFy_LknuW6VjJ@)U2_5RI>Ya(>@I^I3&UL;dZ(lQT?BC0?M%t!ZaN z`@5tb6SJC#T&y{AOf~DZ&ttvPv=P~1xdop*Le(N=wBC~5lKfk)%tcC;#htD$kd;_( zmmHIA!<H7UUWNHZJf2v^nE29DTjlo+Mz1dZU<=at_9SRNgZmOf<#C?@;noZ6^UftD z!;ZDz|F5kt4}^Mq|Cbh(+aiRJPu!2K8kMqS>y|B9E{g2rgRB$7*bP_8oh-RTWd_L- zvL&XOVW=#Xy|IO1vKwaX24lweyxq(F{qZ~h-J5gX=RD_GUeD_}b57@!ahcHqik(PY z-`bQIt_M#C+iwmJYoTuiN_6E-AV&u!^-^kl3D~Vf<&i|5yisys-spVB*EMQi$=cW~ zscRaJ7_-$y3p8JZ2U>Y7Cx}PjA+p<RKYmrQSN^*<Zoo9vWw`w&Iy+YPb-85QilPAc z=OABa<ev6>7kqBYH7qZ;<rWlt^`B%|uBXFE)A0@Gn+JtP^BA{GCK=0D0sahlL_G-} ztZ$?17sRGW`7!ZzF%9hLkr56f`AMukc9Lgnbt@u$z(vikGgjA1_k~%`7vGJklK0N6 zyV?fqXe2@;Nea#QE9KN)6I)5M%Y=3-Ny&VY<+djfzOynsDxlM;rgg4E{1*g!7Mi{N z(I}Y7onuxst&{=<_~lc+Q&iiRLwKnYdtwHPz0zAqE;eeXXXf#8#Z4g|f9bsGDP`uN z{Q@D-{f=>MFr&-vDIzQk31_-rPxw-R3fDg0R-8vewvYFRw#fMvW(1B+wTu~ISLF1* zWyFHdaoOmtgkt3D&ZDyxI>f`EdD&-tf>GTMydHE?;IliQj={t!g7+Yz*w}&~og_lC zKhY`vBc7{FFhj$iGvNNe*ZKuyDzf)B;sK)48@%-VY#Et1J<)Y2T+OEU-hfz*jV$6y zv2rS0;SM<f;pPWl(bMflCCf;GFV*$@u7g{V!|Rx8zXsxaU49R*4~21i7{9+2uG0QQ zh-w|(s{*y<)nDl;4M{*kBcv<de+Jk6XJExWAue5G_>i|X%&qwg_IDhyss-Duijy*P z4wm=P4m^xflMHZ(xEQ#1c<@EC4aL7Oai$$?V<$@(eOo(x!e?&p*8<cZ3eY?b7H!$f z<UXrS6InfshW<yh(;u*zstk#?E}Xkky6<BBg8w{qu%^6RSK%Ao%hG6+?xnW2_smZi zm)C~d(QvmXK3+EGVIj4f?%JmYNjUWtJDC8Pg;j5BBKFx_L_^~Us2FoO-YU!+Em?&? zNp%>vojpE0l*zbSQT7x`f0^*Eh4Ncq0UYfk$gtSFa1i_raQ)*aCV(@jn~~}muM`&b ztWOFYHd<Pe`MwsU`0WxiZ)#)D-(ea0;|m7+2-Qk*xz91rW6hVA+>uBJxRv(uACz%# zwS|8<jyhK`*t4SR0~o{@#@XvFAJ62`9P=d^@&LS6oDciE^5m2bK~+y6=Ig)QUERcX zpS-cWE{Q>(VUmV%Yo_6xnC9}F&g-SzyQ$6Qh?&WMQ*kBUC|Kzojh<rZ83u(oIT}OG z|K8R0KX`asuujL{I0Kq+naDx^U}xGMMo@)_jER^@QvxZ_%j@l#|EC0^bUq3Ox4m*x zc~Xo_R!eI;cP{70kMJ6o_I?^VbWf0ZqBArQ)Q+F&aM`Ob7jR>+ZMyHS)KPKFEl5x{ z@OZtNK<fnf68gAuZdXnGcjNukXU$2L>VT~JyIp&DE$v7)`X$YmJXWub(WrPjF|n#= zfc^ULPFT8Gr_hLnlaE`7Q-J7oIWGHn3__r?>74JbJOjAxlyWwjAI@cBjojML<%p~0 zWutvqHwL?XKL2V5I<!eVTGn#ymLUG~Ij+8buur}#Sp`=!59FOtN^e#1-MkyZ#D3n= zR8p$?=AA>jS)C`sJzw~XrtvsNgR#@E1MES3(I0ssgO|NdIT^^U&i-I8jQohXtf**5 zjM-TE)?e`Z;YdrVNip+ee&lY|@5Ukj9~U0Q5TZZ&7{~!n=&Uz<Ye~i=XJNrL=eD+0 z6>%U>_OKI-t8{2=Yz*CWVdrzP$EV)yIr0Q^z`;OW@}7ssrIW^)20TY+6I0Ok^){(4 zptE+B;+~*!8hL0(l>fP&)hyk6|MEy3=ZC-R&)fYZHl6YP*Hmt5r3hyA=+4kUWHl*f z)$G-Q@&_BYuZFGte!1}!-$nJ56DE7+FO6ZO4oH)ZrE~367V3I_?QqFyVGN|VVKkq) zy5_O27Z^W3i{Yk@>&xlDnxmRTc1E5$K6MHF(t6+|(518l2{q)~&M8B(Q9&%GS-)WE zzY00rRGr+EkVKi4rJXMS>2UeA>-8J?zg}hx;ok?XdcDMAiyQFGX9T&br<_ezg3Ppb zCc?#Sr~8RI_DTM)Q@|EqMI)xWHp8Gb4uzN>-4oQ=gnePB=sxe;<h)C`@qsSa*y9bB zHkwzih~%5J=122PKJww^YTxKn9P(OiJI0dY+nGugEDDxB<Z-5px|m`%3l!?f6E|{K zSBf}K9dE(bnJ?5|19$&aDGFxO1`G$<N@ju>xYNB8C3JVL>jvM+x*iK1eEX8{-!KBW zk177CON$2_kky3hP-e;2#z)rV_cp9rsOg=y;BIQ+&=|UmtE$Sob>d~B^3Dgmyur+e z%BWT7H$Z9ln-X)^lV!+jYeCxn+(nqQe5q8INk7wbdetlDTvZtw#K6)Z!}+G&lI-n$ z1g}HUrrsLgTUDEY?VrPFVvn9y@3WJjTu|0C&CxH|B0xQ<qXt2SJKuB!##HstX-_xx z9dNW_eOl>l8CLoOIC!E5dHg9(Yj(fmOvp?zZaYqHce40zhs!NtOct?!BQ_Q{9HG{B z4r4q=Vzt%izV3|olR``CSRtipX#YJ`RWDwMsO>0f<efwQBEhPYf@D9Qy#r4CNG9V) z#Z1eKnD>auwtgh`CZRi+t7?k>%^Ch~_QEcYBp3ygQaB>#&Xd;tx)6g<poznkM(Y=x zr^o&rZ9->H5hJV)mvdDWe*N=LLDX{6=J;+;J8rvJ&KvpM_mb}*JzM7B8{VUkRm!Tk z)2;#1Gq6nV3n8>7=GU(`)pjfwnxm7rUt1@zr}>{Z+&N=kFJCOL!NGC`RH2vZ_Bbw` zX7aQPLHI#c^#v_)8&g1H`CX<XCSa-_hm{34f)uD!Jh&=;RYi!8&1YHDdBSUt7snaJ zey=E3gNR_Q;#gJUCzl~rIXjMF4ME)<Zy)miDOV_QqBj}@iI!Gz{khuO=Xv>oJ*f(M zgoqEnlm&NhU2vXX%+LsZR3d?dPIpfU|AL6w4j6G)qhRVff=+j|el0QiT?_~a2xq#l zlgSzA16Ng%LMP?-S#zbc*Bnq{Z(z#lt)%9Fh*wa&J6mg6GW6}8*oJf$M7TH#K<hU% zIBQQ+zo*(msq~zv&9JdGBnGxFr?RXr)lFEi&C1R-lUxu89*cN{Q9I}r$(eihI0jEg zs`b-X3tw%!={W8v*xMW7AwG5*{o=rIJ73S`lJh5^faj9GC+=HvZuXR#mZD<K$igcQ zc;=dmOM95vb|+`R2lu+$W2NTKs}iW52o4!Yb;RVqG10c28E+|~=jBN||6DHcpQ2*0 zJY`=Kw^qRU58y)`3Y)W`Xn&W@qUAT>i*yLrw}~v>kI(J6JVUL+uACbZ7ZrVi$M1Cy z32{4ThkuC*Tb4D;xdQ)u47*2ZVnHicz{P46Huv(ydU_4Ct0v0AQ^;Ws2BF!{&Im2& zyuVqz!69y_7HGx(EvbY4KLz_q;h`8S6)cG}F%UM|*g7tEJSh}%`rm9zMCQ5YL%O#f zWOJT;#H*4!fgMoYX~_?YuHi(dIe75Wa;nREQ*3OuEN6(Vxe0f%(lr$b=lB16OTApV z?ShW1(kaP62^uRsdzWfLnNm75fD<M;D$0}k1yh(K<^g+#9@5gHqH7PTKcGfpp?SA2 zXds#N`^p{I=@O2!fqMaIyR;gI{sfD(EJ70-LGTM63A!4*xR%-2*qE)a<96Nomwk>D z7u7W6={iw$<gxVc2*<6r+oOR2x$4Y;ZVH|XldA%nX=t*=W+U9l;Og7#78ikn*h^{b zGk4qg>`6zc@uzFe4QfV%0)mmq%xJ)zaH&Vr5*>-~TRNtjHL~bX3a&OkC6zX?J?b0b z3SMfr$YzvZK(LqBxgpgsl~%*{`pTK!rPq2|0g@Db3LV|H&ra*<fgtCmIr(qJu-ecu z3JFR`>uAH4micnIvS`WeL}LNRSj?rphc?Mt>-bWC67&Tx4<N#5pfaPgFJk<cdgx)S zRc!2(p?eE{R-2GS|20xM>s+%eI(yEaQ5Pi$a3#P;gpjO(`<Dw{P(`(icPmRyZxb7J zvd5=B9e4n;f_`G4i7lx*MS?RQts+D{QgnSVTQ=l32Ke2jStS%~gEp8w-R`CWHA^m5 z;4(WkuRpf!!3!B<$0hn11P|VPlU(Py8s?m{bNg_co1H@4E%FPG4CnSCjf<)mogRZR z>J(35velH7dYG;u+r3|Z+h^DJpTa}&0K2XSxw=Zj6wZ%_GUo!(11XX^)`&u%zzTi$ zb#*QUq-}}xREA1Kbsz@vgFX40I=Bs~KJ^Pujt@La=4v2kEG!7*^0|;&v~ecDK(4Xz z)J4>ycF5ZN;}2ou1`&&EzGMCEx#l@v@Uuk^%#$S3@Iuqv^Y;qVDCf|UAilrc`~w2O z8FQ?ejdiCe1{DeZi|fMS!$htj%*N$Lr(}`9+2`m6MYr#2kB{kT%e2JDw*5-!uj+1p z&njW?^m8eM#lg^$#u@4&16AHLHjvoV(>HPko#5LedF&(1A2?#17<*SFB0m1gJs-xk ztAVSAP|&x}83<I<L4Q&G_6}*cN2Cr>G%|=mU{rj=x}BjgI`8#xn_KY$OYGyKnKH^G z3??zotW~=2YRmPIN$ib_J;E~%4j?|AjL#;IZ+uhВk;o}2?Z0%9aJ{f2ZP<yMJ z#VcCpm|~;j*zGR(C^rQlEVjGvf?@v^MRRYl0)4E$rTT$+Gpt5MhnjAw()8{joCCm# z?iG%!p<V2A%n{|gIONs%mA{F+`4v2NCpvHv-;!jO-%f8Ja8*AAN4M)C-C?WPvCDU& z5Z7BB=+oBamf;jCQjttXZBf|>cOVD1@Xi8%9(Y@sUgWb3r9({e6Cn#RRKxa~omIH2 zxwu5X+|>SU`xqs-gh@yV4}y9%tL>-1tJ4`HuVIqdXwT=N?2{>fHgjcMJ;baVjCzix zq#Y<V*MgiH)FQhN`a5YG8W}Z?{7{_6etx_mGm$5NZ^4qqu)YMjLoJcT?0s)!C69>l z&Y1gY)dc-ih;F)RzFQT%s}Kc?d-`__o7CF)5B>Q|nqhM*Uhy*SYCNsF?w7v)rsi1V zH)<bd!I8ppPuB_f=Y(X=hh3Pk0&FezjeUtmu0X4+B7}gO5>K;-MdNkdqOI@uh-dSb zx#Xr~1IulGH>W~yZc13AvKwyOmHc4~AoV}3{dyK}x~*V*E{O|Q;l*UwZ4Im^YJxa6 z$GDBRqkJTA*=+P#u}yDikl2e)hIK1`%!*qUIeW5iL+2T{TOAn)B3bn0M9+<PDP|az zh;!!wplTcrDI)wO&eNgcb5e&-buws+jku^rROn93|13Qv-SqoEy}2^L48U`?m%*>Y z%AMs;wqtHSJ}Q1mQ|Ljp*z;I0kD;}((WL^;<D=avl<tJmoo;2PqF`QU;&u5RA8pG; z04!QxzdE$|k>OQ&)F|_Sm-NaT<b|^0CS2>n!dfqieIuklV5h5N%|1fe{xMAGMe8=z zD){i}$&>AQujj=71Uiu7l8}<RcM!vJXbWFgN>!NYiHtv&D?mpQ13@GboI$h!+GbM$ zwc%`NY`C1TJLY^gG-gi9Ba$Ht#5yv*p~AgAgVK5WMCl#BHdBG_<{Hc9Sxd)Jnivi( z*i`3XCpf}suH8K2%A^~0FUk+@s+G{0ju<}6W1WS~&r;0d5)+#MeEa@s+8pI^`P2>E z4DegV{rPnh7teht{zNg)pBSAA)iVnp*pS;<o_gv348-C}HZFhpNPSC~>rKO1(?0~y zSdb8tKJfImvBB{H1G(&TxQUdnV(V5&j$)~`h|Xj_>X-0^m2WdWxH-yDUBCgH-H;Ep z%8xOeS4Fb6tn~>Gh7&Ix!y8ZT{i>?>13PAm)GXuBzg0`BJie1j&4EAxpi4@z>+9=l zt&^E~9_+HwUw5aZ!0+$$@JJ&*nvCFaSPTc5z1~o`3>F{)Y3VBF$ly3VZPYe0-s{4L zVuy^(%*0{NM8)kyq<HVn2thCQ5iX3-I)6C6Q4^lEXhs6h3GF(#+>u~v<KL?z5EFZ( z&z9CyE#D@NjJu58NxLG`fRC`Lb9`!p`pW!Br!_;__hdWjIdZnobfA&5PpNmIRQ9S# zV4+H2pM=~mYSO!@$<m3bPbbT)pA!3#0i&(1AWe7%-1-IxNbwBhs$AK{1n=l1I`x0^ z9_b+%;*hiC&Scd~$Hp;HD;~H3-|0m&QsA7uwswjO>R=ioK}^*w=he?a*R)X)j)v#v zfTc~P#r+Sorr!thNWt*y_s5>$lpkO}dZ*z;KNK@2ak#htAMsnIVoQtLczSB>@L?im z20$YPbjl^a6_bn$uQ9=ok{1Ss!}1z;G>TfuH^tpP`}4EJ$l`aih|RT|4k_tUdP(S{ zBeMGmAm8m^mn$6#ocFBORAmO%vMzx|%J1?V)XEc6+@7aSe$>%^5A+DZ^dSW=Stw+k zGvjlCNj2QBdcbWL1ry!s6X-nTj|15)YVGsfD0MLEcIH&gzcxp8k)P#uJYUq{1)1zI zal^SxwRFh#<i6`S;p-YTmAVy742|ni9FwgX2WXF0#=C=)c2mC6mxl;-gtu41FHMR$ zpx8#F5PHb_0s0W~H8SktZ@v5Ml!koW=bv9zRu)2S_G;yL4^$PiuI_Be{JZ!c`|GR= zpL-W)ozE2jVa|xGNcLT!Rc_J)hjs4DMp?d<Mcco(6VSnEget+p{77?&i3g%>|K(Cj zqrn7j1<rBUTJ{A0^{us)-X486(XivnZ)r!?w54<Vdb}FvYBwd1N@%87)DFLZ&W>(3 zh#}i=PrxAF54a3g2b>)yg}aSM$>bV|SRMA?PpHN_8w3mrV;&I!XaTNjJ^UpGBk*%a z3(K71z|@<~8hqt)?_Wl%EHc#Gds_@`Ymn!+)<$33JN7acmy)D(P`{^{p)aMKP2Fpw z2VnKPS#k41mjLja#6O=1X&SGLCT^3L(1ar6>-O1ED?j)yS&$+|bp;Bhc>RlnaU^v; z`*Mn|;~yo52-P214(IDA<<5GWjAn&<0HvOQk_@Ot9=VytTkZc@`tAf~G|d4Oe=7|( z$vSp=nR~E1Z~SQbTUO&1NGJg{Hv8O60PEbCBsJHV=CG**cEsDR3ChQ|TM+*~AkT6O zVdb^&OT!T?3d(`tw^IAwy7(2@&!|H@B6z9^&>tz8Ib8{&pzD+2Ek?5npkwCnPlR_T z6K?<}V^(BDKHq$a6Flw5;jlunE|s!@l?4R&=CEXk;MAgSf`s0X+6f2Fs`8Eei5{Hd z?g6>Tco2K4PZsU>KPJIBo(6Mh1NYil4Jj=?dV(lQoDt!CY_B%RI@^)E1s)_y5MTJ= zmf8681`nB9p2Mk>`?h0Xj<11%m3BMYf*r6Z5)WhywJQ4z4)#e9uUTd_dsck-AS_W` z`}}3=1VUn$6Qmk}PNLV_R8MO~h;1z--ddl`L^0CitR^m@Z!ceO{WwjCZZ5o8qri3+ zm^$nqyee}_PRA-WymQu?*$JVc2Hwni4!c6$W=EnBA6e#fJ6S=E><`x|>ZZkn-5Gl! zsgp3si)0<WU+Mk081*yJ1gvNL#T>ai9C4vbyjq>p6BM@m^D!X1QZDR@)d=1K;~E0g zVW(w2&+42B(baW?RyngiFh_bKP@wR^C@G|O=E*H0#kKNu5Q4^>kte|bN557AlTcms zv8|rJ33S-j7s@oZTV(5(eRhtY3z~3D#_-ls?yXxW?@H@to{}@>0a90!e9&D&3{qEO z^FBL%|KJIhZvg4^q(xp{-bkQB1Ybo3tLwwgNO1yDu=&Pc4usvgYoiq(d%x1!cV-nE zw$xKB3pu1vQwDlqR+msZHYy0DX0^p1C!bT=fbV7#R5edOacghnnN!Gf0=Ihn)B0wC z8a}d&3Dw%1cecfcT!D<LZSl&zK}$XwWS;7y$#E$mndFqK<l@BYz+YiuVVXw9#w8&R z;4sH_i)=N{;`KUc!n;J9fe%(cn;XQ70=xi!$tc2P*ibl%o6#A;&wwhZ`I%huAeYI= z$c+B8uJ09t!#jA+Q4u)W^zYyvw2@3;QW6ns<wDaFUrcjGp6$m#2Gt&vIsFI}%`y{X z$V&x3y!v+|zSkjcJ4bWYL^^zn{;k_{(x$ja(QYm{j}9%shIZ(B;0B#sCD-iN@P2?s zKp+qc4R9@!<m6<e>_2PZvO!-H>RSdUZEcB24b;kta?vAPbaOAi#8G1W3j7?fql7Q~ zG5z5##Vn&M=anJSRbG>|d{6AE|AjlfB5^^x%SbuoA7xa0nxhf4b|E#jWGoXEF^I|% zJt6!uix_5+)!ZR-u##m29@SIT18IC_^hZ|jV~KEKHzDJE$Z3Db?7{8qPNb=H$9|<^ zCv(*SI&zQ{F5^%etSBi7DkLwO-4c8sleD5rt_AWAw->UkS5)6zr^r`RP>$dw&1Qw~ zWA*juQq|vffv!zFxPww;MR-0xGXj0qvUHs1*y+_&jk&SGAv!N4ru9QNKqMVU_f`Gy zYMjgrKLsq_$djV1vs-HL`Y#YOSu_q@zN;}8v2q6rgqs_lMHR-7O~o)QL8*vHNk}m} z2ZL?vnQMjWGU3y%6;u^oBy#o5TJUn28<eAvO5oy#vn96pmva=N0^?zTJX#XCZM9Za zJupZ#&#}gaCz+crt|1%nZg%PE(W4nhPcU|(!UdXP$9~;!)<1`tOa^<M*6oQ3-(35; zM5#JNke>2cVD$htG>r2j-*>jJ^YU6i<q*~4-+*NCpN{=i59JSgRrUkxp@+@%(4P%x zCrApKP8k3CQgS6VUmqwOBb8A5i*biWAj39no^#JbDIK|6&{1yyd{G=>qrOe|b!_0U zD#kT0-+B65_a=BEP47jsK4q(WbWr}>d9(6MK3Ddn7{PM8gd6}H$eT4YgPa=@&$O>T z4(xi<beFz<o7{Jx@4L@G_ET(eRx&kz%A%=}6x#`T1>7h8XegHvM$Htjt!?W0dT{<{ z@Q447`UXjZt!XYW>57jHT5MKWNJMQaLY5pGJ0w7Xvg%lQYp+1*$q6wzK~Ekcv^wc( zhuaP_OG`_>Ka;o3>Eg~{^J2g!=!?er&ZP15hA*|^wyONcY3uLKfp>RQ-X9JqS~9`r zodqW0^A`)~a7`&wBa~Smlc<%zX1S5c427M6>S$n~)G~|vcWVbdDn~(`aJ{IscKYoT zF&+8Te3}Irf%x$vj|iSAowx%{X@+ES+t&vXrrw5HcEV_0$vhxso3yLJ>S|H23-4&= z4`%W|SBX?_&i_2N(0(gzNuhT0yHHu4eiGuxpZ>isv$tn<LNB3OR7k;IKbfB&xy$rc z{|dx(>+ad_cHRR}q^jMJcOXX8fWjX7JrXm3Pja*WFIX4J*xcNFfv8X$3kq7gBRfi0 zcMF(f5IQqrL$1WOCUs6L=)&f;Q&>{DLI&h)9il<~NvCr_K`z%mc8Gc9rCExL2mmb! ziA^9ITHxSy{!KfpCAsY)0|*eB^c@98G^4<`B3G@-bSOzJz7DJ@T<#c^avaw$p<}u% zIp`sAtdR)Ca3O`TzoccPXRqx@I4GuZmOHZYj_+s`n?-I}_6N8~1I1)B`Be1`bhHg> z4qnkgV{WO%Tb4i!);*m!Hg+YM#zsaB5F}Zh%e-=BC+Kn6@8$R3)ARfOglJN2;9R?9 zi7jhpR3<U>l~0??++{QCfZG5WNl%edc;-_=SVb=Z;eij3z;4Mxm7kZbdDvYsm;QN8 zh^kr%rCm#|q<~3dH$R_zgZLD*Z1bh>@)ZUEbyLzdt_>XtFgFN~Vhj%2h5?TZT$c85 z?=^!*f1eQoOROsb0>AtC<8;o-mj!^|??DzuHqkoIQ|>8dvpovOafsdDqS^#XCZi(_ zCL{B&ZWM3={)O+6y?R-^W$2GtzIUm29gw3F#Spo7A2*PMz&FxMIGi4W*cq_pCG5(L zg{H~Tu7dT;p!5^YD2%ks+Ci{frGO%#%4Pi5D{OJ>rY)g5Wp22(wvk@UiTI~`&*?f( zbHuUJ>cZd+i}cHYpKIFLqPhdX+XU?g%y0T!T8S;z9cN8>?M;g*kA6(?xWf*@n9&*v z1Gp)jy#6z<ybTHh@%<)u#OzaDE}x1gp-{jYw&RQz^70X%U2jpX3iKz<@viWXf9$G_ zQkspE&$Z9#ulXR^cfR?Z!uQ!wEpAHEA^#aCA8l<@fwQZDm935+MET19#bX`xov;<D z4CFM=eZcw4#yD;B^JA@gEzWxT=2)6TVZ7wA`cj>wYzi#&jH~wZEVYp+hV>cm$`V=h zkY+(@Yinymey05z(7xqi%HEv;9i2fqug+RAJm(F(>|`4@jNKSddRp}|E8R@nYC;f4 z90@<<ujlgz!+NIqU0k-T<fItHRcw-<KtB7uh49fG304P##ZJDr7QkDmuaCaggYuTJ zElxCPeB~O>8rDGx;rB0+#cgZ~>3}DM-P$waj}18(0?Zuh5er@n{%4p-WfN$Hw2Ncp zPhU1R1_BuqGrgsHMcoV=tq*MU!11ZZHyS?OwGjvCKPqHkwreU!XNNN_Sk@sKr8+xP zp>}VtDnBMEdPeH1=>&vU7Qa6Wn;WVLFlvuKK9#VskK*CMsB%@@@nIPO_x>(XY>zRd z9tEqrH7{v8#vC4IEq#Ahgkn$UXJ*TyN&i7Mu=u7Dy7p00AkP7Usa0x{85(?|v4K}2 z-?d`BtF$tt<NPk}j*PznbbAk!mV!Kn6wYcxUsDF<37C}5iKztrESt=~Y;_1AtBN;K zu!mfk!7f(r8{0<!6d;JQ+cq_tm?$Zk-GX(zq7!(}BR?$uO<wL{e`QcmAAUGyQ1K&f zX;KRfP70WX+wlAD?l9m7xV^Zdf16klRbGrw$7NGIn0duW>Ef!i(ZM#s$5;>{vf8Ju z%jrqXg!+6TSPp$)_~h8GJ3R<8fa)_vG3nil;PP9baKUoJ#6WPJjDFI_9|MfW&uw51 zpZ0nww~4y~xD~-17Xl2L$+KOvl+p(~dZ1g1LJLw?30Rqdlh!%kb8}xHiQ+Cl5>n9P z^A=geS6aC4$%;z==VMe6(wbpgw$^mdI#B-qr}b?@qG&0*k2}}=!9Q3IwbI>-rCyng zP1#3CAOEP78^ruV^j-KQ<L-Aao2hzQeMh0VbfbY+I3jY=U3b~UR{R%b3H31Ht>LXL ziS@6^GTjF%y;*Rz>shQkty&$^`uZ{LO-{3d^DwFA=EL0;*lZ6G((|=Ib@D#0`9lB; z2{QYa*8-)q>hc66B0w0lQ^A6wc@?8{KY5osbzI^HqBqmh3=v3EP#9-1=k#*Ao;XPL z9Q5Z&Sm&m!6iJViOtRa7X$m=PN<)P1J%e{^e_w(J)~%a)O~^5s7%+n*`K?%koO9@% zyoXWJqlY-@Db3!!t_C%UrD(4rYLzt(qD^OkO-^-uyzOlnUi~ke>$?gBCq-QtZSoDC zHURDoE(LVx?@~{=xeZS~h>5-Hjz1_Uz>OJo7IOmzK5X%8lP|3+>=azdlhs?l3l00w z&{$(2zhcd$!4%kOO<G#^7j=5~QQX2JXN?=qZ)3ys6j44<an0`bXaHRJD6W>RZe(oO zwd%<ritlWvqbJa+xaSr{g1sen?Y;29xLBv3#n%EgAQn<*OY_h10z9CLHMce^RFKOx zmuCq@G59>_m(|-1s>gH3Jq_7hr+$oHOGMdz)6(21$H5M4i<M5!mfaX);t`W0(M%z8 zKnBy7KF%ZW#-82fiz17E%i_Jj-E&wAK19H#rIu(HQP6`&91#inH?xRC;nrBKpm|5z z5AzES$kvukx=TdD&eS72B|G*D^A#ESZ6|iy;D)XiD4C{O*v(D3a{50+)+Nd8ZFG)0 zsW+_lmv+@oSBQh&qid_tSA*L6*qM9Q5(X@(lvtwGVUz^+go$SN!qez?df^k-aHmI( z62lmS_b_U>=b*?Z$l~7_#ZeeIr<2Ku1foOuGcfh~b}g-hOKC~j{Fv2|fmlI)e^%Am zX41ewOBBQ7BmLjF{ZQf5&KT4e+cOc&I?8JbAN=q_LBZ}%Kv)HIA0l*nk73l3e6Bbl zlMOq>F|n-oD-h0_&KDX1<%9UIyM~qV1gK~I5ne=*Gs-{?O3G?|6&-3Lq$1W=(u}p! z@7>R`N%U5}m1V<bnS-RIIm#En(1CBNO=~vr2EgCPL8qFmS-TO0>JHS)rq1J)dw6hB zH(FE~J^^F|6_EE6_)MR;5tC**`jF1X9mSspY2m%2gA2GuPz<ane-NSxC1r48J{>Ak zZnsD$NLPI>$QC=CKAB!+UHk#b)+GU3+63r-n~UTFCE5frIkOb}pa8%BW25$Bg-k%| z@@8U8T3r#{Y;tJbtnrW_IH3DaGXV^lu&HMZ{xj?t0^pM{`bPW*)K-Lm4qq{{NT|?f z`5JCRr3mF_D$wbJ8!g5SgRo%S_~}ytfEo*iED*bQhJva&j=VPTln{uj8zuy>N|k+v zX3q~yMftR;f^!hw!(K|GgZKuOa1Rpv9^(n)--Z3gZO7G946Liw2Dj9jjvM*-nWyGB zt_53Gb$Ut{P`G%~HDyUZD_x?O9{RF+N2}^L<a&$55;$ux0!pVU$k{iAyFMo9JP^~{ zTUS)8u7*Q3L&&v-Pa1D-lG{xu{DRZ{f=@A?7<K?vPouX55PAV-fup?xNStzSPo>cs zDZP=F7i84S7a1I4`z~uXfAx_6o*<u<yUaEUah+l5(7<LfLz4rF4k~ABl@;IXH|`P* zkMhyzkB=R?O+gYVfovKZf(4yV{Dy-kf3HTYJt#zl?FfsjH2IoPWE!m(@ObcA77WFt zFc%=hr_GdxzVae=CxD`DxwqixgpWTsR+WNR3&yq7e8II)R_JZZgR!wdPn?-06klpx zR1lN$83hi5F3sKBb!(1N$EUdG2Me2?ZfFnC{K7-%5VB(PFrmtI1BkvOUlnTWU+X1~ zJeG)<GVC#u`-Tiv9rFg~B+<61onjJ+FQ%vadInDt1L<fxMa7G%SMVNBJw0GM3z*Mi Zo7}0F{F7;{vR%r)sbj2Na^3Nd{{#BXb*caW literal 0 HcmV?d00001 diff --git a/ethercat_driver_ros2/sphinx/index.rst b/ethercat_driver_ros2/sphinx/index.rst new file mode 100644 index 0000000..fb30737 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/index.rst @@ -0,0 +1,35 @@ +EtherCAT Driver ROS2 Stack +========================== + +`EtherCAT <https://www.ethercat.org/default.htm>`_ provides applications with the capacity of reliable, real-time communication between systems and is therefore a common industrial standard. In order to simplify the development/deployment of new application using EtherCAT modules, this stack allows to combine them with `ros2_control <https://github.com/ros-controls/ros2_control>`_. This driver proposes a generic ways to parametrize and assemble Hardware Interfaces based on EtherCAT modules that can be defined using parameter files. + +**Project GitHub repository:** `ethercat_driver_ros2 <https://github.com/ICube-Robotics/ethercat_driver_ros2>`_ + +.. toctree:: + :maxdepth: 1 + :caption: Quickstart + :glob: + + quickstart/installation + quickstart/configuration + quickstart/usage + +.. toctree:: + :maxdepth: 1 + :caption: User Guide + :glob: + + user_guide/config_generic_slave + user_guide/config_cia402_drive + user_guide/config_use_case_motor_with_gear_box + user_guide/sdo_async_com + +.. toctree:: + :maxdepth: 1 + :caption: Developer Guide + :glob: + + developer_guide/coe + developer_guide/cia402_drive + developer_guide/new_plugin + API Reference <https://ICube-Robotics.github.io/ethercat_driver_ros2/api/> diff --git a/ethercat_driver_ros2/sphinx/make.bat b/ethercat_driver_ros2/sphinx/make.bat new file mode 100755 index 0000000..8084272 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/make.bat @@ -0,0 +1,35 @@ +@ECHO OFF + +pushd %~dp0 + +REM Command file for Sphinx documentation + +if "%SPHINXBUILD%" == "" ( + set SPHINXBUILD=sphinx-build +) +set SOURCEDIR=. +set BUILDDIR=_build + +if "%1" == "" goto help + +%SPHINXBUILD% >NUL 2>NUL +if errorlevel 9009 ( + echo. + echo.The 'sphinx-build' command was not found. Make sure you have Sphinx + echo.installed, then set the SPHINXBUILD environment variable to point + echo.to the full path of the 'sphinx-build' executable. Alternatively you + echo.may add the Sphinx directory to PATH. + echo. + echo.If you don't have Sphinx installed, grab it from + echo.https://www.sphinx-doc.org/ + exit /b 1 +) + +%SPHINXBUILD% -M %1 %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% +goto end + +:help +%SPHINXBUILD% -M help %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% + +:end +popd diff --git a/ethercat_driver_ros2/sphinx/quickstart/configuration.rst b/ethercat_driver_ros2/sphinx/quickstart/configuration.rst new file mode 100644 index 0000000..5c7153e --- /dev/null +++ b/ethercat_driver_ros2/sphinx/quickstart/configuration.rst @@ -0,0 +1,74 @@ +Configuration +============= + +Hardware Interfaces and EtherCAT Master +--------------------------------------- + +The EtherCAT Driver is designed in such a way that each EtherCAT Master is defined in :code:`ros2_control` as a specific Hardware Interface. This is done in the :code:`ros2_control` description file, where the EtherCAT driver is loaded as Hardware Interface and linked to an EtherCAT Master by its ID: + +.. code-block:: xml + + <ros2_control name="mySystem" type="system"> + <hardware> + <plugin>ethercat_driver/EthercatDriver</plugin> + <param name="master_id">0</param> + <param name="control_frequency">100</param> + </hardware> + </ros2_control> + +.. note:: As in the current implementation of :code:`ros2_control` there is no information about the system update frequency, it needs to be passed here as parameter. This is only needed by systems that include EtherCAT modules that use the Distributed Clock. + +EtherCAT Slave modules as Plugins +--------------------------------- + +In this driver, the EtherCAT Slave modules are defined as `Plugins <https://docs.ros.org/en/foxy/Tutorials/Pluginlib.html>`_ and can be parametrized in the :code:`ros2_control` description file : + +.. code-block:: xml + + <ec_module name="ECModule"> + <plugin>ethercat_plugins/ECModule</plugin> + <param name="alias">0</param> + <param name="position">1</param> + </ec_module> + +.. note:: All modules have :code:`alias` and :code:`position` parameters that specify their address in the EtherCAT Bus topology. Additional parameters can be specified depending on the purpose of the module. + +EtherCAT Slave module plugins come in two version: + +* **Generic plugins** : generic module implementation configured using a configuration file which purpose is to facilitate the use of generally available devices. For most applications, the use of these plugins is encouraged. +* **Specific plugins** : specific implementations for dedicated devices or dedicated functionalities. + +Creating components with EtherCAT Slave modules +----------------------------------------------- + +In :code:`ros2_control` the access to resources within a system from a controller is done by means of `Hardware Resources <https://github.com/ros-controls/roadmap/blob/master/design_drafts/hardware_access.md>`_. For this purpose :code:`state_interface` and :code:`command_interface` tags need to be defined and associated with the module functionalities. +Also, for better understanding of the overall system, the purpose of the used modules need to be clearly identified and sorted into the following types: + +* :code:`<joint>`: logical component actuated by at least one actuator with read-write capacity. +* :code:`<sensor>`: logical component to read-only states from system. +* :code:`<gpio>`: logical component for general purpose IO systems. + +Here is an example of a :code:`gpio` resource built using 2 EtherCAT IO modules: + +.. code-block:: xml + + <gpio name="myGPIO"> + <command_interface name="dig_output.1"/> + <command_interface name="dig_output.2"/> + <state_interface name="ana_input.1"/> + <state_interface name="ana_input.2"/> + <ec_module name="EL3104"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">0</param> + <param name="slave_config">/path/to/EL3104_slave_config.yaml</param> + </ec_module> + <ec_module name="EL2008"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">1</param> + <param name="slave_config">/path/to/EL2008_slave_config.yaml</param> + </ec_module> + </gpio> + +.. note:: To send commands to :code:`gpio` resources, a generic controller was developed and can be found on this `branch <https://github.com/mcbed/ros2_controllers/tree/gpio_controllers_only>`_. diff --git a/ethercat_driver_ros2/sphinx/quickstart/installation.rst b/ethercat_driver_ros2/sphinx/quickstart/installation.rst new file mode 100644 index 0000000..504b845 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/quickstart/installation.rst @@ -0,0 +1,189 @@ +Installation +=============================== + +**Required setup : Ubuntu 22.04 LTS** + +Installing EtherLab +------------------- +The proposed development builds upon the `IgH EtherCAT Master <https://etherlab.org/en/ethercat/>`_. +Installation steps are summarized here: + +* Verify that you can run unsigned kernel modules + +Etherlab is a kernel module that is not signed by default. +To allow the kernel to load unsigned modules, you need to disable secure boot. + +Verify if secure boot is enabled (you need to install ''mokutil'' first): + .. code-block:: console + + $ sudo apt-get install mokutil + $ mokutil --sb-state + +it should print: + .. code-block:: console + + SecureBoot disabled + +if it prints: + .. code-block:: console + + SecureBoot enabled + +Then you need to disable secure boot. +To do so: + + 1. reboot your computer and enter the BIOS settings. + 2. In the security tab, disable secure boot. + 3. Save and exit. + +* Install required tools: + + .. code-block:: console + + $ sudo apt-get update + $ sudo apt-get upgrade + $ sudo apt-get install git autoconf libtool pkg-config make build-essential net-tools + +* Setup sources for the EtherCAT Master: + + .. code-block:: console + + $ git clone https://gitlab.com/etherlab.org/ethercat.git + $ cd ethercat + $ git checkout stable-1.5 + $ sudo rm /usr/bin/ethercat + $ sudo rm /etc/init.d/ethercat + $ ./bootstrap # to create the configure script + +* Configure, build and install libs and kernel modules: + + .. code-block:: console + + $ ./configure --prefix=/usr/local/etherlab --disable-8139too --disable-eoe --enable-generic + + $ make all modules + $ sudo make modules_install install + $ sudo depmod + +* Configure system: + + .. code-block:: console + + $ sudo ln -s /usr/local/etherlab/bin/ethercat /usr/bin/ + $ sudo ln -s /usr/local/etherlab/etc/init.d/ethercat /etc/init.d/ethercat + $ sudo mkdir -p /etc/sysconfig + $ sudo cp /usr/local/etherlab/etc/sysconfig/ethercat /etc/sysconfig/ethercat + + .. note:: + + These 4 steps may be needed every time the Linux kernel is updated. + Before re-doing the 4 steps, you can try the following lighter steps: + + Go in the folder where the ethercat project was cloned, from step 2 (Setup sources) do: + + .. code-block:: console + + cd ethercat + sudo rm /usr/bin/ethercat /etc/init.d/ethercat + ./bootstrap + + Do integrally step 3 (Configure, build and install ...) + From Step 4 (Configure system) + + .. code-block:: console + + sudo ln -s /usr/local/etherlab/bin/ethercat /usr/bin/ + sudo ln -s /usr/local/etherlab/etc/init.d/ethercat /etc/init.d/ethercat + + +* Create a new :code:`udev` rule: + + .. code-block:: console + + $ sudo gedit /etc/udev/rules.d/99-EtherCAT.rules + + containing: + + .. code-block:: console + + KERNEL=="EtherCAT[0-9]*", MODE="0666" + + +* Configure the network adapter for EtherCAT: + + .. code-block:: console + + $ sudo gedit /etc/sysconfig/ethercat + + In the configuration file specify the mac address of the network card to be used and its driver + + .. code-block:: console + + MASTER0_DEVICE="ff:ff:ff:ff:ff:ff" # mac address + DEVICE_MODULES="generic" + +Now you can start the EtherCAT master: + +.. code-block:: console + + $ sudo /etc/init.d/ethercat start + +it should print + +.. code-block:: console + + Starting EtherCAT master 1.5.2 done + + +You can check connected slaves: + +.. code-block:: console + + $ ethercat slaves + +It should print information of connected slave device: + +.. code-block:: console + + <id> <alias>:<position> <device_state> + <device_name> + +Example: + +.. code-block:: console + + 0 0:0 PREOP + <device_0_name> + 0 0:1 PREOP + <device_1_name> + +Building :code:`ethercat_driver_ros2` +------------------------------------- + +1. Install ROS2 packages. The current development is based of :code:`ros2 humble`. Installation steps are described in the `ROS2 Humble Documentation <https://docs.ros.org/en/humble/Installation.html>`_. +2. Source your ROS2` environment: + + .. code-block:: console + + source /opt/ros/humble/setup.bash + + .. note:: The ROS2 environment needs to be sources in every used terminal. If only one distribution of ROS2 is used, it can be added to the :code:`~/.bashrc` file. + +3. Install :code:`colcon` and its extensions : + + .. code-block:: console + + sudo apt install python3-colcon-common-extensions + +4. Create a new ROS2 workspace: + + .. code-block:: console + + mkdir ~/ros2_ws/src + +5. Pull relevant packages, install dependencies, compile, and source the workspace by using: + + .. code-block:: console + + cd ~/ros2_ws + git clone https://github.com/ICube-Robotics/ethercat_driver_ros2.git src/ethercat_driver_ros2 + rosdep install --ignore-src --from-paths . -y -r + colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release --symlink-install + source install/setup.bash diff --git a/ethercat_driver_ros2/sphinx/quickstart/usage.rst b/ethercat_driver_ros2/sphinx/quickstart/usage.rst new file mode 100644 index 0000000..e1605b3 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/quickstart/usage.rst @@ -0,0 +1,40 @@ +Usage +===== + +Start EtherCAT Master +--------------------- + +First start the EtherCAT Master + +.. code-block:: console + + $ sudo /etc/init.d/ethercat start + +it should print + +.. code-block:: console + + Starting EtherCAT master 1.5.2 done + +You can check connected slaves: + +.. code-block:: console + + $ ethercat slaves + +It should print information of connected slave device: + +.. code-block:: console + + <id> <alias>:<position> <device_state> + <device_name> + +.. note:: If nothing is displayed or some slave modules are missing, it means that your EtherCAT Master is either not well configured, or that the connection on your field-bus is interrupted. + +Launch configuration +-------------------- + +Once the EtherCAT Master is running you can go on and launch your configuration package. + +.. code-block:: console + + $ ros2 launch [package] [launchfile] diff --git a/ethercat_driver_ros2/sphinx/user_guide/config_cia402_drive.rst b/ethercat_driver_ros2/sphinx/user_guide/config_cia402_drive.rst new file mode 100644 index 0000000..5a6f18a --- /dev/null +++ b/ethercat_driver_ros2/sphinx/user_guide/config_cia402_drive.rst @@ -0,0 +1,125 @@ +CiA402 EtherCAT Motor Drive configuration +========================================= + +The generic plugin :code:`EcCiA402Drive` is a particular case of the :code:`GenericEcSlave` enabling features compliant with the CiA402 (“CANopen device profile for drives and motion controlâ€) norm. Therefore, the configuration of such a drive uses the same formalism for the :code:`slave_config` file as in the case of the :code:`GenericEcSlave`. + +Plugin features +--------------- + +* **Drive State transitions**: Management of the motor drive states and their transitions. +* **Drive Fault reset**: Management of the motor drive fault reset using :code:`command_interface` "reset_fault". +* **Mode of Operation**: Management of multiple cyclic modes of operation : position (8), velocity (9), effort (10) and homing (6) with the possibility of switch between them. +* **Default position**: Management of the target position when not controlled. + +Configuration options +--------------------- + +In addition to the configuration options given by the :code:`GenericEcSlave`, the :code:`EcCiA402Drive` allows to configure the following options in the :code:`slave_config` file: + +.. list-table:: + :widths: 15 35 + :header-rows: 1 + + * - Configuration flag + - Description + * - :code:`auto_fault_reset` + - if set to :code:`true` the drive performs automatic fault reset; if set to :code:`false`, fault reset is only performed on rising edge (0 -> 1) command on the :code:`command_interface` "reset_fault". + +Behavior +-------- +Here are some remarks about the implemented motor drive behavior logic. + +After launching the well-configured drive, by default and without fault, motor drive module is brought automatically into the state :code:`OPERATION_ENABLED` making it ready for use. Automatic transition is only enabled when the :code:`control_word` command interface is either missing or set to :code:`NaN` making it possible for the user to take control over the motor drive's state machine by sending corresponding state transition values using the :code:`control_word` command interface. + +The default mode of operation of the motor drive can be set either in the configuration yaml file as the default value of the corresponding PDO channel or in urdf using the :code:`mode_of_operation` parameter of the the :code:`EcCiA402Drive`. If both are set, the urdf parameter value overrides the default one from the configuration yaml file. + +In order to prevent unwanted movements of the motor, if uncontrolled, the default target position that is send to the drive in all modes of operation is always the last read position. That is why, it is important to send :code:`NaN` in the position command interface when not controlling the motor position. This applies especially for cases when switching between modes. + +Usage +----- + +Example configuration for the Maxon EPOS3 motor dive: + +.. code-block:: yaml + :linenos: + + # Configuration file for Maxon EPOS3 drive + vendor_id: 0x000000fb + product_id: 0x64400000 + assign_activate: 0x0300 # DC Synch register + auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault" + sdo: # sdo data to be transferred at drive startup + - {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms + - {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s + rpdo: # RxPDO = receive PDO Mapping + - index: 0x1603 + channels: + - {index: 0x6040, sub_index: 0, type: uint16, default: 0} # Control word + - { + index: 0x607a, + sub_index: 0, + type: int32, + command_interface: position, + default: .nan} # Target position + - {index: 0x60ff, sub_index: 0, type: int32, default: 0} # Target velocity + - {index: 0x6071, sub_index: 0, type: int16, default: 0} # Target torque + - {index: 0x60b0, sub_index: 0, type: int32, default: 0} # Offset position + - {index: 0x60b1, sub_index: 0, type: int32, default: 0} # Offset velocity + - {index: 0x60b2, sub_index: 0, type: int16, default: 0} # Offset torque + - {index: 0x6060, sub_index: 0, type: int8, default: 8} # Mode of operation + - {index: 0x2078, sub_index: 1, type: uint16, default: 0} # Digital Output Functionalities + - {index: 0x60b8, sub_index: 0, type: uint16, default: 0} # Touch Probe Function + tpdo: # TxPDO = transmit PDO Mapping + - index: 0x1a03 + channels: + - {index: 0x6041, sub_index: 0, type: uint16} # Status word + - { + index: 0x6064, + sub_index: 0, + type: int32, + state_interface: position + } # Position actual value + - { + index: 0x606c, + sub_index: 0, + type: int32, + state_interface: velocity + } # Velocity actual value + - { + index: 0x6077, + sub_index: 0, + type: int16, + state_interface: effort + } # Torque actual value + - {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display + - {index: 0x2071, sub_index: 1, type: int16} # Digital Input Functionalities State + - {index: 0x60b9, sub_index: 0, type: int16} # Touch Probe Status + - {index: 0x60ba, sub_index: 0, type: int32} # Touch Probe Position 1 Positive Value + - {index: 0x60bb, sub_index: 0, type: int32} # Touch Probe Position 1 Negative Value + +This configuration can be used for controlling a :code:`joint` component. Here is an example urdf for :code:`ros2_control` using this configuration together with the :code:`EcCiA402Drive` plugin: + +.. code-block:: xml + + <ros2_control name="ec_single_axis" type="system"> + <hardware> + <plugin>ethercat_driver/EthercatDriver</plugin> + <param name="master_id">0</param> + <param name="control_frequency">100</param> + </hardware> + + <joint name="joint_0"> + <state_interface name="position"/> + <state_interface name="velocity"/> + <state_interface name="effort"/> + <command_interface name="position"/> + <command_interface name="reset_fault"/> + <ec_module name="MAXON"> + <plugin>ethercat_generic_plugins/EcCiA402Drive</plugin> + <param name="alias">0</param> + <param name="position">0</param> + <param name="mode_of_operation">8</param> + <param name="slave_config">/path/to/maxon.yaml</param> + </ec_module> + </joint> + </ros2_control> diff --git a/ethercat_driver_ros2/sphinx/user_guide/config_generic_slave.rst b/ethercat_driver_ros2/sphinx/user_guide/config_generic_slave.rst new file mode 100644 index 0000000..51a4ce0 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/user_guide/config_generic_slave.rst @@ -0,0 +1,238 @@ +Generic EtherCAT Slave configuration +==================================== + +Configuration options +--------------------- + +The :code:`GenericEcSlave` allows to configure the following options in the :code:`slave_config` file: + +.. list-table:: + :widths: 15 35 + :header-rows: 1 + + * - Configuration flag + - Description + * - :code:`vendor_id` + - Vendor identification number in hexadecimal format :code:`0x...`. + * - :code:`product_id` + - Product identification number in hexadecimal format :code:`0x...`. + * - :code:`assign_activate` + - Distributed Clock Synchronization register in hexadecimal format :code:`0x...`. If not used remove or set to :code:`0x00`. + * - :code:`sdo` + - SDO data to be transferred at drive startup for configuration purposes. + * - :code:`tpdo` + - Transmit PDO mapping configuration. + * - :code:`rpdo` + - Receive PDO mapping configuration. + * - :code:`sm` + - Sync Manager configuration. + +SDO configuration +~~~~~~~~~~~~~~~~~ + +Service Data Objects (SDO) are used to setup the module at startup. This is done only one during the activation phase. +Each SDO has the following configuration flags: + +.. list-table:: + :widths: 15 35 + :header-rows: 1 + + * - SDO flag + - Description + * - :code:`index` + - SDO index in hexadecimal format :code:`0x...`. + * - :code:`sub_index` + - SDO sub-index in hexadecimal format :code:`0x...`. + * - :code:`type` + - SDO data type. Possible types: :code:`bool`, :code:`uint8`, :code:`int8`, :code:`uint16`, :code:`int16`, :code:`uint32`, :code:`uint32`, :code:`uint64`, :code:`uint64`, :code:`bitN` with N the number of bits required. + * - :code:`value` + - Value to be transferred to the module. + +PDO mapping configuration +~~~~~~~~~~~~~~~~~~~~~~~~~ + +The :code:`tpdo` and :code:`rpdo` Process Data Object (PDO) mapping configurations can be composed of multiple PDO mappings. +Each PDO mapping requires to specify its register :code:`index` and the configuration of the PDO Channels it is composed of. + +PDO channel configuration +~~~~~~~~~~~~~~~~~~~~~~~~~ + +Each PDO Channel has the following configuration flags: + +.. list-table:: + :widths: 15 35 + :header-rows: 1 + + * - PDO Channel flag + - Description + * - :code:`index` + - Channel index in hexadecimal format :code:`0x...`. + * - :code:`sub_index` + - Channel sub-index in hexadecimal format :code:`0x...`. + * - :code:`type` + - Channel data type. Possible types: :code:`bool`, :code:`uint8`, :code:`int8`, :code:`uint16`, :code:`int16`, :code:`uint32`, :code:`uint32`, :code:`uint64`, :code:`uint64`, :code:`bitN` with N the number of bits required. + * - :code:`command_interface` + - **Only for** :code:`rpdo`. Name of the command interface to be used inside :code:`ros2_control`. + * - :code:`state_interface` + - **Only for** :code:`tpdo`. Name of the state interface to be used inside :code:`ros2_control`. + * - :code:`default` + - **Only for** :code:`rpdo`. Default value to be sent if data received on the command interface is :code:`NaN`. + * - :code:`mask` + - Data mask, to be used with :code:`type` = :code:`bool`. + * - :code:`factor` + - Data conversion factor/scale (:code:`type` : :code:`double`). + * - :code:`offset` + - Data offset term (:code:`type` : :code:`double`). + + +.. warning:: For each channel, tags :code:`index`, :code:`sub_index` and :code:`type` are **mandatory** even if the channel is not used in order to fill the data layout expected by the module. All other tags can remain unset. +.. note:: Data type :code:`bitN` is used for gaps in the config. Refer to module manual if required. +.. note:: Data type :code:`bool` requires the use of the :code:`mask` option as the registers can only be read as a multiple of 8 bits. + +.. note:: + + Data (d) can be modified using the optional :code:`factor` (f) and :code:`offset` (o) parameters following a linear relation: :math:`d \longrightarrow f\times d + o`. Default value are :math:`f=1` and :math:`o=0`. It is particularly useful for: + + - scaling analog values to physical units, + - take into account calibration offsets, + - convert between different units, + - take into account transmission parameters like gear reduction or screw lead for motor control. + +Sync Manager Configuration +~~~~~~~~~~~~~~~~~~~~~~~~~~ + +A SyncManager protects a DPRAM area from simultaneous access and thus ensures data consistency. For more information, refer to the `Synch Manager EtherCAT documentation <https://infosys.beckhoff.com/english.php?content=../content/1033/tc3_io_intro/4981170059.html&id=>`_. +Sync Manager can be configured with the following options: + +.. list-table:: + :widths: 15 35 + :header-rows: 1 + + * - Sync Manager flag + - Description + * - :code:`index` + - Sync Manager index. + * - :code:`type` + - Sync Manager type. Can be either :code:`output` or :code:`input`. + * - :code:`pdo` + - PDO to be mapped on the Sync Manager. Can be :code:`rpdo`, :code:`tpdo` or :code:`~` if empty. + * - :code:`watchdog` + - Enables Sync Manager Watchdog. Can be :code:`disable` or :code:`enable`. + +.. note:: If :code:`sm` is not specified, the default Sync Manager configuration is : + + .. code-block:: yaml + + sm: # Sync Manager + - {index: 0, type: output, pdo: ~, watchdog: disable} + - {index: 1, type: input, pdo: ~, watchdog: disable} + - {index: 2, type: output, pdo: rpdo, watchdog: enable} + - {index: 3, type: input, pdo: tpdo, watchdog: disable} + +Usage +----- + +Example configuration for the Beckhoff EL3104 analog input module: + +.. code-block:: yaml + + # Configuration file for Beckhoff EL3104 + vendor_id: 0x00000002 + product_id: 0x0c1e3052 + tpdo: # TxPDO + - index: 0x1a00 + channels: + - {index: 0x3101, sub_index: 1, type: uint8} + - { + index: 0x3101, + sub_index: 2, + type: int16, + state_interface: analog_input.1, + factor: 0.000305185 + } + - index: 0x1a01 + channels: + - {index: 0x3102, sub_index: 1, type: uint8} + - { + index: 0x3102, + sub_index: 2, + type: int16, + state_interface: analog_input.2, + factor: 0.000305185 + } + sm: # Sync Manager + - {index: 0, type: output, pdo: ~, watchdog: disable} + - {index: 1, type: input, pdo: ~, watchdog: disable} + - {index: 2, type: output, pdo: ~, watchdog: disable} + - {index: 3, type: input, pdo: tpdo, watchdog: disable} + +Example configuration for the Beckhoff EL2008 digital output module using data type :code:`bool` with :code:`mask`: + +.. code-block:: yaml + + # Configuration file for Beckhoff EL2008 + vendor_id: 0x00000002 + product_id: 0x07d83052 + rpdo: # RxPDO + - index: 0x1a00 + channels: + - {index: 0x6000, sub_index: 1, type: bool, mask: 1, command_interface: d_output.1} + - index: 0x1a01 + channels: + - {index: 0x6010, sub_index: 1, type: bool} + - index: 0x1a02 + channels: + - {index: 0x6020, sub_index: 1, type: bool} + - index: 0x1a03 + channels: + - {index: 0x6030, sub_index: 1, type: bool, mask: 8, command_interface: d_output.4} + - index: 0x1a04 + channels: + - {index: 0x6040, sub_index: 1, type: bool} + - index: 0x1a05 + channels: + - {index: 0x6050, sub_index: 1, type: bool} + - index: 0x1a06 + channels: + - {index: 0x6060, sub_index: 1, type: bool} + - index: 0x1a07 + channels: + - {index: 0x6070, sub_index: 1, type: bool} + sm: # Sync Manager + - {index: 0, type: output, pdo: rpdo, watchdog: enable} + +.. note:: In this configuration only digital output 1 and 4 will be used and are therefore configured. The other channels are set up with the mandatory tags :code:`index`, :code:`sub_index` and :code:`type` to fill the data layout expected by the module. + +This configuration can be used for controlling a :code:`gpio` component. Here is an example urdf for :code:`ros2_control` using this configuration together with the :code:`GenericEcSlave` plugin: + +.. code-block:: xml + + <ros2_control name="ec_single_gpio" type="system"> + <hardware> + <plugin>ethercat_driver/EthercatDriver</plugin> + <param name="master_id">0</param> + <param name="control_frequency">100</param> + </hardware> + + <gpio name="gpio_0"> + <state_interface name="analog_input.1"/> + <state_interface name="analog_input.2"/> + <ec_module name="EL3104"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">0</param> + <param name="slave_config">/path/to/EL3104_slave_config.yaml</param> + </ec_module> + </gpio> + + <gpio name="gpio_1"> + <command_interface name="d_output.1"/> + <command_interface name="d_output.4"/> + <ec_module name="EL2008"> + <plugin>ethercat_generic_plugins/GenericEcSlave</plugin> + <param name="alias">0</param> + <param name="position">1</param> + <param name="slave_config">/path/to/EL2008_slave_config.yaml</param> + </ec_module> + </gpio> + </ros2_control> diff --git a/ethercat_driver_ros2/sphinx/user_guide/config_use_case_motor_with_gear_box.rst b/ethercat_driver_ros2/sphinx/user_guide/config_use_case_motor_with_gear_box.rst new file mode 100644 index 0000000..ced552d --- /dev/null +++ b/ethercat_driver_ros2/sphinx/user_guide/config_use_case_motor_with_gear_box.rst @@ -0,0 +1,286 @@ +Case study: motor coupled to a gearbox and a transmission screw with an encoder +=============================================================================== + +This case study is a simple example to show how to set up the config of the :code:`EcCiA402Drive` generic plugin to take into account transmission parameters and encoder parameters. + +System configuration +-------------------- + +The system is composed of a motor coupled to a transmission line (a gearbox and a transmission screw) whose rotation is measured by an encoder. + + +Transmission configuration +~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The transmission is composed of a motor, a gearbox, and a transmission screw (lead screw with ball bearing for zero friction) with the following characteristics: + +- gearbox with gear ratio, reduction absolute value: 57/13 (:math:`r \triangleq \frac{13}{57}`) +- gearbox maximum efficiency: 0.84 (:math:`\eta_g \triangleq 0.84`) +- lead screw with lead: 1 mm (:math:`l \triangleq 1 mm`) + +Encoder configuration +~~~~~~~~~~~~~~~~~~~~~ + +The encoder has the following characteristics: + +- Resolution (number of pulses/revolution): 500 CPR +- Encoder type: quadrature encoder +- Digital resolution (number of counts/revolution): :math:`\text{C} \triangleq 500\times 4 = 2000` + +Convert state values +-------------------- + +The drive will transmit the following state values: + +- :code:`position` in :math:`\text{counts}` or :math:`c` +- :code:`velocity` in :math:`\theta` (revolutions per minute) +- :code:`torque` (:math:`T_i`) in :math:`\text{mNm}` (torque of the motor at the input of the gearbox) + +We would like to have the following state values: + +- :code:`position` (:math:`d`) in :math:`\text{m}` +- :code:`velocity` (:math:`v`) in :math:`\text{m/s}` +- :code:`force` (:math:`F_o`) in :math:`\text{mN}` (Force of the lead screw) + +This is the configuration part of the tpdo of the :code:`EcCiA402Drive` plugin and corresponding to the :code:`state_interface` in ROS2 control terminology. + + +Linear displacement per count of the encoder +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +The motor has a reductor so each revolution of the motor does not correspond to a revolution of the system. +It is necessary to first compute the rotation of the shaft at the output of the gearbox. + + * reduction absolute value is :math:`r \triangleq \frac{13}{57}` + +So for 57 revolutions of the motor, the shaft will only turn 13 times. So the motor has to turn approximately 4.4 times to make the system turn once. + +The lead of the screw is defined as the linear distance traveled per rotation of the screw and in this case is :math:`1mm`. + +The encoder reports :math:`C \triangleq 2000` counts per revolution (CPR) so 2000 counts per revolution of the shaft, so an angular resolution of :math:`\frac{360}{2000} = 0.18^{\circ}`. + +Let :math:`d` be the linear displacement in meters, :math:`r` the reduction absolute value, :math:`l` the lead of the screw in meters and :math:`C` the counts per revolution of the encoder and :math:`c` the value of the encoder. +Then, a count :math:`c` of the encoder corresponds to a linear displacement :math:`d` of + +.. math:: + + \begin{eqnarray} + c ~~\text{(in counts)} \longrightarrow d & = & r \times l \times \frac{c}{C} ~~\text{m}\\ + & = & \frac{13}{57} \times 10^{-3} \frac{c}{2000} ~~\text{m}\\ + & \approx & 0.000000114 \times c ~~\text{m} + \end{eqnarray} + + +The conversion factor is more precisely :math:`0.11403508771929824 \times 10^{-6}`. +So the displacement resolution, the displacement corresponding to one count of the encoder, is approximately :math:`0.114 µm`. + + +The tpdo part of the configuration of the :code:`EcCiA402Drive` plugin will then be set up with the following values: + +.. code-block:: yaml + + tpdo: # TxPDO = transmit PDO Mapping, slave (out) to master (in) (MISO), state values transmitted by the drive to ROS2 control + - index: 0x1a03 + channels: + - { + index: 0x6064, + sub_index: 0, + type: int32, + state_interface: position, + factor: 0.11403508771929824e-6, + offset: 0 + } # Position actual value + +Convert velocity in :math:`\text{m/s}` from :math:`\text{rpm}` +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +If the motor moves at a velocity of :math:`\theta` RPM, then the linear velocity :math:`v` in :math:`\text{m/s}` of the system is given by: + +.. math:: + + \begin{eqnarray} + \theta ~~\text{(in rpm)} \longrightarrow v & = & \frac{13}{57} \times 10^{-3} \times \frac{1}{60} \times \theta ~~ \text{m/s} \\ + & \approx & 3.8011695906432747 \times 10^{-6} \times \theta ~~\text{m/s} + \end{eqnarray} + +The tpdo part of the configuration of the :code:`EcCiA402Drive` plugin will then be set up with the following values: + +.. code-block:: yaml + + tpdo: # TxPDO = transmit PDO Mapping, slave (out) to master (in) (MISO), state values transmitted by the drive to ROS2 control + - index: 0x1a03 + channels: + - { + index: 0x606c, + sub_index: 0, + type: int32, + state_interface: velocity, + factor: 3.8011695906432747e-6, + offset: 0 + } # Velocity actual value + +Transform torque +~~~~~~~~~~~~~~~~ + +The output torque (:math:`T_o`) of the gearbox given the input torque of the motor (:math:`T_i`) is given by the formula: + +.. math:: + + \begin{eqnarray} + T_i \longrightarrow T_o & = & \frac{57}{13} \times \eta_g \times T_i \\ + & \approx & 3.683076923076923 \times T_i + \end{eqnarray} + +Torque to Force conversion +~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The force :math:`F_o` of the lead screw is given by the formula: + +.. math:: + + \begin{eqnarray} + T_o \longrightarrow F_o & = & \frac{2\pi}{l}T_o \\ + \end{eqnarray} + + +Thus the force :math:`F_o` in :math:`\text{mN}` given the input torque of the motor (:math:`T_i` in :math:`\text{mNm}`) is provided by the formula: + +.. math:: + + \begin{eqnarray} + T_i \longrightarrow F_o & = & \frac{2\pi}{l} \times \frac{57}{13} \times \eta_g \times T_i \\ + & \approx & 23141.45480828912 \times T_i + \end{eqnarray} + + +The tpdo part of the configuration of the :code:`EcCiA402Drive` plugin will then be set up with the following values: + +.. code-block:: yaml + + tpdo: # TxPDO = transmit PDO Mapping, slave (out) to master (in) (MISO), state values transmitted by the drive to ROS2 control + - index: 0x1a03 + channels: + - { + index: 0x6077, + sub_index: 0, + type: int32, + state_interface: effort, + factor: 23141.45480828912, + offset: 0 + } # Force actual value in mN + + +Convert command values +---------------------- + +This is the configuration part of the rpdo of the :code:`EcCiA402Drive` plugin and corresponding to the :code:`command_interface` in ROS2 control terminology. + +The drive will take the following command values: + +- :code:`position` in :math:`\text{counts}` or :math:`c` +- :code:`velocity` in :math:`\theta` (revolutions per minute) +- :code:`torque` (:math:`T_i`) in :math:`\text{mNm}` (torque of the motor at the input of the gearbox) + +We would like to send the following command values: + +- :code:`position` (:math:`d`) in :math:`\text{m}` +- :code:`velocity` (:math:`v`) in :math:`\text{m/s}` +- :code:`force` (:math:`F_o`) in :math:`\text{mN}` (Force of the lead screw) + +Command in counts to move by a certain distance in m +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +To command the motor to move by a certain distance :math:`d` in meters, the number of counts :math:`c` to send to the motor is given by the formula: + +.. math:: + + \begin{equation} + d \longrightarrow \text{c} = \frac{C}{rl} \times d \approx 8769.23076923077 \times d + \end{equation} + +The 'rpdo' part of the configuration of the :code:`EcCiA402Drive` plugin will then be set up with the following values: + + +.. code-block:: yaml + + rpdo: # RxPDO = receive PDO Mapping, master (out) to slave (in) (MOSI), command values received by the drive from ROS2 control + - index: 0x1603 + channels: + - { + index: 0x607a, + sub_index: 0, + type: int32, + command_interface: position, + factor: 8769.23076923077, + offset: 0 + } # Target position + + + +Command in rpm to move at a certain velocity given in m/s +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +To command the motor to move at a certain velocity in m/s, the number of rpm to send to the motor is given by the formula: + +.. math:: + + \begin{eqnarray} + v ~~\text{(in m/s)}\longrightarrow \theta & = & \frac{60}{rl} \times v ~~\text{(in counts)}\\ + & \approx & 263076.92307692306 \times v ~~\text{(in counts)} + \end{eqnarray} + +The 'rpdo' part of the configuration of the :code:`EcCiA402Drive` plugin will then be set up with the following values: + + +.. code-block:: yaml + + rpdo: # RxPDO = receive PDO Mapping, master (out) to slave (in) (MOSI), command values received by the drive from ROS2 control + - index: 0x1603 + channels: + - { + index: 0x60ff, + sub_index: 0, + type: int32, + command_interface: velocity, + factor: 263076.92307692306, + offset: 0 + } # Target velocity + +Force to torque conversion +~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The input torque of the motor (:math:`T_i` in :math:`\text{mNm}`) given the target command force :math:`F_o` in :math:`\text{mN}` is provided by the formula: + +.. math:: + + \begin{eqnarray} + F_o \longrightarrow T_i & = & \frac{l}{2\pi} \times \frac{13}{57} \times \frac{1}{\eta_g} \times F_o \\ + & \approx & 23141.45480828912 \times F_o + \end{eqnarray} + + +The tpdo part of the configuration of the :code:`EcCiA402Drive` plugin will then be set up with the following values: + +.. code-block:: yaml + + rpdo: # RxPDO = receive PDO Mapping, master (out) to slave (in) (MOSI), command values received by the drive from ROS2 control + - index: 0x1603 + channels: + - { + index: 0x6071, + sub_index: 0, + type: int32, + state_interface: effort, + factor: 4.321249499153383e-05, + offset: 0 + } # Target force + + +Complete configuration example for an EPOS4 drive +------------------------------------------------- + +Note that we omit the ``offset`` parameter since their default value is equal to zero. + +.. literalinclude:: epos4_config_with_gear_box.yaml + :language: yaml + :caption: Example of a complete configuration for an EPOS4 drive with a gearbox and a transmission screw + :linenos: diff --git a/ethercat_driver_ros2/sphinx/user_guide/epos4_config_with_gear_box.yaml b/ethercat_driver_ros2/sphinx/user_guide/epos4_config_with_gear_box.yaml new file mode 100644 index 0000000..8e0079f --- /dev/null +++ b/ethercat_driver_ros2/sphinx/user_guide/epos4_config_with_gear_box.yaml @@ -0,0 +1,92 @@ +# Configuration file for Maxon EPOS4 50/5 drive +vendor_id: 0x000000fb +product_id: 0x63500000 # Product code +assign_activate: 0x0300 # DC Synch register +auto_fault_reset: true # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault" +sdo: # sdo data to be transferred at drive startup + - { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms + - { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s +rpdo: # RxPDO = receive PDO 4 Mapping, master (out) to slave (in) (MOSI), command values received by the drive from ROS2 control + - index: 0x1603 + channels: + - { + index: 0x6040, + sub_index: 0, + type: uint16, + command_interface: control_word, + default: 0, + } # Control word + - { + index: 0x607a, + sub_index: 0, + type: int32, + command_interface: position, + factor: 8769.23076923077, + default: .nan, + } # Target position + - { + index: 0x60ff, + sub_index: 0, + type: int32, + command_interface: velocity, + factor: 263076.92307692306, + default: 0, + } # Target velocity + - { + index: 0x6071, + sub_index: 0, + type: int16, + command_interface: effort, + factor: 4.321249499153383e-05, + default: 0, + } # Target torque + - { index: 0x60b0, sub_index: 0, type: int32, default: 0 } # Offset position + - { index: 0x60b1, sub_index: 0, type: int32, default: 0 } # Offset velocity + - { index: 0x60b2, sub_index: 0, type: int16, default: 0 } # Offset torque + - { + index: 0x6060, + sub_index: 0, + type: int8, + command_interface: mode_of_operation, + default: 9, + } # Mode of operation. Available modes are: position (8), velocity (9), effort (10) and homing (6) +tpdo: # TxPDO = transmit PDO 4 Mapping, slave (out) to master (in) (MISO), state values transmitted by the drive to ROS2 control + - index: 0x1a03 + channels: + - { + index: 0x6041, + sub_index: 0, + type: uint16, + state_interface: status_word, + } # Status word + - { + index: 0x6064, + sub_index: 0, + type: int32, + state_interface: position, + factor: 0.11403508771929824e-6, + } # Position actual value + - { + index: 0x606c, + sub_index: 0, + type: int32, + state_interface: velocity, + factor: 3.8011695906432747e-6, + } # Velocity actual value + - { + index: 0x6077, + sub_index: 0, + type: int16, + state_interface: effort, + factor: 23141.45480828912, + } # Force actual value + - { + index: 0x6061, + sub_index: 0, + type: int8, + state_interface: mode_of_operation, + } # Mode of operation display + - { index: 0x3141, sub_index: 1, type: int16 } # Digital Input Properties + - { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status + - { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive edge + - { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative edge diff --git a/ethercat_driver_ros2/sphinx/user_guide/sdo_async_com.rst b/ethercat_driver_ros2/sphinx/user_guide/sdo_async_com.rst new file mode 100644 index 0000000..fb11d84 --- /dev/null +++ b/ethercat_driver_ros2/sphinx/user_guide/sdo_async_com.rst @@ -0,0 +1,57 @@ +SDO acyclic exchange using ROS2 services +======================================== + +Service Data Objects (SDO) contain object dictionary entries that can be exchanged acyclically. SDO works as a mailbox sending and buffering received data. This communication is acyclic and is dependent on available bandwidth in the communication cycle. This communication is not deterministic and is best suited for transmitting configuration data. + +Services +-------- + +The EtherCAT Driver ROS2 stack comes with a service server that allows the exchange of data with an EtherCAT slave using ROS2 services through SDO. +The following services are available: + +.. list-table:: + :header-rows: 1 + + * - Service + - Interface + - Description + * - :code:`ethercat_manager/get_sdo` + - :code:`ethercat_msgs::srv::GetSdo` + - Read data from slave SDO register + * - :code:`ethercat_manager/set_sdo` + - :code:`ethercat_msgs::srv::SetSdo` + - Write data to slave SDO register + +Interfaces +---------- + +The interfaces used by the services are defined such that: + ++---------------+-------------------------------------+-------------------------------------+ +| | :code:`ethercat_msgs::srv::GetSdo` | :code:`ethercat_msgs::srv::SetSdo` | ++---------------+-------------------------------------+-------------------------------------+ +| **Request** | .. code-block:: shell | .. code-block:: shell | +| | | | +| | int16 master_id | int16 master_id | +| | uint16 slave_position | int16 slave_position | +| | uint16 sdo_index | uint16 sdo_index | +| | uint8 sdo_subindex | uint8 sdo_subindex | +| | string sdo_data_type | string sdo_data_type | +| | | string sdo_value | ++---------------+-------------------------------------+-------------------------------------+ +| **Response** | .. code-block:: shell | .. code-block:: shell | +| | | | +| | bool success | bool success | +| | string sdo_return_message | string sdo_return_message | +| | string sdo_return_value_string | | +| | float64 sdo_return_value | | ++---------------+-------------------------------------+-------------------------------------+ + +Usage +----- + +Build and source the :code:`ethercat_manager` package and run: + +.. code-block:: shell + + $ ros2 run ethercat_manager ethercat_sdo_srv_server diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/CMakeLists.txt b/ethercat_generic_plugins/ethercat_generic_cia402_drive/CMakeLists.txt new file mode 100644 index 0000000..6db4383 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/CMakeLists.txt @@ -0,0 +1,89 @@ +cmake_minimum_required(VERSION 3.8) +project(ethercat_generic_cia402_drive) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) +find_package(ethercat_interface REQUIRED) +find_package(ethercat_generic_slave REQUIRED) +find_package(pluginlib REQUIRED) +find_package(yaml_cpp_vendor REQUIRED) + +file(GLOB_RECURSE PLUGINS_SRC src/*.cpp) +add_library(ethercat_generic_cia402_drive ${PLUGINS_SRC}) +target_compile_features(ethercat_generic_cia402_drive PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 +target_include_directories(ethercat_generic_cia402_drive PUBLIC + $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> + $<INSTALL_INTERFACE:include>) +ament_target_dependencies( + ethercat_generic_cia402_drive + ethercat_interface + ethercat_generic_slave + pluginlib + yaml_cpp_vendor +) + +pluginlib_export_plugin_description_file(ethercat_interface ethercat_plugins.xml) + +install( + DIRECTORY include/ + DESTINATION include +) + +install( + TARGETS ethercat_generic_cia402_drive + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + find_package(pluginlib REQUIRED) + find_package(ethercat_interface REQUIRED) + find_package(ethercat_generic_slave REQUIRED) + ament_lint_auto_find_test_dependencies() + + # Test Load EtherCAT modules + ament_add_gmock( + test_load_generic_plugins + test/test_load_ec_modules.cpp + ) + target_include_directories(test_load_generic_plugins PRIVATE include) + ament_target_dependencies(test_load_generic_plugins + pluginlib + ethercat_interface + ) + + # Test Generic EtherCAT CIA402 Drive Plugin + ament_add_gmock( + test_generic_ec_cia402_drive + test/test_generic_ec_cia402_drive.cpp + ) + target_include_directories(test_generic_ec_cia402_drive PRIVATE include) + target_link_libraries(test_generic_ec_cia402_drive + ethercat_generic_cia402_drive + ) + ament_target_dependencies(test_generic_ec_cia402_drive + pluginlib + ethercat_interface + ethercat_generic_slave + ) +endif() + +ament_export_include_directories( + include +) +ament_export_libraries( + ethercat_generic_cia402_drive +) +ament_export_targets( + export_${PROJECT_NAME} +) + +ament_package() diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/ethercat_plugins.xml b/ethercat_generic_plugins/ethercat_generic_cia402_drive/ethercat_plugins.xml new file mode 100644 index 0000000..95b66a6 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/ethercat_plugins.xml @@ -0,0 +1,5 @@ +<library path="ethercat_generic_cia402_drive"> + <class name="ethercat_generic_plugins/EcCiA402Drive" type="ethercat_generic_plugins::EcCiA402Drive" base_class_type="ethercat_interface::EcSlave"> + <description>Generic EtherCAT CiA402 Drive.</description> + </class> +</library> diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/cia402_common_defs.hpp b/ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/cia402_common_defs.hpp new file mode 100644 index 0000000..c4ba4aa --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/cia402_common_defs.hpp @@ -0,0 +1,71 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_GENERIC_PLUGINS__CIA402_COMMON_DEFS_HPP_ +#define ETHERCAT_GENERIC_PLUGINS__CIA402_COMMON_DEFS_HPP_ + +#define CiA402D_RPDO_CONTROLWORD ((uint16_t) 0x6040) +#define CiA402D_RPDO_POSITION ((uint16_t) 0x607a) +#define CiA402D_RPDO_VELOCITY ((uint16_t) 0x60ff) +#define CiA402D_RPDO_EFFORT ((uint16_t) 0x6071) +#define CiA402D_RPDO_MODE_OF_OPERATION ((uint16_t) 0x6060) + +#define CiA402D_TPDO_POSITION ((uint16_t) 0x6064) +#define CiA402D_TPDO_STATUSWORD ((uint16_t) 0x6041) +#define CiA402D_TPDO_MODE_OF_OPERATION_DISPLAY ((uint16_t) 0x6061) + +#include <map> +#include <string> + +enum DeviceState +{ + STATE_UNDEFINED = 0, + STATE_START = 1, + STATE_NOT_READY_TO_SWITCH_ON, + STATE_SWITCH_ON_DISABLED, + STATE_READY_TO_SWITCH_ON, + STATE_SWITCH_ON, + STATE_OPERATION_ENABLED, + STATE_QUICK_STOP_ACTIVE, + STATE_FAULT_REACTION_ACTIVE, + STATE_FAULT +}; + +enum ModeOfOperation +{ + MODE_NO_MODE = 0, + MODE_PROFILED_POSITION = 1, + MODE_PROFILED_VELOCITY = 3, + MODE_PROFILED_TORQUE = 4, + MODE_HOMING = 6, + MODE_INTERPOLATED_POSITION = 7, + MODE_CYCLIC_SYNC_POSITION = 8, + MODE_CYCLIC_SYNC_VELOCITY = 9, + MODE_CYCLIC_SYNC_TORQUE = 10 +}; + +const std::map<DeviceState, std::string> DEVICE_STATE_STR = { + {STATE_START, "Start"}, + {STATE_NOT_READY_TO_SWITCH_ON, "Not Ready to Switch On"}, + {STATE_SWITCH_ON_DISABLED, "Switch on Disabled"}, + {STATE_READY_TO_SWITCH_ON, "Ready to Switch On"}, + {STATE_SWITCH_ON, "Switch On"}, + {STATE_OPERATION_ENABLED, "Operation Enabled"}, + {STATE_QUICK_STOP_ACTIVE, "Quick Stop Active"}, + {STATE_FAULT_REACTION_ACTIVE, "Fault Reaction Active"}, + {STATE_FAULT, "Fault"}, + {STATE_UNDEFINED, "Undefined State"} +}; + +#endif // ETHERCAT_GENERIC_PLUGINS__CIA402_COMMON_DEFS_HPP_ diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/generic_ec_cia402_drive.hpp b/ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/generic_ec_cia402_drive.hpp new file mode 100644 index 0000000..4f75dc5 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/include/ethercat_generic_plugins/generic_ec_cia402_drive.hpp @@ -0,0 +1,88 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) + +#ifndef ETHERCAT_GENERIC_PLUGINS__GENERIC_EC_CIA402_DRIVE_HPP_ +#define ETHERCAT_GENERIC_PLUGINS__GENERIC_EC_CIA402_DRIVE_HPP_ + +#include <vector> +#include <string> +#include <unordered_map> +#include <limits> + +#include "yaml-cpp/yaml.h" +#include "ethercat_interface/ec_slave.hpp" +#include "ethercat_interface/ec_pdo_single_interface_channel_manager.hpp" +#include "ethercat_generic_plugins/generic_ec_slave.hpp" +#include "ethercat_generic_plugins/cia402_common_defs.hpp" + +namespace ethercat_generic_plugins +{ + +class EcCiA402Drive : public GenericEcSlave +{ +public: + EcCiA402Drive(); + virtual ~EcCiA402Drive(); + /** Returns true if drive has reached "operation enabled" state. + * The transition through the state machine is handled automatically. */ + bool initialized(); + + virtual void processData(size_t entry_idx, uint8_t * domain_address); + + virtual bool setupSlave( + std::unordered_map<std::string, std::string> slave_parameters, + std::vector<double> * state_interface, + std::vector<double> * command_interface); + + int8_t mode_of_operation_display_ = 0; + int8_t mode_of_operation_ = -1; + + void updateState(); + +public: + bool checkOperationEnabled(); + + bool activate(); + bool deactivate(); + +protected: + uint32_t counter_ = 0; + uint16_t last_status_word_ = -1; + uint16_t status_word_ = 0; + uint16_t control_word_ = 0; + DeviceState last_state_ = STATE_START; + DeviceState state_ = STATE_START; + bool initialized_ = false; + bool auto_fault_reset_ = false; + bool auto_state_transitions_ = true; + bool fault_reset_ = false; + int fault_reset_command_interface_index_ = -1; + bool last_fault_reset_command_ = false; + bool is_activated_ = false; + double last_position_ = std::numeric_limits<double>::quiet_NaN(); + + /** returns device state based upon the status_word */ + DeviceState deviceState(uint16_t status_word); + /** returns the control word that will take device from state to next desired state */ + uint16_t transition(DeviceState state, uint16_t control_word); + /** set up of the drive configuration from yaml node*/ + bool setup_from_config(YAML::Node drive_config); + /** set up of the drive configuration from yaml file*/ + bool setup_from_config_file(std::string config_file); +}; +} // namespace ethercat_generic_plugins + +#endif // ETHERCAT_GENERIC_PLUGINS__GENERIC_EC_CIA402_DRIVE_HPP_ diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/package.xml b/ethercat_generic_plugins/ethercat_generic_cia402_drive/package.xml new file mode 100644 index 0000000..d5f4235 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/package.xml @@ -0,0 +1,23 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_generic_cia402_drive</name> + <version>1.2.0</version> + <description>Plugin implementations of generic EtherCAT modules for CiA402 drives.</description> + <maintainer email="yguel.robotics@gamil.com">Manuel YGUEL</maintainer> + <license>Apache-2.0</license> + + <buildtool_depend>ament_cmake_ros</buildtool_depend> + + <depend>ethercat_interface</depend> + <depend>ethercat_generic_slave</depend> + <depend>pluginlib</depend> + <depend>yaml_cpp_vendor</depend> + + <test_depend>ament_lint_auto</test_depend> + <test_depend>ament_lint_common</test_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> \ No newline at end of file diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/src/generic_ec_cia402_drive.cpp b/ethercat_generic_plugins/ethercat_generic_cia402_drive/src/generic_ec_cia402_drive.cpp new file mode 100644 index 0000000..f9c031a --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/src/generic_ec_cia402_drive.cpp @@ -0,0 +1,285 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) + +#include <numeric> + +#include "rclcpp/rclcpp.hpp" + +#include "ethercat_generic_plugins/generic_ec_cia402_drive.hpp" + +namespace ethercat_generic_plugins +{ + +EcCiA402Drive::EcCiA402Drive() +: GenericEcSlave() {} +EcCiA402Drive::~EcCiA402Drive() {} + +bool EcCiA402Drive::initialized() {return initialized_;} + +bool EcCiA402Drive::checkOperationEnabled() +{ + initialized_ = (state_ == STATE_OPERATION_ENABLED) && + (last_state_ == STATE_OPERATION_ENABLED); + return initialized_; +} + + +void EcCiA402Drive::updateState() +{ + last_state_ = state_; + if (status_word_ != last_status_word_) { + state_ = deviceState(status_word_); + if (state_ != last_state_) { + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "STATE: %s with status word :%d", + DEVICE_STATE_STR.at(state_).c_str(), + status_word_ + ); + } + } + checkOperationEnabled(); +} + +bool EcCiA402Drive::activate() +{ + if (is_activated_) { + return checkOperationEnabled(); + } + is_activated_ = true; + return false; +} + +bool EcCiA402Drive::deactivate() +{ + is_activated_ = false; + if (checkOperationEnabled()) { + return false; + } else { + return true; + } +} + +void EcCiA402Drive::processData(size_t entry_idx, uint8_t * domain_address) +{ + auto index = domain_map_[entry_idx]; + ethercat_interface::EcPdoSingleInterfaceChannelManager * channel_ptr = + static_cast< + ethercat_interface::EcPdoSingleInterfaceChannelManager *>( + pdo_channels_info_[index]); + ethercat_interface::EcPdoSingleInterfaceChannelManager & channel(*channel_ptr); + // Special case: ControlWord + if (channel.index == CiA402D_RPDO_CONTROLWORD) { + if (is_operational_) { + if (fault_reset_command_interface_index_ >= 0) { + if (command_interface_ptr_->at(fault_reset_command_interface_index_) == 0) { + last_fault_reset_command_ = false; + } + if (last_fault_reset_command_ == false && + command_interface_ptr_->at(fault_reset_command_interface_index_) != 0 && + !std::isnan(command_interface_ptr_->at(fault_reset_command_interface_index_))) + { + last_fault_reset_command_ = true; + fault_reset_ = true; + } + } + + if (auto_state_transitions_) { + channel.default_value = transition( + state_, + channel.ec_read(domain_address)); + } + } + } + + // setup current position as default position + if (channel.index == CiA402D_RPDO_POSITION) { + if (mode_of_operation_display_ != ModeOfOperation::MODE_NO_MODE) { + channel.default_value = + channel.factor * last_position_ + channel.offset; + } + channel.override_command = + (mode_of_operation_display_ != ModeOfOperation::MODE_CYCLIC_SYNC_POSITION) ? true : false; + } + + // setup mode of operation + if (channel.index == CiA402D_RPDO_MODE_OF_OPERATION) { + if (mode_of_operation_ >= 0 && mode_of_operation_ <= 10) { + channel.default_value = mode_of_operation_; + } + } + + channel.ec_update(domain_address); + + // get mode_of_operation_display_ + if (channel.index == CiA402D_TPDO_MODE_OF_OPERATION_DISPLAY) { + mode_of_operation_display_ = channel.last_value; + } + + if (channel.index == CiA402D_TPDO_POSITION) { + last_position_ = channel.last_value; + } + + // Special case: StatusWord + if (channel.index == CiA402D_TPDO_STATUSWORD) { + last_status_word_ = status_word_; + status_word_ = channel.last_value; + } + + + // CHECK FOR STATE CHANGE + if (entry_idx == domain_map_.size() - 1) { // if last entry in domain + updateState(); + counter_++; + } +} + +bool EcCiA402Drive::setupSlave( + std::unordered_map<std::string, std::string> slave_parameters, + std::vector<double> * state_interface, + std::vector<double> * command_interface) +{ + state_interface_ptr_ = state_interface; + command_interface_ptr_ = command_interface; + parameters_ = slave_parameters; + + if (parameters_.find("slave_config") != parameters_.end()) { + if (!setup_from_config_file(parameters_["slave_config"])) { + return false; + } + } else { + std::cerr << "EcCiA402Drive: failed to find 'slave_config' tag in URDF." << std::endl; + return false; + } + + setup_interface_mapping(); + setup_syncs(); + + if (parameters_.find("mode_of_operation") != parameters_.end()) { + mode_of_operation_ = std::stod(parameters_["mode_of_operation"]); + } + + if (parameters_.find("command_interface/reset_fault") != parameters_.end()) { + fault_reset_command_interface_index_ = std::stoi(parameters_["command_interface/reset_fault"]); + RCLCPP_INFO( + rclcpp::get_logger( + "EthercatDriver"), "fault_reset_command_interface_index_:%d", + fault_reset_command_interface_index_); + } + + return true; +} + +bool EcCiA402Drive::setup_from_config(YAML::Node drive_config) +{ + if (!GenericEcSlave::setup_from_config(drive_config)) {return false;} + // additional configuration parameters for CiA402 Drives + if (drive_config["auto_fault_reset"]) { + auto_fault_reset_ = drive_config["auto_fault_reset"].as<bool>(); + } + if (drive_config["auto_state_transitions"]) { + auto_state_transitions_ = drive_config["auto_state_transitions"].as<bool>(); + } + return true; +} + +bool EcCiA402Drive::setup_from_config_file(std::string config_file) +{ + // Read drive configuration from YAML file + try { + slave_config_ = YAML::LoadFile(config_file); + } catch (const YAML::ParserException & ex) { + std::cerr << "EcCiA402Drive: failed to load drive configuration: " << ex.what() << std::endl; + return false; + } catch (const YAML::BadFile & ex) { + std::cerr << "EcCiA402Drive: failed to load drive configuration: " << ex.what() << std::endl; + return false; + } + if (!setup_from_config(slave_config_)) { + return false; + } + return true; +} + +/** returns device state based upon the status_word */ +DeviceState EcCiA402Drive::deviceState(uint16_t status_word) +{ + if ((status_word & 0b01001111) == 0b00000000) { + return STATE_NOT_READY_TO_SWITCH_ON; + } else if ((status_word & 0b01001111) == 0b01000000) { + return STATE_SWITCH_ON_DISABLED; + } else if ((status_word & 0b01101111) == 0b00100001) { + return STATE_READY_TO_SWITCH_ON; + } else if ((status_word & 0b01101111) == 0b00100011) { + return STATE_SWITCH_ON; + } else if ((status_word & 0b01101111) == 0b00100111) { + return STATE_OPERATION_ENABLED; + } else if ((status_word & 0b01101111) == 0b00000111) { + return STATE_QUICK_STOP_ACTIVE; + } else if ((status_word & 0b01001111) == 0b00001111) { + return STATE_FAULT_REACTION_ACTIVE; + } else if ((status_word & 0b01001111) == 0b00001000) { + return STATE_FAULT; + } + return STATE_UNDEFINED; +} + +/** returns the control word that will take device from state to next desired state */ +uint16_t EcCiA402Drive::transition(DeviceState state, uint16_t control_word) +{ + switch (state) { + case STATE_START: // -> STATE_NOT_READY_TO_SWITCH_ON (automatic) + return control_word; + case STATE_NOT_READY_TO_SWITCH_ON: // -> STATE_SWITCH_ON_DISABLED (automatic) + return control_word; + case STATE_SWITCH_ON_DISABLED: // -> STATE_READY_TO_SWITCH_ON + return (control_word & 0b01111110) | 0b00000110; + case STATE_READY_TO_SWITCH_ON: // -> STATE_SWITCH_ON + return (control_word & 0b01110111) | 0b00000111; + case STATE_SWITCH_ON: // -> STATE_OPERATION_ENABLED + if (is_activated_) { + return (control_word & 0b01111111) | 0b00001111; + } else { + return control_word; + } + case STATE_OPERATION_ENABLED: // -> GOOD + if (is_activated_) { + return control_word; + } else { + return (control_word & 0b01110111) | 0b00000111; + } + case STATE_QUICK_STOP_ACTIVE: // -> STATE_OPERATION_ENABLED + return (control_word & 0b01111111) | 0b00001111; + case STATE_FAULT_REACTION_ACTIVE: // -> STATE_FAULT (automatic) + return control_word; + case STATE_FAULT: // -> STATE_SWITCH_ON_DISABLED + if (auto_fault_reset_ || fault_reset_) { + fault_reset_ = false; + return (control_word & 0b11111111) | 0b10000000; // automatic reset + } else { + return control_word; + } + default: + break; + } + return control_word; +} + +} // namespace ethercat_generic_plugins + +#include <pluginlib/class_list_macros.hpp> + +PLUGINLIB_EXPORT_CLASS(ethercat_generic_plugins::EcCiA402Drive, ethercat_interface::EcSlave) diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.cpp b/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.cpp new file mode 100644 index 0000000..ab9990c --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.cpp @@ -0,0 +1,324 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 <map> +#include <limits> +#include <pluginlib/class_loader.hpp> +#include "ethercat_interface/ec_slave.hpp" +#include "test_generic_ec_cia402_drive.hpp" + +const char test_drive_config[] = + R"( +# Configuration file for Test drive +vendor_id: 0x00000011 +product_id: 0x07030924 +assign_activate: 0x0321 # DC Synch register +period: 100 # Hz +auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault" +sdo: # sdo data to be transferred at drive startup + - {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms + - {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s +rpdo: # RxPDO + - index: 0x1607 + channels: + - {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position + - {index: 0x60ff, sub_index: 0, type: int32, command_interface: velocity, default: 0} # Target velocity + - {index: 0x6071, sub_index: 0, type: int16, command_interface: effort, default: -5} # Target torque + - {index: 0x6072, sub_index: 0, type: int16, command_interface: ~, default: 1000} # Max torque + - {index: 0x6040, sub_index: 0, type: uint16, command_interface: ~, default: 0} # Control word + - {index: 0x6060, sub_index: 0, type: int8, command_interface: mode_of_operation, default: 8} # Mode of operation +tpdo: # TxPDO + - index: 0x1a07 + channels: + - {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value + - {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} # Velocity actual value + - {index: 0x6077, sub_index: 0, type: int16, state_interface: effort} # Torque actual value + - {index: 0x6041, sub_index: 0, type: uint16, state_interface: ~} # Status word + - {index: 0x6061, sub_index: 0, type: int8, state_interface: mode_of_operation} # Mode of operation display + - index: 0x1a45 + channels: + - {index: 0x2205, sub_index: 1, type: int16, state_interface: analog_input1} # Analog input + - {index: 0x2205, sub_index: 2, type: int16, state_interface: analog_input2} # Analog input +)"; + +void EcCiA402DriveTest::SetUp() +{ + plugin_ = std::make_unique<FriendEcCiA402Drive>(); +} + +void EcCiA402DriveTest::TearDown() +{ + plugin_.reset(nullptr); +} + +TEST_F(EcCiA402DriveTest, SlaveSetupNoDriveConfig) +{ + SetUp(); + std::vector<double> state_interface = {0}; + std::vector<double> command_interface = {0}; + std::unordered_map<std::string, std::string> slave_parameters; + // setup failed, 'drive_config' parameter not set + ASSERT_EQ( + plugin_->setupSlave( + slave_parameters, + &state_interface, + &command_interface + ), + false + ); +} + +TEST_F(EcCiA402DriveTest, SlaveSetupMissingFileDriveConfig) +{ + SetUp(); + std::vector<double> state_interface = {0}; + std::vector<double> command_interface = {0}; + std::unordered_map<std::string, std::string> slave_parameters; + slave_parameters["drive_config"] = "drive_config.yaml"; + // setup failed, 'drive_config.yaml' file not set + ASSERT_EQ( + plugin_->setupSlave( + slave_parameters, + &state_interface, + &command_interface + ), + false + ); +} + +TEST_F(EcCiA402DriveTest, SlaveSetupDriveFromConfig) +{ + SetUp(); + ASSERT_EQ( + plugin_->setup_from_config(YAML::Load(test_drive_config)), + true + ); + ASSERT_EQ(plugin_->vendor_id_, 0x00000011); + ASSERT_EQ(plugin_->product_id_, 0x07030924); + ASSERT_EQ(plugin_->assign_activate_, 0x0321); + ASSERT_EQ(plugin_->auto_fault_reset_, false); + + ASSERT_EQ(plugin_->rpdos_.size(), 1); + ASSERT_EQ(plugin_->rpdos_[0].index, 0x1607); + + ASSERT_EQ(plugin_->tpdos_.size(), 2); + ASSERT_EQ(plugin_->tpdos_[0].index, 0x1a07); + ASSERT_EQ(plugin_->tpdos_[1].index, 0x1a45); + + + auto channels = plugin_->pdo_channels_info_; + ASSERT_EQ(channels[1]->interface_name(), "velocity") << "Interface name is not 'velocity'"; + ASSERT_EQ(channels[3]->data().default_value, 1000) << "Default value is not 1000"; + ASSERT_TRUE(std::isnan(channels[0]->data().default_value)) << "Default value is not NaN"; + ASSERT_EQ(channels[4]->interface_name(), "null") << "Interface name is not 'null'"; + ASSERT_EQ( + channels[12]->interface_name(), + "analog_input2") << "Interface name is not 'analog_input2'"; + ASSERT_EQ(channels[4]->data_type(), "uint16") << "Data type is not 'uint16'"; +} + +TEST_F(EcCiA402DriveTest, SlaveSetupPdoChannels) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_drive_config)); + std::vector<ec_pdo_entry_info_t> channels( + plugin_->channels(), + plugin_->channels() + plugin_->all_channels_.size() + ); + + ASSERT_EQ(channels.size(), 13); + ASSERT_EQ(channels[0].index, 0x607a); + ASSERT_EQ(channels[11].index, 0x2205); + ASSERT_EQ(channels[11].subindex, 0x01); +} + +TEST_F(EcCiA402DriveTest, SlaveSetupSyncs) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_drive_config)); + plugin_->setup_syncs(); + std::vector<ec_sync_info_t> syncs( + plugin_->syncs(), + plugin_->syncs() + plugin_->syncSize() + ); + + ASSERT_EQ(syncs.size(), 5); + ASSERT_EQ(syncs[1].index, 1); + ASSERT_EQ(syncs[1].dir, EC_DIR_INPUT); + ASSERT_EQ(syncs[1].n_pdos, 0); + ASSERT_EQ(syncs[1].watchdog_mode, EC_WD_DISABLE); + ASSERT_EQ(syncs[2].dir, EC_DIR_OUTPUT); + ASSERT_EQ(syncs[2].n_pdos, 1); + ASSERT_EQ(syncs[3].index, 3); + ASSERT_EQ(syncs[3].dir, EC_DIR_INPUT); + ASSERT_EQ(syncs[3].n_pdos, 2); + ASSERT_EQ(syncs[3].watchdog_mode, EC_WD_DISABLE); +} + +TEST_F(EcCiA402DriveTest, SlaveSetupDomains) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_drive_config)); + std::map<unsigned int, std::vector<unsigned int>> domains; + plugin_->domains(domains); + + ASSERT_EQ(domains[0].size(), 13); + ASSERT_EQ(domains[0][0], 0); + ASSERT_EQ(domains[0][12], 12); +} + +TEST_F(EcCiA402DriveTest, EcReadTPDOToStateInterface) +{ + SetUp(); + std::unordered_map<std::string, std::string> slave_parameters; + std::vector<double> state_interface = {0, 0}; + plugin_->state_interface_ptr_ = &state_interface; + slave_parameters["state_interface/effort"] = "1"; + plugin_->parameters_ = slave_parameters; + plugin_->setup_from_config(YAML::Load(test_drive_config)); + plugin_->setup_interface_mapping(); + ASSERT_EQ(plugin_->pdo_channels_info_[8]->state_interface_index(), 1); + uint8_t domain_address[2]; + EC_WRITE_S16(domain_address, 42); + plugin_->processData(8, domain_address); + ASSERT_EQ(plugin_->state_interface_ptr_->at(1), 42); +} + +TEST_F(EcCiA402DriveTest, EcWriteRPDOFromCommandInterface) +{ + SetUp(); + std::unordered_map<std::string, std::string> slave_parameters; + std::vector<double> command_interface = {0, 42}; + plugin_->command_interface_ptr_ = &command_interface; + slave_parameters["command_interface/effort"] = "1"; + plugin_->parameters_ = slave_parameters; + plugin_->setup_from_config(YAML::Load(test_drive_config)); + plugin_->setup_interface_mapping(); + auto channels = plugin_->pdo_channels_info_; + ASSERT_EQ(channels[2]->command_interface_index(), 1); + plugin_->mode_of_operation_display_ = 10; + uint8_t domain_address[2]; + plugin_->processData(2, domain_address); + ASSERT_EQ(channels[2]->data().last_value, 42); + ASSERT_EQ(EC_READ_S16(domain_address), 42); +} + +TEST_F(EcCiA402DriveTest, EcWriteRPDODefaultValue) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_drive_config)); + plugin_->setup_interface_mapping(); + plugin_->mode_of_operation_display_ = 10; + uint8_t domain_address[2]; + plugin_->processData(2, domain_address); + auto channels = plugin_->pdo_channels_info_; + ASSERT_EQ(channels[2]->data().last_value, -5); + ASSERT_EQ(EC_READ_S16(domain_address), -5); +} + +// TEST_F(EcCiA402DriveTest, FaultReset) +// { +// std::unordered_map<std::string, std::string> slave_parameters; +// std::vector<double> command_interface = {0, 1}; +// plugin_->command_interface_ptr_ = &command_interface; +// plugin_->setup_from_config(YAML::Load(test_drive_config)); +// plugin_->setup_interface_mapping(); +// plugin_->fault_reset_command_interface_index_ = 1; +// plugin_->state_ = STATE_FAULT; +// plugin_->is_operational_ = true; +// uint8_t domain_address = 0; +// plugin_->pdo_channels_info_[4].data_type = ""; +// ASSERT_FALSE(plugin_->last_fault_reset_command_); +// ASSERT_FALSE(plugin_->fault_reset_); +// ASSERT_EQ(plugin_->command_interface_ptr_->at( +// plugin_->fault_reset_command_interface_index_), 1); +// plugin_->processData(4, &domain_address); +// ASSERT_EQ(plugin_->pdo_channels_info_[4].default_value, 0b10000000); +// plugin_->pdo_channels_info_[4].last_value = 0; +// plugin_->processData(4, &domain_address); +// ASSERT_EQ(plugin_->pdo_channels_info_[4].default_value, 0b00000000); +// command_interface[1] = 0; +// plugin_->processData(4, &domain_address); +// ASSERT_EQ(plugin_->pdo_channels_info_[4].default_value, 0b00000000); +// command_interface[1] = 2; plugin_->processData(4, &domain_address); +// ASSERT_EQ(plugin_->pdo_channels_info_[4].default_value, 0b10000000); +// } + +TEST_F(EcCiA402DriveTest, SwitchModeOfOperation) +{ + std::unordered_map<std::string, std::string> slave_parameters; + std::vector<double> command_interface = { + std::numeric_limits<double>::quiet_NaN(), + std::numeric_limits<double>::quiet_NaN()}; + slave_parameters["command_interface/mode_of_operation"] = "1"; + plugin_->parameters_ = slave_parameters; + plugin_->command_interface_ptr_ = &command_interface; + plugin_->setup_from_config(YAML::Load(test_drive_config)); + plugin_->setup_interface_mapping(); + plugin_->is_operational_ = true; + uint8_t domain_address[2]; + plugin_->processData(5, domain_address); + ASSERT_EQ(EC_READ_S8(domain_address), 8); + command_interface[1] = 9; + plugin_->processData(5, domain_address); + plugin_->processData(10, domain_address); + ASSERT_EQ(EC_READ_S8(domain_address), 9); + ASSERT_EQ(plugin_->mode_of_operation_display_, 9); +} + +TEST_F(EcCiA402DriveTest, EcWriteDefaultTargetPosition) +{ + std::unordered_map<std::string, std::string> slave_parameters; + std::vector<double> command_interface = { + std::numeric_limits<double>::quiet_NaN(), + std::numeric_limits<double>::quiet_NaN()}; + slave_parameters["command_interface/mode_of_operation"] = "1"; + plugin_->parameters_ = slave_parameters; + plugin_->command_interface_ptr_ = &command_interface; + plugin_->setup_from_config(YAML::Load(test_drive_config)); + plugin_->setup_interface_mapping(); + plugin_->is_operational_ = true; + plugin_->mode_of_operation_display_ = 8; + uint8_t domain_address[4]; + uint8_t domain_address_moo[2]; + + plugin_->processData(5, domain_address_moo); // mode_of_operation + plugin_->processData(10, domain_address_moo); // mode_of_operation_display + ASSERT_EQ(plugin_->mode_of_operation_display_, 8); + + EC_WRITE_S32(domain_address, 123456); + plugin_->processData(6, domain_address); + ASSERT_EQ(plugin_->last_position_, 123456); + + EC_WRITE_S32(domain_address, 0); + plugin_->processData(0, domain_address); + ASSERT_EQ(EC_READ_S32(domain_address), 123456); + + command_interface[1] = 9; + plugin_->processData(5, domain_address_moo); + plugin_->processData(10, domain_address_moo); + ASSERT_EQ(plugin_->mode_of_operation_display_, 9); + + EC_WRITE_S32(domain_address, 0); + plugin_->processData(0, domain_address); + ASSERT_EQ(EC_READ_S32(domain_address), 123456); + + EC_WRITE_S32(domain_address, 654321); + plugin_->processData(6, domain_address); + ASSERT_EQ(plugin_->last_position_, 654321); + + EC_WRITE_S32(domain_address, 0); + plugin_->processData(0, domain_address); + ASSERT_EQ(EC_READ_S32(domain_address), 654321); +} diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.hpp b/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.hpp new file mode 100644 index 0000000..ad123ff --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_generic_ec_cia402_drive.hpp @@ -0,0 +1,52 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 TEST_GENERIC_EC_CIA402_DRIVE_HPP_ +#define TEST_GENERIC_EC_CIA402_DRIVE_HPP_ + +#include <memory> +#include <string> +#include <vector> +#include <unordered_map> + +#include "gmock/gmock.h" + +#include "ethercat_generic_plugins/generic_ec_cia402_drive.hpp" + +// subclassing and friending so we can access member variables +class FriendEcCiA402Drive : public ethercat_generic_plugins::EcCiA402Drive +{ + FRIEND_TEST(EcCiA402DriveTest, SlaveSetupDriveFromConfig); + FRIEND_TEST(EcCiA402DriveTest, SlaveSetupPdoChannels); + FRIEND_TEST(EcCiA402DriveTest, SlaveSetupSyncs); + FRIEND_TEST(EcCiA402DriveTest, SlaveSetupDomains); + FRIEND_TEST(EcCiA402DriveTest, EcReadTPDOToStateInterface); + FRIEND_TEST(EcCiA402DriveTest, EcWriteRPDOFromCommandInterface); + FRIEND_TEST(EcCiA402DriveTest, EcWriteRPDODefaultValue); + // FRIEND_TEST(EcCiA402DriveTest, FaultReset); + FRIEND_TEST(EcCiA402DriveTest, SwitchModeOfOperation); + FRIEND_TEST(EcCiA402DriveTest, EcWriteDefaultTargetPosition); +}; + +class EcCiA402DriveTest : public ::testing::Test +{ +public: + void SetUp(); + void TearDown(); + +protected: + std::unique_ptr<FriendEcCiA402Drive> plugin_; +}; + +#endif // TEST_GENERIC_EC_CIA402_DRIVE_HPP_ diff --git a/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_load_ec_modules.cpp b/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_load_ec_modules.cpp new file mode 100644 index 0000000..820249c --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_cia402_drive/test/test_load_ec_modules.cpp @@ -0,0 +1,26 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 <gtest/gtest.h> +#include <memory> + +#include <pluginlib/class_loader.hpp> +#include "ethercat_interface/ec_slave.hpp" + +TEST(TestLoadEcCiA402Drive, load_ec_module) +{ + pluginlib::ClassLoader<ethercat_interface::EcSlave> ec_loader_{ + "ethercat_interface", "ethercat_interface::EcSlave"}; + ASSERT_NO_THROW(ec_loader_.createSharedInstance("ethercat_generic_plugins/EcCiA402Drive")); +} diff --git a/ethercat_generic_plugins/ethercat_generic_slave/CMakeLists.txt b/ethercat_generic_plugins/ethercat_generic_slave/CMakeLists.txt new file mode 100644 index 0000000..3a6b787 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/CMakeLists.txt @@ -0,0 +1,88 @@ +cmake_minimum_required(VERSION 3.8) +project(ethercat_generic_slave) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) +find_package(ethercat_interface REQUIRED) +find_package(pluginlib REQUIRED) +find_package(yaml_cpp_vendor REQUIRED) + +file(GLOB_RECURSE PLUGINS_SRC src/*.cpp) + +add_library(${PROJECT_NAME} ${PLUGINS_SRC}) + +target_compile_features(${PROJECT_NAME} PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 + +target_include_directories(${PROJECT_NAME} PUBLIC + $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include> + $<INSTALL_INTERFACE:include> +) +ament_target_dependencies( ${PROJECT_NAME} + ethercat_interface + pluginlib + yaml_cpp_vendor +) + +pluginlib_export_plugin_description_file(ethercat_interface ethercat_plugins.xml) + +install( + DIRECTORY include/ + DESTINATION include +) + +install( + TARGETS ${PROJECT_NAME} + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + find_package(pluginlib REQUIRED) + find_package(ethercat_interface REQUIRED) + ament_lint_auto_find_test_dependencies() + + # Test Load EtherCAT modules + ament_add_gmock( + test_load_generic_plugins + test/test_load_ec_modules.cpp + ) + target_include_directories(test_load_generic_plugins PRIVATE include) + ament_target_dependencies(test_load_generic_plugins + pluginlib + ethercat_interface + ) + + # Test Generic EtherCAT Slave Plugin + ament_add_gmock( + test_generic_ec_slave + test/test_generic_ec_slave.cpp + ) + ament_target_dependencies(test_generic_ec_slave + pluginlib + ethercat_interface + ) + target_include_directories(test_generic_ec_slave PRIVATE include) + target_link_libraries(test_generic_ec_slave + ${PROJECT_NAME} + ) +endif() + +ament_export_include_directories( + include +) +ament_export_libraries( + ${PROJECT_NAME} +) +ament_export_targets( + export_${PROJECT_NAME} +) + +ament_package() diff --git a/ethercat_generic_plugins/ethercat_generic_slave/ethercat_plugins.xml b/ethercat_generic_plugins/ethercat_generic_slave/ethercat_plugins.xml new file mode 100644 index 0000000..febe9fb --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/ethercat_plugins.xml @@ -0,0 +1,5 @@ +<library path="ethercat_generic_slave"> + <class name="ethercat_generic_plugins/GenericEcSlave" type="ethercat_generic_plugins::GenericEcSlave" base_class_type="ethercat_interface::EcSlave"> + <description>Generic EtherCAT Slave.</description> + </class> +</library> diff --git a/ethercat_generic_plugins/ethercat_generic_slave/include/ethercat_generic_plugins/generic_ec_slave.hpp b/ethercat_generic_plugins/ethercat_generic_slave/include/ethercat_generic_plugins/generic_ec_slave.hpp new file mode 100644 index 0000000..556546c --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/include/ethercat_generic_plugins/generic_ec_slave.hpp @@ -0,0 +1,76 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) + +#ifndef ETHERCAT_GENERIC_PLUGINS__GENERIC_EC_SLAVE_HPP_ +#define ETHERCAT_GENERIC_PLUGINS__GENERIC_EC_SLAVE_HPP_ + +#include <vector> +#include <string> +#include <unordered_map> + +#include "yaml-cpp/yaml.h" +#include "ethercat_interface/ec_slave.hpp" +#include "ethercat_interface/ec_pdo_channel_manager.hpp" +#include "ethercat_interface/ec_sync_manager.hpp" + +namespace ethercat_generic_plugins +{ + +class GenericEcSlave : public ethercat_interface::EcSlave +{ +public: + GenericEcSlave(); + virtual ~GenericEcSlave(); + virtual int assign_activate_dc_sync(); + virtual bool is_reference_clock( uint16_t clock_position ); + + virtual void processData(size_t entry_idx, uint8_t * domain_address); + + virtual const ec_sync_info_t * syncs(); + virtual size_t syncSize(); + virtual const ec_pdo_entry_info_t * channels(); + virtual void domains(DomainMap & domains) const; + + virtual bool setupSlave( + std::unordered_map<std::string, std::string> slave_parameters, + std::vector<double> * state_interface, + std::vector<double> * command_interface); + +protected: + uint32_t counter_ = 0; + std::vector<ec_pdo_info_t> rpdos_; + std::vector<ec_pdo_info_t> tpdos_; + std::vector<bool> all_channels_skip_list_; + std::vector<ec_pdo_entry_info_t> all_channels_; + std::vector<ethercat_interface::EcPdoChannelManager *> pdo_channels_info_; + std::vector<ethercat_interface::SMConfig> sm_configs_; + std::vector<ec_sync_info_t> syncs_; + std::vector<unsigned int> domain_map_; + YAML::Node slave_config_; + uint32_t assign_activate_ = 0; + + /** set up of the drive configuration from yaml node*/ + bool setup_from_config(YAML::Node slave_config); + /** set up of the drive configuration from yaml file*/ + bool setup_from_config_file(std::string config_file); + + void setup_syncs(); + + void setup_interface_mapping(); +}; +} // namespace ethercat_generic_plugins + +#endif // ETHERCAT_GENERIC_PLUGINS__GENERIC_EC_SLAVE_HPP_ diff --git a/ethercat_generic_plugins/ethercat_generic_slave/package.xml b/ethercat_generic_plugins/ethercat_generic_slave/package.xml new file mode 100644 index 0000000..ab4bf92 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/package.xml @@ -0,0 +1,22 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_generic_slave</name> + <version>1.2.0</version> + <description>Plugin implementations of generic EtherCAT modules</description> + <maintainer email="mcbed.robotics@gamil.com">Maciej Bednarczyk</maintainer> + <license>Apache-2.0</license> + + <buildtool_depend>ament_cmake_ros</buildtool_depend> + + <depend>ethercat_interface</depend> + <depend>pluginlib</depend> + <depend>yaml_cpp_vendor</depend> + + <test_depend>ament_lint_auto</test_depend> + <test_depend>ament_lint_common</test_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> \ No newline at end of file diff --git a/ethercat_generic_plugins/ethercat_generic_slave/src/generic_ec_slave.cpp b/ethercat_generic_plugins/ethercat_generic_slave/src/generic_ec_slave.cpp new file mode 100644 index 0000000..51a1614 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/src/generic_ec_slave.cpp @@ -0,0 +1,309 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) + +#include <numeric> + +#include "ethercat_generic_plugins/generic_ec_slave.hpp" +#include "ethercat_interface/ec_pdo_single_interface_channel_manager.hpp" +#include "ethercat_interface/ec_pdo_group_interface_channel_manager.hpp" + +#include "rclcpp/rclcpp.hpp" + +namespace ethercat_generic_plugins +{ + +GenericEcSlave::GenericEcSlave() +: EcSlave(0, 0) {} +GenericEcSlave::~GenericEcSlave() +{ + for (size_t c = 0; c < pdo_channels_info_.size(); c++) { + delete pdo_channels_info_[c]; + } +} +int GenericEcSlave::assign_activate_dc_sync() {return assign_activate_;} + +bool GenericEcSlave::is_reference_clock( uint16_t clock_position ) { + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "clock position : %u, slave position :%u", clock_position,position_); + if (clock_position == position_) return true; + return false; +}; + +void GenericEcSlave::processData(size_t entry_idx, uint8_t * domain_address) +{ + pdo_channels_info_[domain_map_[entry_idx]]->ec_update(domain_address); +} + +const ec_sync_info_t * GenericEcSlave::syncs() +{ + return syncs_.data(); +} +size_t GenericEcSlave::syncSize() +{ + return syncs_.size(); +} +const ec_pdo_entry_info_t * GenericEcSlave::channels() +{ + return all_channels_.data(); +} +void GenericEcSlave::domains(DomainMap & domains) const +{ + domains = {{0, domain_map_}}; +} + +void GenericEcSlave::setup_syncs() +{ + if (sm_configs_.size() == 0) { + syncs_.push_back({0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE}); + syncs_.push_back({1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE}); + syncs_.push_back( + {2, EC_DIR_OUTPUT, (unsigned int)(rpdos_.size()), rpdos_.data(), + EC_WD_ENABLE}); + syncs_.push_back( + {3, EC_DIR_INPUT, (unsigned int)(tpdos_.size()), tpdos_.data(), + EC_WD_DISABLE}); + } else { + for (auto & sm : sm_configs_) { + if (sm.pdo_name == "null") { + syncs_.push_back({sm.index, sm.type, 0, NULL, sm.watchdog}); + } else if (sm.pdo_name == "rpdo") { + syncs_.push_back( + {sm.index, sm.type, (unsigned int)(rpdos_.size()), + rpdos_.data(), sm.watchdog}); + } else if (sm.pdo_name == "tpdo") { + syncs_.push_back( + {sm.index, sm.type, (unsigned int)(tpdos_.size()), + tpdos_.data(), sm.watchdog}); + } + } + } + syncs_.push_back({0xff, EC_DIR_INVALID, 0, nullptr, EC_WD_DISABLE}); +} + +bool GenericEcSlave::setupSlave( + std::unordered_map<std::string, std::string> slave_parameters, + std::vector<double> * state_interface, + std::vector<double> * command_interface) +{ + state_interface_ptr_ = state_interface; + command_interface_ptr_ = command_interface; + parameters_ = slave_parameters; + + if (parameters_.find("slave_config") != parameters_.end()) { + if (!setup_from_config_file(parameters_["slave_config"])) { + return false; + } + } else { + std::cerr << "GenericEcSlave: failed to find 'slave_config' tag in URDF." << std::endl; + return false; + } + + setup_interface_mapping(); + setup_syncs(); + + return true; +} + +bool GenericEcSlave::setup_from_config(YAML::Node slave_config) +{ + if (slave_config.size() != 0) { + if (slave_config["vendor_id"]) { + vendor_id_ = slave_config["vendor_id"].as<uint32_t>(); + } else { + std::cerr << "GenericEcSlave: failed to load drive vendor ID." << std::endl; + return false; + } + if (slave_config["product_id"]) { + product_id_ = slave_config["product_id"].as<uint32_t>(); + } else { + std::cerr << "GenericEcSlave: failed to load drive product ID." << std::endl; + return false; + } + if (slave_config["assign_activate"]) { + assign_activate_ = slave_config["assign_activate"].as<uint32_t>(); + } + + if (slave_config["sm"]) { + for (const auto & sm : slave_config["sm"]) { + ethercat_interface::SMConfig config; + if (config.load_from_config(sm)) { + sm_configs_.push_back(config); + } + } + } + + if (slave_config["sdo"]) { + for (const auto & sdo : slave_config["sdo"]) { + ethercat_interface::SdoConfigEntry config; + if (config.load_from_config(sdo)) { + sdo_config.push_back(config); + } + } + } + + auto channels_nbr = 0; + + if (slave_config["rpdo"]) { + for (auto i = 0ul; i < slave_config["rpdo"].size(); i++) { + channels_nbr += slave_config["rpdo"][i]["channels"].size(); + } + } + if (slave_config["tpdo"]) { + for (auto i = 0ul; i < slave_config["tpdo"].size(); i++) { + channels_nbr += slave_config["tpdo"][i]["channels"].size(); + } + } + + all_channels_.reserve(channels_nbr); + all_channels_skip_list_.reserve(channels_nbr); + channels_nbr = 0; + + if (slave_config["rpdo"]) { + for (auto i = 0ul; i < slave_config["rpdo"].size(); i++) { + auto rpdo_channels_size = slave_config["rpdo"][i]["channels"].size(); + for (auto c = 0ul; c < rpdo_channels_size; c++) { + ethercat_interface::EcPdoChannelManager * channel_info = nullptr; + // Check if the channel is a special data area holding several in memory data + if (slave_config["rpdo"][i]["channels"][c]["data_mapping"]) { + channel_info = new ethercat_interface::EcPdoGroupInterfaceChannelManager; + } else { + channel_info = new ethercat_interface::EcPdoSingleInterfaceChannelManager; + } + + channel_info->pdo_type = ethercat_interface::RPDO; + channel_info->load_from_config(slave_config["rpdo"][i]["channels"][c]); + pdo_channels_info_.push_back(channel_info); + all_channels_.push_back(channel_info->get_pdo_entry_info()); + all_channels_skip_list_.push_back(channel_info->skip); + } + rpdos_.push_back( + { + slave_config["rpdo"][i]["index"].as<uint16_t>(), + (unsigned int)(rpdo_channels_size), + all_channels_.data() + channels_nbr + } + ); + channels_nbr += rpdo_channels_size; + } + } + + if (slave_config["tpdo"]) { + for (auto i = 0ul; i < slave_config["tpdo"].size(); i++) { + auto tpdo_channels_size = slave_config["tpdo"][i]["channels"].size(); + + for (auto c = 0ul; c < tpdo_channels_size; c++) { + ethercat_interface::EcPdoChannelManager * channel_info = nullptr; + // Check if the channel is a special data area holding several in memory data + if (slave_config["tpdo"][i]["channels"][c]["data_mapping"]) { + channel_info = new ethercat_interface::EcPdoGroupInterfaceChannelManager; + } else { + channel_info = new ethercat_interface::EcPdoSingleInterfaceChannelManager; + } + channel_info->pdo_type = ethercat_interface::TPDO; + channel_info->load_from_config(slave_config["tpdo"][i]["channels"][c]); + pdo_channels_info_.push_back(channel_info); + all_channels_.push_back(channel_info->get_pdo_entry_info()); + all_channels_skip_list_.push_back(channel_info->skip); + } + tpdos_.push_back( + { + slave_config["tpdo"][i]["index"].as<uint16_t>(), + (unsigned int)(tpdo_channels_size), + all_channels_.data() + channels_nbr + } + ); + channels_nbr += tpdo_channels_size; + } + } + + // Remove gaps from domain mapping + for (auto i = 0ul; i < all_channels_.size(); i++) { + if (all_channels_[i].index != 0x0000 && all_channels_skip_list_[i] != true) { + domain_map_.push_back(i); + } + } + + return true; + } else { + std::cerr << "GenericEcSlave: failed to load slave configuration: empty configuration" << + std::endl; + return false; + } +} + +bool GenericEcSlave::setup_from_config_file(std::string config_file) +{ + // Read drive configuration from YAML file + try { + slave_config_ = YAML::LoadFile(config_file); + } catch (const YAML::ParserException & ex) { + std::cerr << + "GenericEcSlave: failed to load EtherCAT module configuration " + "(YAML file is incorrect): " << ex.what() << std::endl; + return false; + } catch (const YAML::BadFile & ex) { + std::cerr << + "GenericEcSlave: failed to load EtherCAT module configuration " + "(file path is incorrect or file is damaged): " << ex.what() + << std::endl; + return false; + } + if (!setup_from_config(slave_config_)) { + return false; + } + return true; +} + +void GenericEcSlave::setup_interface_mapping() +{ + for (auto & channel_ptr : pdo_channels_info_) { + auto & channel = *channel_ptr; + for (size_t i = 0; i < channel.number_of_interfaces(); ++i) { + if (channel.has_state_interface_name(i) ) { + std::string interface = "state_interface/" + channel.interface_name(i); + if (parameters_.find(interface) != parameters_.end()) { + const size_t idx = std::stoi(parameters_[interface]); + channel.set_state_interface_index(channel.interface_name(i), idx); + } + } else if (channel.has_command_interface_name(i) ) { + std::string interface = "command_interface/" + channel.interface_name(i); + if (channel.pdo_type == ethercat_interface::RPDO) { + std::string interface = "command_interface/" + channel.interface_name(i); + if (parameters_.find(interface) != parameters_.end()) { + const size_t idx = std::stoi(parameters_[interface]); + channel.set_command_interface_index(channel.interface_name(i), idx); + } + } else { + throw std::runtime_error( + std::string("GenericEcSlave: command interface (") + + "index: " + channel.index_hex_str() + ", " + + "sub_index: " + channel.sub_index_hex_str() + ", " + + "name: " + interface + + ") is not allowed for TPDO channels"); + } + } + } + + channel.setup_interface_ptrs(state_interface_ptr_, command_interface_ptr_); + } +} + +} // namespace ethercat_generic_plugins + +#include <pluginlib/class_list_macros.hpp> + +PLUGINLIB_EXPORT_CLASS(ethercat_generic_plugins::GenericEcSlave, ethercat_interface::EcSlave) diff --git a/ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.cpp b/ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.cpp new file mode 100644 index 0000000..0508de5 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.cpp @@ -0,0 +1,254 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 <map> +#include <pluginlib/class_loader.hpp> +#include "ethercat_interface/ec_slave.hpp" +#include "test_generic_ec_slave.hpp" + +const char test_slave_config[] = + R"( +# Configuration file for Test Slave +vendor_id: 0x00000011 +product_id: 0x07030924 +assign_activate: 0x0321 # DC Synch register +sdo: # sdo data to be transferred at slave startup + - {index: 0x60C2, sub_index: 1, type: int8, value: 10} + - {index: 0x60C2, sub_index: 2, type: int8, value: -3} + - {index: 0x6098, sub_index: 0, type: int8, value: 35} + - {index: 0x6099, sub_index: 0, type: int32, value: 0} +rpdo: # Receive PDO Mapping + - index: 0x1607 + channels: + - {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan} + - {index: 0x60ff, sub_index: 0, type: int32, command_interface: velocity, default: 0} + - {index: 0x6071, sub_index: 0, type: int16, command_interface: effort, default: -5, factor: 2, offset: 10} + - {index: 0x6072, sub_index: 0, type: int16, command_interface: ~, default: 1000} + - {index: 0x6040, sub_index: 0, type: uint16, command_interface: ~, default: 0} + - {index: 0x6060, sub_index: 0, type: int8, command_interface: ~, default: 8} +tpdo: # Transmit PDO Mapping + - index: 0x1a07 + channels: + - {index: 0x6064, sub_index: 0, type: int32, state_interface: position} + - {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} + - {index: 0x6077, sub_index: 0, type: int16, state_interface: effort, factor: 5, offset: 15} + - {index: 0x6041, sub_index: 0, type: uint16, state_interface: ~} + - {index: 0x6061, sub_index: 0, type: int8, state_interface: ~} + - index: 0x1a45 + channels: + - {index: 0x2205, sub_index: 1, type: int16, state_interface: analog_input1} + - {index: 0x2205, sub_index: 2, type: int16, state_interface: analog_input2} +sm: # Sync Manager + - {index: 0, type: output, pdo: ~, watchdog: disable} + - {index: 1, type: input, pdo: ~, watchdog: disable} + - {index: 2, type: output, pdo: rpdo, watchdog: enable} + - {index: 3, type: input, pdo: tpdo, watchdog: disable} +)"; + +void GenericEcSlaveTest::SetUp() +{ + plugin_ = std::make_unique<FriendGenericEcSlave>(); +} + +void GenericEcSlaveTest::TearDown() +{ + plugin_.reset(nullptr); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupNoSlaveConfig) +{ + SetUp(); + std::vector<double> state_interface = {0}; + std::vector<double> command_interface = {0}; + std::unordered_map<std::string, std::string> slave_parameters; + // setup failed, 'slave_config' parameter not set + ASSERT_EQ( + plugin_->setupSlave( + slave_parameters, + &state_interface, + &command_interface + ), + false + ); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupMissingFileSlaveConfig) +{ + SetUp(); + std::vector<double> state_interface = {0}; + std::vector<double> command_interface = {0}; + std::unordered_map<std::string, std::string> slave_parameters; + slave_parameters["slave_config"] = "slave_config.yaml"; + // setup failed, 'slave_config.yaml' file not set + ASSERT_EQ( + plugin_->setupSlave( + slave_parameters, + &state_interface, + &command_interface + ), + false + ); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupSlaveFromConfig) +{ + SetUp(); + ASSERT_EQ( + plugin_->setup_from_config(YAML::Load(test_slave_config)), + true + ); + ASSERT_EQ(plugin_->vendor_id_, 0x00000011); + ASSERT_EQ(plugin_->product_id_, 0x07030924); + ASSERT_EQ(plugin_->assign_activate_, 0x0321); + + ASSERT_EQ(plugin_->rpdos_.size(), 1); + ASSERT_EQ(plugin_->rpdos_[0].index, 0x1607); + + ASSERT_EQ(plugin_->tpdos_.size(), 2); + ASSERT_EQ(plugin_->tpdos_[0].index, 0x1a07); + ASSERT_EQ(plugin_->tpdos_[1].index, 0x1a45); + + auto channels = plugin_->pdo_channels_info_; + ASSERT_EQ(channels[1]->interface_name(), "velocity"); + ASSERT_EQ(channels[2]->data().factor, 2); + ASSERT_EQ(channels[2]->data().offset, 10); + ASSERT_EQ(channels[3]->data().default_value, 1000); + ASSERT_TRUE(std::isnan(channels[0]->data().default_value)); + ASSERT_EQ(channels[4]->interface_name(), "null"); + ASSERT_EQ(channels[12]->interface_name(), "analog_input2"); + ASSERT_EQ(channels[4]->data_type(), "uint16"); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupPdoChannels) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_slave_config)); + std::vector<ec_pdo_entry_info_t> channels( + plugin_->channels(), + plugin_->channels() + plugin_->all_channels_.size() + ); + + ASSERT_EQ(channels.size(), 13); + ASSERT_EQ(channels[0].index, 0x607a); + ASSERT_EQ(channels[11].index, 0x2205); + ASSERT_EQ(channels[11].subindex, 0x01); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupSyncs) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_slave_config)); + plugin_->setup_syncs(); + std::vector<ec_sync_info_t> syncs( + plugin_->syncs(), + plugin_->syncs() + plugin_->syncSize() + ); + + ASSERT_EQ(syncs.size(), 5); + ASSERT_EQ(syncs[1].index, 1); + ASSERT_EQ(syncs[1].dir, EC_DIR_INPUT); + ASSERT_EQ(syncs[1].n_pdos, 0); + ASSERT_EQ(syncs[1].watchdog_mode, EC_WD_DISABLE); + ASSERT_EQ(syncs[2].dir, EC_DIR_OUTPUT); + ASSERT_EQ(syncs[2].n_pdos, 1); + ASSERT_EQ(syncs[3].index, 3); + ASSERT_EQ(syncs[3].dir, EC_DIR_INPUT); + ASSERT_EQ(syncs[3].n_pdos, 2); + ASSERT_EQ(syncs[3].watchdog_mode, EC_WD_DISABLE); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupDomains) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_slave_config)); + std::map<unsigned int, std::vector<unsigned int>> domains; + plugin_->domains(domains); + + ASSERT_EQ(domains[0].size(), 13); + ASSERT_EQ(domains[0][0], 0); + ASSERT_EQ(domains[0][12], 12); +} + +TEST_F(GenericEcSlaveTest, EcReadTPDOToStateInterface) +{ + SetUp(); + std::unordered_map<std::string, std::string> slave_parameters; + std::vector<double> state_interface = {0, 0}; + plugin_->state_interface_ptr_ = &state_interface; + slave_parameters["state_interface/effort"] = "1"; + plugin_->parameters_ = slave_parameters; + plugin_->setup_from_config(YAML::Load(test_slave_config)); + plugin_->setup_interface_mapping(); + ASSERT_EQ(plugin_->pdo_channels_info_[8]->state_interface_index(), 1); + uint8_t domain_address[2]; + EC_WRITE_S16(domain_address, 42); + plugin_->processData(8, domain_address); + ASSERT_EQ(plugin_->state_interface_ptr_->at(1), 5 * 42 + 15); +} + +TEST_F(GenericEcSlaveTest, EcWriteRPDOFromCommandInterface) +{ + SetUp(); + std::unordered_map<std::string, std::string> slave_parameters; + std::vector<double> command_interface = {0, 42}; + plugin_->command_interface_ptr_ = &command_interface; + slave_parameters["command_interface/effort"] = "1"; + plugin_->parameters_ = slave_parameters; + plugin_->setup_from_config(YAML::Load(test_slave_config)); + plugin_->setup_interface_mapping(); + auto channels = plugin_->pdo_channels_info_; + ASSERT_EQ(channels[2]->command_interface_index(), 1); + uint8_t domain_address[2]; + plugin_->processData(2, domain_address); + ASSERT_EQ(channels[2]->data().last_value, 2 * 42 + 10); + ASSERT_EQ(EC_READ_S16(domain_address), 2 * 42 + 10); +} + +TEST_F(GenericEcSlaveTest, EcWriteRPDODefaultValue) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_slave_config)); + plugin_->setup_interface_mapping(); + uint8_t domain_address[2]; + plugin_->processData(2, domain_address); + ASSERT_EQ(plugin_->pdo_channels_info_[2]->data().last_value, -5); + ASSERT_EQ(EC_READ_S16(domain_address), -5); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupSDOConfig) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_slave_config)); + ASSERT_EQ(plugin_->sdo_config[0].index, 0x60C2); + ASSERT_EQ(plugin_->sdo_config[0].sub_index, 1); + ASSERT_EQ(plugin_->sdo_config[1].sub_index, 2); + ASSERT_EQ(plugin_->sdo_config[0].data_size(), 1); + ASSERT_EQ(plugin_->sdo_config[0].data, 10); + ASSERT_EQ(plugin_->sdo_config[2].index, 0x6098); + ASSERT_EQ(plugin_->sdo_config[3].data_type, "int32"); + ASSERT_EQ(plugin_->sdo_config[3].data_size(), 4); +} + +TEST_F(GenericEcSlaveTest, SlaveSetupSyncManagerConfig) +{ + SetUp(); + plugin_->setup_from_config(YAML::Load(test_slave_config)); + ASSERT_EQ(plugin_->sm_configs_.size(), 4); + ASSERT_EQ(plugin_->sm_configs_[0].index, 0); + ASSERT_EQ(plugin_->sm_configs_[0].type, EC_DIR_OUTPUT); + ASSERT_EQ(plugin_->sm_configs_[0].watchdog, EC_WD_DISABLE); + ASSERT_EQ(plugin_->sm_configs_[0].pdo_name, "null"); + ASSERT_EQ(plugin_->sm_configs_[2].pdo_name, "rpdo"); + ASSERT_EQ(plugin_->sm_configs_[2].watchdog, EC_WD_ENABLE); +} diff --git a/ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.hpp b/ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.hpp new file mode 100644 index 0000000..a78e482 --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/test/test_generic_ec_slave.hpp @@ -0,0 +1,51 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 TEST_GENERIC_EC_SLAVE_HPP_ +#define TEST_GENERIC_EC_SLAVE_HPP_ + +#include <memory> +#include <string> +#include <vector> +#include <unordered_map> + +#include "gmock/gmock.h" + +#include "ethercat_generic_plugins/generic_ec_slave.hpp" + +// subclassing and friending so we can access member variables +class FriendGenericEcSlave : public ethercat_generic_plugins::GenericEcSlave +{ + FRIEND_TEST(GenericEcSlaveTest, SlaveSetupSlaveFromConfig); + FRIEND_TEST(GenericEcSlaveTest, SlaveSetupPdoChannels); + FRIEND_TEST(GenericEcSlaveTest, SlaveSetupSyncs); + FRIEND_TEST(GenericEcSlaveTest, SlaveSetupDomains); + FRIEND_TEST(GenericEcSlaveTest, EcReadTPDOToStateInterface); + FRIEND_TEST(GenericEcSlaveTest, EcWriteRPDOFromCommandInterface); + FRIEND_TEST(GenericEcSlaveTest, EcWriteRPDODefaultValue); + FRIEND_TEST(GenericEcSlaveTest, SlaveSetupSDOConfig); + FRIEND_TEST(GenericEcSlaveTest, SlaveSetupSyncManagerConfig); +}; + +class GenericEcSlaveTest : public ::testing::Test +{ +public: + void SetUp(); + void TearDown(); + +protected: + std::unique_ptr<FriendGenericEcSlave> plugin_; +}; + +#endif // TEST_GENERIC_EC_SLAVE_HPP_ diff --git a/ethercat_generic_plugins/ethercat_generic_slave/test/test_load_ec_modules.cpp b/ethercat_generic_plugins/ethercat_generic_slave/test/test_load_ec_modules.cpp new file mode 100644 index 0000000..19942cc --- /dev/null +++ b/ethercat_generic_plugins/ethercat_generic_slave/test/test_load_ec_modules.cpp @@ -0,0 +1,26 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 <gtest/gtest.h> +#include <memory> + +#include <pluginlib/class_loader.hpp> +#include "ethercat_interface/ec_slave.hpp" + +TEST(TestLoadGenericEcSlave, load_ec_module) +{ + pluginlib::ClassLoader<ethercat_interface::EcSlave> ec_loader_{ + "ethercat_interface", "ethercat_interface::EcSlave"}; + ASSERT_NO_THROW(ec_loader_.createSharedInstance("ethercat_generic_plugins/GenericEcSlave")); +} diff --git a/ethercat_interface/CMakeLists.txt b/ethercat_interface/CMakeLists.txt new file mode 100644 index 0000000..12c0699 --- /dev/null +++ b/ethercat_interface/CMakeLists.txt @@ -0,0 +1,90 @@ +cmake_minimum_required(VERSION 3.8) +project(ethercat_interface) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_ros REQUIRED) +find_package(rclcpp REQUIRED) + +# EtherLab +set(ETHERLAB_DIR /usr/local/etherlab) +set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) + +find_library(ETHERCAT_LIB ethercat HINTS ${ETHERLAB_DIR}/lib) + +ament_export_include_directories( + include + ${ETHERLAB_DIR}/include +) + +add_library( + ${PROJECT_NAME} + SHARED + src/ec_master.cpp + src/ec_safety.cpp + src/ec_pdo_channel_manager.cpp + src/ec_pdo_single_interface_channel_manager.cpp + src/ec_pdo_group_interface_channel_manager.cpp +) + +target_include_directories( + ${PROJECT_NAME} + PRIVATE + include + ${ETHERLAB_DIR}/include +) + +target_link_libraries(${PROJECT_NAME} ${ETHERCAT_LIB}) + +ament_target_dependencies( + ${PROJECT_NAME} + rclcpp +) + +# INSTALL +install( + TARGETS ${PROJECT_NAME} + DESTINATION lib +) +install( + DIRECTORY include/ + DESTINATION include +) + +if(BUILD_TESTING) + # find_package(ament_cmake_gtest REQUIRED) + find_package(ament_lint_auto REQUIRED) + find_package(yaml_cpp_vendor REQUIRED) + ament_lint_auto_find_test_dependencies() + + # Test PdoChannelManager + ament_add_gmock( + test_ec_pdo_channel_manager + test/test_ec_pdo_channel_manager.cpp + ) + target_include_directories(test_ec_pdo_channel_manager PRIVATE include ${ETHERLAB_DIR}/include) + ament_target_dependencies(test_ec_pdo_channel_manager + yaml_cpp_vendor + ) + + target_link_libraries(test_ec_pdo_channel_manager + ${PROJECT_NAME} + ) +endif() + +## EXPORTS +ament_export_include_directories( + include +) +ament_export_libraries( + ${PROJECT_NAME} + ${ETHERCAT_LIBRARY} +) +ament_export_dependencies( + rclcpp +) +ament_package() diff --git a/ethercat_interface/include/ethercat_interface/ec_master.hpp b/ethercat_interface/include/ethercat_interface/ec_master.hpp new file mode 100644 index 0000000..bf0603a --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_master.hpp @@ -0,0 +1,218 @@ +// Copyright 2022 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_INTERFACE__EC_MASTER_HPP_ +#define ETHERCAT_INTERFACE__EC_MASTER_HPP_ + +#include <ecrt.h> + +#include <time.h> +#include <string> +#include <vector> +#include <map> +#include <chrono> + +#include "rclcpp/rclcpp.hpp" + +#include "ethercat_interface/ec_slave.hpp" + + +namespace ethercat_interface +{ + +inline uint64_t EC_NEWTIMEVAL2NANO(struct timespec & TV) +{ + return (TV.tv_sec - 946684800ULL) * 1000000000ULL + TV.tv_nsec; +} + +inline uint64_t TIMESPEC2NS(struct timespec & TV) +{ + return (uint64_t)TV.tv_sec * 1000000000ULL + TV.tv_nsec; +} + +class EcMaster +{ +public: + explicit EcMaster(const unsigned int master = 0); + virtual ~EcMaster(); + + /** \brief check if master is reserved */ + bool checkMaster( ) {if (NULL==master_) return false; return true;} + + /** \brief add a slave device to the master + * alias and position can be found by running the following command + * /opt/etherlab/bin$ sudo ./ethercat slaves + * look for the "A B:C STATUS DEVICE" (e.g. B=alias, C=position) + */ + void addSlave(uint16_t alias, uint16_t position, EcSlave * slave); + + /** \brief add a slave device to the master + * alias and position should have been set + * before calling this function. + */ + bool addSlave(EcSlave * slave); + + /** \brief check compatibility between slave requested and slave detected */ + bool checkSlaveIdentity(EcSlave * slave); + + /** \brief configure slave using SDO + */ + int configSlaveSdo(uint16_t slave_position, SdoConfigEntry sdo_config, uint32_t * abort_code); + + /** call after adding all slaves, and before update */ + bool activate(); + + /** perform one EtherCAT cycle, passing the domain to the slaves */ + virtual bool update(uint32_t domain = 0); + + /** stop the control loop. use within callback, or from a separate thread. */ + virtual void stop(); + + /** time of last ethercat update, since calling run. stops if stop called. + * returns actual time. use elapsedCycles()/frequency for discrete time at last update. */ + virtual double elapsedTime(); + + /** number of EtherCAT updates since calling run. */ + virtual uint64_t elapsedCycles(); + + void setCtrlFrequency(double frequency) + { + interval_ = 1000000000.0 / frequency; + } + + void setClockReferenceId(uint16_t clock_reference_id) + { + reference_clock_postition_ = clock_reference_id; + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "reference clock id : %u, %u", reference_clock_postition_, clock_reference_id ); + } + + /** + * @brief get the time interval between control loops in nanoseconds + * + * @return uint32_t time interval in nanoseconds + */ + uint32_t getInterval() {return interval_;} + + virtual bool readData(uint32_t domain = 0); + virtual void writeData(uint32_t domain = 0); + + /** check if all slaves are operational + * @return true if all slaves are operational, false otherwise + */ + bool checkAllSlavesOperational(); + +protected: + + /** start and current time */ + std::chrono::time_point<std::chrono::system_clock> start_t_, curr_t_; + + // EtherCAT Control + + /** register a domain of the slave */ + struct DomainInfo; + void registerPDOInDomain( + std::vector<uint32_t> & channel_indices, + DomainInfo * domain_info, + EcSlave * slave); + + /** check for change in the domain state */ + bool checkDomainState(uint32_t domain); + + /** check for change in the master state */ + void checkMasterState(); + + /** check for change in the slave states */ + void checkSlaveStates(); + + /** print warning message to logger */ + inline + static + void printWarning(const std::string & message) + { + RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"), "WARNING. Master. %s", message.c_str()); + } + + /** EtherCAT master data */ + ec_master_t * master_ = NULL; + ec_master_state_t master_state_ = {}; + + /** data for a single domain */ + struct DomainInfo + { + explicit DomainInfo(ec_master_t * master); + ~DomainInfo(); + + ec_domain_t * domain = NULL; + ec_domain_state_t domain_state = {}; + uint8_t * domain_pd = NULL; //< pointer to process domain data + + /** domain pdo registration array. + * do not modify after active(), or may invalidate */ + std::vector<ec_pdo_entry_reg_t> domain_regs; + + /** slave's pdo and in memory data entries in the domain */ + struct Entry + { + EcSlave * slave = NULL; + int num_pdos = 0; + uint32_t * offset = NULL; + uint32_t * bit_position = NULL; + int num_in_memory_data = 0; + uint32_t * offset_in_memory = NULL; + }; + + std::vector<Entry> entries; + }; + + /** map from domain index to domain info */ + std::map<uint32_t, DomainInfo *> domain_info_; + + /** data needed to check slave state */ + struct SlaveInfo + { + EcSlave * slave = NULL; + ec_slave_config_t * config = NULL; + ec_slave_config_state_t config_state = {0, 0, 0}; + }; + + std::vector<SlaveInfo> slave_info_; + + /** counter of control loops */ + uint64_t update_counter_ = 0; + + /** frequency to check for master or slave state change. + * state checked every frequency_ control loops */ + uint32_t check_state_frequency_ = 10; + + /** time interval between control loops in nanoseconds */ + uint32_t interval_; + + //bool write_data_ = false; + +protected: + friend struct EcTransferInfo; + + rclcpp::Clock monotonic_clock_; + rclcpp::Duration ecat_timeout_ = rclcpp::Duration(10, 0); // 10 seconds + rclcpp::Time time_begin ; + bool ecat_communication_timeout_start_ = false; + uint16_t reference_clock_postition_; + + struct timespec last_time_; + +}; + +} // namespace ethercat_interface + +#endif // ETHERCAT_INTERFACE__EC_MASTER_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_pdo_channel_manager.hpp b/ethercat_interface/include/ethercat_interface/ec_pdo_channel_manager.hpp new file mode 100644 index 0000000..977016c --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_pdo_channel_manager.hpp @@ -0,0 +1,249 @@ +// Copyright 2023-2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + + +#ifndef ETHERCAT_INTERFACE__EC_PDO_CHANNEL_MANAGER_HPP_ +#define ETHERCAT_INTERFACE__EC_PDO_CHANNEL_MANAGER_HPP_ + +#include <yaml-cpp/yaml.h> +#include <ecrt.h> + +#include <string> +#include <vector> +#include <limits> +#include <stdexcept> +#include <utility> +#include <sstream> + +namespace ethercat_interface +{ + +enum PdoType +{ + RPDO = 0, // < Receive PDO, Master out to Slave in (MoSi) + TPDO = 1 // < Transmit PDO, Master in from Slave out (MiSo) +}; + +/** @brief Global table that stores all the names of the known types */ +extern const std::vector<std::string> ec_pdo_channel_data_types; + +/** @brief Global table that stores all the number of bits of the known types */ +extern const std::vector<uint8_t> ec_pdo_channel_data_bits; + +/** @brief Returns the index of a data type in the table of types */ +size_t typeIdx(const std::string & type); + +/** @brief Returns the number of bits associated with a data type */ +uint8_t type2bits(const std::string & type); + +/** @brief Returns the type name */ +std::string id_and_bits_to_type(size_t i, uint8_t bits); + +/** @brief Check if the definition of a type is correct + * @param[in] type the name of the type to check + * @param[in] mask the mask associated with the type to check the compatibility + * @return true if the type is correct, false otherwise + */ +bool check_type(const std::string & type, uint8_t mask); + +/** @brief Global table that stores all the names of the recorded state interfaces */ +extern std::vector<std::string> all_state_interface_names; + +/** @brief Global table that stores all the names of the recorded command interfaces */ +extern std::vector<std::string> all_command_interface_names; + +/** @brief The type of the functions used to read from EtherCAT frame and return a double + * to be compatible with a ROS2 control state interface */ +typedef double (* SingleReadFunctionType)(uint8_t * domain_address, uint8_t data_mask); + +/** @brief Global table that stores each read function associated with a data type */ +extern const SingleReadFunctionType ec_pdo_single_read_functions[]; + +/** @brief The type of the functions used to write to EtherCAT frame from a double + * to be compatible with a ROS2 control command interface */ +typedef void (* SingleWriteFunctionType)(uint8_t * domain_address, double value, uint8_t data_mask); + +/** @brief Global table that stores each write function associated with a data type */ +extern const SingleWriteFunctionType ec_pdo_single_write_functions[]; + +struct InterfaceData +{ + bool override_command = false; + uint8_t mask = 255; + double default_value = std::numeric_limits<double>::quiet_NaN(); + /** last_value stores either: + * - the last read value modified by mask, factor and offset + * - the last written value modified by mask, factor and offset + * */ + double last_value = std::numeric_limits<double>::quiet_NaN(); + double factor = 1; + double offset = 0; +}; + + +/** + * @brief Virtual class for managing a single PDO channel + * @details The EcPdoChannelManager class is used to manage a single PDO + * channel. It is used to read and write data to the channel, and to update + * the ROS2 control interfaces (state and command). + * The PDO can correspond to a single interface, or to a group of interfaces. + * Hence the specializations of this class to manage these two cases. + * The most common case is the single interface case, where the PDO corresponds + * to a single interface. It is less common to have a group of interfaces, + * but it is still possible and useful (see the example below). + * @example Single interface example: a joint position PDO. + * The channel manager will read the joint position from the PDO and write the + * joint position to the PDO. The joint position will be updated in the state + * interface, and the joint position will be read from the command interface. + * The data in the channel may be an integer corresponding to coder ticks. + * The coder ticks will be converted to radians and stored in the state + * interface. The joint position in radians will be read from the command + * interface and converted to coder ticks and written to the PDO. + * @example Group of interfaces example: a set of states can be encoded in an + * octet, each bit corresponding to a state. It is particularly useful from a + * coding perspective to have one interface per state. The channel manager will + * read the octet from the PDO and update a group of state interfaces + * corresponding to each bit in the octet related to a state. The channel + * manager will also read the group of command interfaces and write the single + * octet to the PDO that encodes all the states. + * @note More generally the EcGroupInterfacePdoChannelManager class is used + * when some specific data encoding is used to represent a group of + * interfaces in the EtherCAT memory frame but associated to a single PDO. + */ +class EcPdoChannelManager +{ +public: + EcPdoChannelManager(); + EcPdoChannelManager(const EcPdoChannelManager &) = delete; + virtual ~EcPdoChannelManager() = 0; + +public: +//======================= +/** @name Setup methods + * @brief Methods to setup the PDO channel manager + * @{ + */ + + /** @brief Record the pointers to the state and command interfaces */ + void setup_interface_ptrs( + std::vector<double> * state_interface, + std::vector<double> * command_interface); + + /** @brief Load the channel configuration from a YAML node */ + virtual bool load_from_config(YAML::Node channel_config) = 0; + +/** @} */ // < end of Setup methods +//======================= + +public: +//======================= +/** @name Data exchange methods + * @brief Methods to read and write data from/to the PDO + * @{ + */ + virtual double ec_read(uint8_t * domain_address, size_t i = 0) = 0; + + /// @brief Perform an ec_read and update the state interface + virtual void ec_read_to_interface(uint8_t * domain_address) = 0; + + virtual void ec_write(uint8_t * domain_address, double value, size_t i = 0) = 0; + + /// @brief Perform an ec_write and update the command interface + virtual void ec_write_from_interface(uint8_t * domain_address) = 0; + + /// @brief Update the state and command interfaces + virtual void ec_update(uint8_t * domain_address); + +/** @} */ // < end of Data exchange methods +//======================= + +public: + /** @brief Get the PDO entry info as it should be recorded by the master*/ + ec_pdo_entry_info_t get_pdo_entry_info(); + +public: + PdoType pdo_type; + uint16_t index; + uint8_t sub_index; + + inline + std::string index_hex_str() const + { + std::stringstream ss; + ss << "0x" << std::hex << index; + return ss.str(); + } + + inline + std::string sub_index_hex_str() const + { + std::stringstream ss; + ss << "0x" << std::hex << sub_index; + return ss.str(); + } + + /** @brief Get the number of bits in the PDO */ + inline uint8_t pdo_bits() const {return bits_;} + + /** @brief Get the string describing the data type of the PDO */ + inline + std::string pdo_data_type() const + { + return id_and_bits_to_type(data_type_idx_, bits_); + } + + /** @brief Get the string describing the type of the data associated with interface i + * @param i The index of the interface in the group of interfaces managed by the PDO channel. In case of a single interface, i must be 0. + */ + virtual std::string data_type(size_t i = 0) const = 0; + + /** @brief Get the data */ + virtual InterfaceData & data(size_t i = 0) = 0; + + /** @brief Get the data */ + virtual const InterfaceData & data(size_t i = 0) const = 0; + + bool allow_ec_write = true; // < Is the PDO channel writable ? + +public: + bool skip = false; // < Skip the PDO channel in ? TODO(@yguel@unistra.fr) + +public: + virtual size_t number_of_interfaces() const = 0; + virtual void setup_managed_interfaces() = 0; + virtual size_t number_of_managed_interfaces() const = 0; + virtual std::string interface_name(size_t i = 0) const = 0; + virtual std::pair<bool, size_t> is_interface_managed(std::string interface_name) const = 0; + virtual void set_state_interface_index(const std::string & interface_name, size_t index) = 0; + virtual void set_command_interface_index(const std::string & interface_name, size_t index) = 0; + virtual size_t state_interface_index(size_t i = 0) const = 0; + virtual size_t command_interface_index(size_t i = 0) const = 0; + virtual bool has_interface_name(size_t i = 0) const = 0; + virtual bool has_state_interface_name(size_t i = 0) const = 0; + virtual bool has_command_interface_name(size_t i = 0) const = 0; + +protected: + uint8_t bits_; // < Number of bits declared in the PDO + uint8_t data_type_idx_; // < Index to the table of types to infer the data type + +protected: + std::vector<double> * command_interface_ptr_; + std::vector<double> * state_interface_ptr_; +}; + +} // < namespace ethercat_interface +#endif // ETHERCAT_INTERFACE__EC_PDO_CHANNEL_MANAGER_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_pdo_group_interface_channel_manager.hpp b/ethercat_interface/include/ethercat_interface/ec_pdo_group_interface_channel_manager.hpp new file mode 100644 index 0000000..f34ee11 --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_pdo_group_interface_channel_manager.hpp @@ -0,0 +1,278 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#ifndef ETHERCAT_INTERFACE__EC_PDO_GROUP_INTERFACE_CHANNEL_MANAGER_HPP_ +#define ETHERCAT_INTERFACE__EC_PDO_GROUP_INTERFACE_CHANNEL_MANAGER_HPP_ + +#include <utility> // for std::pair +#include <limits> +#include <string> +#include <vector> +#include "ethercat_interface/ec_pdo_channel_manager.hpp" + +namespace ethercat_interface +{ + +struct InterfaceDataWithAddrOffset : public InterfaceData +{ + InterfaceDataWithAddrOffset() + : InterfaceData(), + addr_offset(0) {} + + explicit InterfaceDataWithAddrOffset(const InterfaceData & data) + : InterfaceData(data), + addr_offset(0) {} + + InterfaceDataWithAddrOffset(const InterfaceData & data, size_t addr_offset) + : InterfaceData(data), + addr_offset(addr_offset) {} + + size_t addr_offset = 0; + uint8_t bits = 0; + uint8_t data_type_idx = 0; +}; + +/** + * @brief Class to manage a PDO channel corresponding to a group of interfaces + */ +class EcPdoGroupInterfaceChannelManager : public EcPdoChannelManager +{ +public: + EcPdoGroupInterfaceChannelManager(); + EcPdoGroupInterfaceChannelManager(const EcPdoGroupInterfaceChannelManager &) = delete; + ~EcPdoGroupInterfaceChannelManager(); + +public: +//======================= +/** @name Setup methods + * @brief Methods to setup the PDO channel manager + * @{ + */ + +/// @brief Load the channel configuration from a YAML node + bool load_from_config(YAML::Node channel_config); + +/** @} */ // end of Setup methods +//======================= + +public: +//======================= +/** @name Data exchange methods + * @brief Methods to read and write data from/to the PDO + * @{ + */ + + /** @brief Read the data from the PDO applying data mask, factor and offset + * @param i The index of the interface to read + * @param domain_address The pdo start address in the domain to read from, the read address will be domain_address + v_data[i].addr_offset + * @returns The value read from the domain + */ + double ec_read(uint8_t * domain_address, size_t i = 0); + + /// @brief Perform an ec_read and update the state interface + void ec_read_to_interface(uint8_t * domain_address); + + /** @brief Write the value to the PDO applying data mask, factor and offset + * @param i The index of the interface to write + * @param domain_address The pdo start address in the domain to write into, the write address will be domain_address + v_data[i].addr_offset + * @param value The value to write + */ + void ec_write(uint8_t * domain_address, double value, size_t i = 0); + + /// @brief Perform an ec_write and update the command interface + void ec_write_from_interface(uint8_t * domain_address); + +/** @} */ // < end of Data exchange methods +//======================= + +public: + std::vector<InterfaceDataWithAddrOffset> v_data; + +public: + inline + size_t number_of_interfaces() const + { + return v_data.size(); + } + + inline + size_t number_of_managed_interfaces() const + { + return managed_.size(); + } + + void setup_managed_interfaces(); + + std::string interface_name(size_t i = 0) const; + + std::pair<bool, size_t> is_interface_managed(std::string name) const; + + size_t channel_state_interface_index(const std::string & name) const; + + size_t channel_command_interface_index(const std::string & name) const; + + std::string data_type(size_t i = 0) const; + + size_t state_interface_index(size_t i = 0) const; + size_t command_interface_index(size_t i = 0) const; + +public: + inline + void set_state_interface_index(const std::string & interface_name, size_t index) + { + size_t i = channel_state_interface_index(interface_name); + interface_ids_.at(i) = index; + } + + inline + void set_command_interface_index(const std::string & interface_name, size_t index) + { + size_t i = channel_command_interface_index(interface_name); + interface_ids_.at(i) = index; + } + + inline + bool is_interface_defined(size_t i) const + { + return std::numeric_limits<size_t>::max() != interface_ids_.at(i); + } + + inline + bool is_state_interface_defined(size_t i) const + { + return is_interface_defined(i) && !is_command_interface_.at(i); + } + + inline + bool is_command_interface_defined(size_t i) const + { + return is_interface_defined(i) && is_command_interface_.at(i); + } + + inline + bool has_interface_name(size_t i = 0) const + { + return 0 != interface_name_ids_.at(i); + } + + inline bool has_state_interface_name(size_t i = 0) const + { + return has_interface_name(i) && !is_command_interface_.at(i); + } + + inline bool has_command_interface_name(size_t i = 0) const + { + return has_interface_name(i) && is_command_interface_.at(i); + } + +public: + inline + InterfaceData & data(size_t i = 0) + { + return v_data.at(i); + } + + inline + const InterfaceData & data(size_t i = 0) const + { + return v_data.at(i); + } + +protected: +/** @brief Create the necessary allocations to add a new interface */ + void allocate_for_new_interface(); + +/** @brief Add a state interface named name + * @details If the interface is already present, the function does nothing and + * returns the index of the interface, otherwise it adds the interface and + * returns its index + * + * @param[in] name the name of the interface to add + * @returns the index for the added interface in all the vectors + * (interface_ids_, interface_name_ids_, read_functions_, data, + * write_functions_) + * + */ + size_t add_state_interface(const std::string & name); + +/** @brief Add a data without interface + * @details The function adds a data without interface and returns the index + * of the data in all the vectors (interface_ids_, interface_name_ids_, + * read_functions_, data, write_functions_) + * @returns the index for the added data in all the vectors + */ + size_t add_data_without_interface(); + +/** @brief Add a command interface named name + * @details If the interface is already present, the function does nothing and + * returns the index of the interface, otherwise it adds the interface and + * returns its index + * + * @param[in] name the name of the interface to add + * @returns the index for the added interface in all the vectors + * (command_interface_ids_, command_interface_name_ids_, write_functions_, data + * but also state_interface_ids_, state_interface_name_ids_, + * read_functions_) + * + */ + size_t add_command_interface(const std::string & name); + +protected: + /** @brief Indices of the state/or command interfaces in the ros2 control + * state interface or command interface vector + * @details If the index is not set, the value is std::numeric_limits<size_t>::max() + * To know which type of interface vector the index refers to, it is necessary to + * look into the is_command_interface_ vector. + */ + std::vector<size_t> interface_ids_; + + /** @brief Store a boolean indicating if the interface is a command interface + * or a state interface + */ + std::vector<bool> is_command_interface_; + + /** @brief Stores the function used to read the data from the EtherCAT + * frame for each interface */ + std::vector<SingleReadFunctionType> read_functions_; + + /** @brief Stores the function used to write the data to the EtherCAT + * frame for each interface */ + std::vector<SingleWriteFunctionType> write_functions_; + + /** @brief Stores the index to the name of the interfaces + * @details The index of the name of the interfaces is stored in the same + * order as the interfaces in the data vector. To know if the interface is + * a command or a state interface, it is necessary to look into the + * is_command_interface_ vector. + * If the interface is a command interface then the index refers to a name in + * the all_command_interface_names vector, otherwise it refers to a name in the + * all_state_interface_names vector. + * If the interface is not defined, the value is 0 + */ + std::vector<size_t> interface_name_ids_; + + /** @brief Indices of the interfaces that are either state or command interfaces + * @details The indices are stored in the same order as the interfaces in the + * data vector. It stores only the indices of the interfaces index idx where + * interface_name_ids_[idx] is not 0. + */ + std::vector<size_t> managed_; +}; + +} // < namespace ethercat_interface + + +#endif // ETHERCAT_INTERFACE__EC_PDO_GROUP_INTERFACE_CHANNEL_MANAGER_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_pdo_single_interface_channel_manager.hpp b/ethercat_interface/include/ethercat_interface/ec_pdo_single_interface_channel_manager.hpp new file mode 100644 index 0000000..d1842a2 --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_pdo_single_interface_channel_manager.hpp @@ -0,0 +1,224 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#ifndef ETHERCAT_INTERFACE__EC_PDO_SINGLE_INTERFACE_CHANNEL_MANAGER_HPP_ +#define ETHERCAT_INTERFACE__EC_PDO_SINGLE_INTERFACE_CHANNEL_MANAGER_HPP_ + +#include <utility> // for std::pair +#include <limits> +#include <string> +#include <vector> +#include "ethercat_interface/ec_pdo_channel_manager.hpp" + +namespace ethercat_interface +{ + +/** + * @brief Class to manage a PDO channel corresponding to a single interface + */ +class EcPdoSingleInterfaceChannelManager : public EcPdoChannelManager, public InterfaceData +{ +public: + EcPdoSingleInterfaceChannelManager(); + EcPdoSingleInterfaceChannelManager(const EcPdoSingleInterfaceChannelManager &) = delete; + ~EcPdoSingleInterfaceChannelManager(); + +public: +//======================= +/** @name Setup methods + * @brief Methods to setup the PDO channel manager + * @{ + */ + + /// @brief Load the channel configuration from a YAML node + bool load_from_config(YAML::Node channel_config); + +/** @} */ // end of Setup methods +//======================= + +public: +//======================= +/** @name Data exchange methods + * @brief Methods to read and write data from/to the PDO + * @{ + */ + + /// @brief Read the data from the PDO applying data mask, factor and offset + double ec_read(uint8_t * domain_address, size_t i = 0); + + /// @brief Perform an ec_read and update the state interface + void ec_read_to_interface(uint8_t * domain_address); + + /// @brief Write the value to the PDO applying data mask, factor and offset + void ec_write(uint8_t * domain_address, double value, size_t i = 0); + + /// @brief Perform an ec_write and update the command interface + void ec_write_from_interface(uint8_t * domain_address); + +/** @} */ // < end of Data exchange methods +//======================= + +public: + inline + size_t number_of_interfaces() const + { + return 1; + } + + inline + size_t number_of_managed_interfaces() const + { + return (state_interface_name_idx_ + command_interface_name_idx_) > 0; + } + + inline + void setup_managed_interfaces() {} + + inline std::string interface_name(size_t i = 0) const + { + if (0 == i) { + if (has_command_interface_name()) { + return all_command_interface_names[command_interface_name_idx_]; + } else { + if (has_state_interface_name()) { + return all_state_interface_names[state_interface_name_idx_]; + } else { + return "null"; + } + } + } + throw std::out_of_range( + "EcPdoSingleInterfaceChannelManager::interface_name " + "unknown interface index : must be 0 (instead of " + + std::to_string(i) + ")"); + } + + inline + std::string data_type(size_t i = 0) const + { + if (0 == i) { + return id_and_bits_to_type(data_type_idx_, bits_); + } else { + throw std::out_of_range( + "EcPdoSingleInterfaceChannelManager::data_type unknown " + "interface index : must be 0 (instead of " + + std::to_string(i) + ")"); + } + } + + /** @brief Test if an interface named «name» is managed and returns its index among the + * interfaces managed by the PDO channel. + * @param name the name of the interface to test + * @return a pair with a boolean indicating if the interface is managed and the index + * of the interface among the interfaces managed by the PDO channel + */ + std::pair<bool, size_t> is_interface_managed(std::string name) const; + +public: + inline + void set_state_interface_index(const std::string & /*interface_name*/, size_t index) + { + state_interface_index_ = index; + } + + inline + void set_command_interface_index(const std::string & /*interface_name*/, size_t index) + { + command_interface_index_ = index; + } + + inline + bool has_state_interface_name(size_t /*i*/ = 0) const + { + return 0 != state_interface_name_idx_; + } + + inline + bool has_command_interface_name(size_t /*i*/ = 0) const + { + return 0 != command_interface_name_idx_; + } + + inline + bool has_interface_name(size_t /*i*/) const + { + return has_state_interface_name() || has_command_interface_name(); + } + + inline + bool is_state_interface_defined() const + { + return std::numeric_limits<size_t>::max() != state_interface_index_; + } + + inline + bool is_command_interface_defined() const + { + return std::numeric_limits<size_t>::max() != command_interface_index_; + } + + inline size_t state_interface_index(size_t /*i*/) const + { + return state_interface_index_; + } + + inline size_t command_interface_index(size_t /*i*/) const + { + return command_interface_index_; + } + +public: + inline InterfaceData & data(size_t i = 0) + { + if (0 == i) { + return *this; + } + throw std::out_of_range( + "EcPdoSingleInterfaceChannelManager::data unknown " + "interface index : must be 0 (instead of " + + std::to_string(i) + ")"); + } + + inline const InterfaceData & data(size_t i = 0) const + { + if (0 == i) { + return *this; + } + throw std::out_of_range( + "EcPdoSingleInterfaceChannelManager::data unknown " + "interface index : must be 0 (instead of " + + std::to_string(i) + ")"); + } + +protected: + /** @brief Index of the state interface in the ros2 control state interface vector + * @details If the index is not set, the value is std::numeric_limits<size_t>::max() + */ + size_t state_interface_index_ = std::numeric_limits<size_t>::max(); + /** @brief Index of the command interface in the ros2 control state interface vector + * @details If the index is not set, the value is std::numeric_limits<size_t>::max() + */ + size_t command_interface_index_ = std::numeric_limits<size_t>::max(); + SingleReadFunctionType read_function_ = nullptr; + SingleWriteFunctionType write_function_ = nullptr; + size_t state_interface_name_idx_ = 0; + size_t command_interface_name_idx_ = 0; +}; + +} // < namespace ethercat_interface + + +#endif // ETHERCAT_INTERFACE__EC_PDO_SINGLE_INTERFACE_CHANNEL_MANAGER_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_safety.hpp b/ethercat_interface/include/ethercat_interface/ec_safety.hpp new file mode 100644 index 0000000..ac17a9a --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_safety.hpp @@ -0,0 +1,161 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#ifndef ETHERCAT_INTERFACE__EC_SAFETY_HPP_ +#define ETHERCAT_INTERFACE__EC_SAFETY_HPP_ + +#include <ecrt.h> + +#include <string> +#include <vector> + +#include "ethercat_interface/ec_master.hpp" +#include "ethercat_interface/ec_transfer.hpp" + +namespace ethercat_interface +{ + +class EcMemoryEntry +{ +public: + std::string module_name; //< Module. + uint16_t alias; //< Slave alias. + uint16_t position; //< Slave position. + uint16_t index; //< Channel index. + uint16_t subindex; //< Channel subindex. + +public: + inline + std::string to_simple_string() const + { + return "( name= " + module_name + ", index= " + + std::to_string(index) + ", subindex= " + std::to_string(subindex) + " )"; + } +}; + +class EcTransferEntry +{ +public: + EcMemoryEntry input; + EcMemoryEntry output; + size_t size; //< Size of the exchange data. + +public: + inline + std::string to_simple_string() const + { + return input.to_simple_string() + " -> " + output.to_simple_string() + " / ( size= " + + std::to_string(size) + " )"; + } +}; + +class EcSafetyNet +{ +public: + std::string name; //< safety net name + std::string master; //< safety master + std::vector<EcTransferEntry> transfers; //< safety data transfers + +public: + void reset(const std::string & new_name) + { + name = new_name; + master = ""; + transfers.clear(); + } +}; + +class EcSafety : public EcMaster +{ +public: + explicit EcSafety(const unsigned int master = 0); + virtual ~EcSafety(); + +public: + /** @brief Fill in the EcTransferInfo structures + * + * @param safety_nets Safety nets + * + * \pre DomainInfo and domain_regs vectors must have been initialized and + * activated. A call to EcMaster::activate() is required before calling + * this function, to fill in the domain_regs vector offsets. Specifically + * with IgH EtherCAT Master, the offset must have been initialized with the + * ecrt_domain_reg_pdo_entry_list function. + * + * @throw std::runtime_error if some domain_info or some pdo_entry_reg are + * not valid + */ + void registerTransferInDomain(const std::vector<EcSafetyNet> & safety_nets); + + /** @brief Proceed to the transfer of all the data declared in transfers_. + */ + void transferAll(); + + /** perform one EtherCAT cycle, passing the domain to the slaves */ + bool update(uint32_t domain = 0); + + bool readData(uint32_t domain = 0); + // TODO(yguel) investigate readData and writeData specifications + // both functions are called but process all the data in the domain + // not only the data rpdos for the write and the tpdos for the read + // why ? + // void writeData(uint32_t domain = 0); + +protected: + /** @brief Output the memory content of the all the domains + * (available for pedagogic and debug purposes) + * + * @param[out] os Output stream + */ + void printMemoryFrames(std::ostream & os); + + /** @brief Get pointer on memory frame for a certain point + * in the frame defined by a slave position, an index and a subindex + */ + uint8_t * getMemoryStart( + const uint16_t position, + const uint16_t index, + const uint16_t subindex); + + /** @brief Output memory n bytes of memory from a certain point in + * the frame defined by a slave position, an index, subindex */ + void printMemoryFrame( + const uint16_t position, + const uint16_t index, + const uint16_t subindex, + const size_t n, + bool binary = false, + std::ostream & os = std::cout); + + /** @brief Check the validity of the domain info and the ec_pdo_entry_reg_t + * and throw an exception if not valid. + * + * @param domain_info Domain info + * @param pdo_entry_reg PDO entry registration + * + * @throw std::runtime_error if domain_info or pdo_entry_reg is not valid + */ + void checkDomainInfoValidity( + const DomainInfo & domain_info, + const ec_pdo_entry_reg_t & pdo_entry_reg); + +protected: + std::vector<EcTransferInfo> transfers_; +}; + +} // namespace ethercat_interface + +#endif // ETHERCAT_INTERFACE__EC_SAFETY_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_sdo_manager.hpp b/ethercat_interface/include/ethercat_interface/ec_sdo_manager.hpp new file mode 100644 index 0000000..125aee6 --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_sdo_manager.hpp @@ -0,0 +1,118 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) + +#ifndef ETHERCAT_INTERFACE__EC_SDO_MANAGER_HPP_ +#define ETHERCAT_INTERFACE__EC_SDO_MANAGER_HPP_ + +#include <ecrt.h> +#include <string> +#include <vector> +#include <limits> + +#include "yaml-cpp/yaml.h" + +namespace ethercat_interface +{ + +class SdoConfigEntry +{ +public: + SdoConfigEntry() {} + ~SdoConfigEntry() {} + + void buffer_write(uint8_t * buffer) + { + if (data_type == "uint8") { + EC_WRITE_U8(buffer, static_cast<uint8_t>(data)); + } else if (data_type == "int8") { + EC_WRITE_S8(buffer, static_cast<int8_t>(data)); + } else if (data_type == "uint16") { + EC_WRITE_U16(buffer, static_cast<uint16_t>(data)); + } else if (data_type == "int16") { + EC_WRITE_S16(buffer, static_cast<int16_t>(data)); + } else if (data_type == "uint32") { + EC_WRITE_U32(buffer, static_cast<uint32_t>(data)); + } else if (data_type == "int32") { + EC_WRITE_S32(buffer, static_cast<int32_t>(data)); + } else if (data_type == "uint64") { + EC_WRITE_U64(buffer, static_cast<uint64_t>(data)); + } else if (data_type == "int64") { + EC_WRITE_S64(buffer, static_cast<int64_t>(data)); + } + } + + bool load_from_config(YAML::Node sdo_config) + { + // index + if (sdo_config["index"]) { + index = sdo_config["index"].as<uint16_t>(); + } else { + std::cerr << "missing sdo index info" << std::endl; + return false; + } + // sub_index + if (sdo_config["sub_index"]) { + sub_index = sdo_config["sub_index"].as<uint8_t>(); + } else { + std::cerr << "sdo " << index << ": missing sdo info" << std::endl; + return false; + } + // data type + if (sdo_config["type"]) { + data_type = sdo_config["type"].as<std::string>(); + } else { + std::cerr << "sdo " << index << ": missing sdo data type info" << std::endl; + return false; + } + // value + if (sdo_config["value"]) { + data = sdo_config["value"].as<int>(); + } else { + std::cerr << "sdo " << index << ": missing sdo value" << std::endl; + return false; + } + + return true; + } + + size_t data_size() + { + return type2bytes(data_type); + } + + uint16_t index; + uint8_t sub_index; + std::string data_type; + int data; + +private: + size_t type2bytes(std::string type) + { + if (type == "int8" || type == "uint8") { + return 1; + } else if (type == "int16" || type == "uint16") { + return 2; + } else if (type == "int32" || type == "uint32") { + return 4; + } else if (type == "int64" || type == "uint64") { + return 8; + } + return 0; + } +}; + +} // namespace ethercat_interface +#endif // ETHERCAT_INTERFACE__EC_SDO_MANAGER_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_slave.hpp b/ethercat_interface/include/ethercat_interface/ec_slave.hpp new file mode 100644 index 0000000..61e4ae0 --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_slave.hpp @@ -0,0 +1,110 @@ +// Copyright 2022 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_INTERFACE__EC_SLAVE_HPP_ +#define ETHERCAT_INTERFACE__EC_SLAVE_HPP_ + +#include <ecrt.h> +#include <map> +#include <vector> +#include <unordered_map> +#include <iostream> +#include <cmath> +#include <string> + +#include "ethercat_interface/ec_sdo_manager.hpp" + +namespace ethercat_interface +{ + +class EcSlave +{ +public: + EcSlave(uint32_t vendor_id, uint32_t product_id) + : vendor_id_(vendor_id), + product_id_(product_id) {} + EcSlave(uint32_t vendor_id, uint32_t product_id, uint16_t alias, uint16_t position) + : vendor_id_(vendor_id), + product_id_(product_id) + { + setAliasAndPosition(alias, position); + } + virtual ~EcSlave() {} + +public: + /** read or write data to the domain from the index of the entry in the recorded pdos */ + virtual void processData(size_t /*entry_idx*/, uint8_t * /*domain_address*/) {} + /** a pointer to syncs. return &syncs[0] */ + virtual const ec_sync_info_t * syncs() {return NULL;} + virtual bool initialized() {return true;} + virtual void set_state_is_operational(bool value) {is_operational_ = value;} + /** Assign activate DC synchronization. return activate word*/ + virtual int assign_activate_dc_sync() {return 0x00;} + virtual bool is_reference_clock( uint16_t /*clock_position*/ ) {return false;} + /** number of elements in the syncs array. */ + virtual size_t syncSize() {return 0;} + /** a pointer to all PDO entries */ + virtual const ec_pdo_entry_info_t * channels() {return NULL;} + /** a map from domain index to pdo indices in that domain. + * map<domain index, vector<channels_ indices> > */ + typedef std::map<unsigned int, std::vector<unsigned int>> DomainMap; + virtual void domains(DomainMap & /*domains*/) const {} + virtual bool setupSlave( + std::unordered_map<std::string, std::string> slave_parameters, + std::vector<double> * state_interface, + std::vector<double> * command_interface) + { + state_interface_ptr_ = state_interface; + command_interface_ptr_ = command_interface; + parameters_ = slave_parameters; + return true; + } + virtual bool configure() {return true;} + virtual bool cleanup() {return true;} + virtual bool activate() {return true;} + virtual bool deactivate() {return true;} + virtual bool shutdown() {return true;} + +public: + inline + void setAliasAndPosition(uint16_t alias, uint16_t position) + { + alias_ = alias; + position_ = position; + is_alias_and_position_set_ = true; + } + + inline + bool isAliasAndPositionSet() + { + return is_alias_and_position_set_; + } + +public: + uint16_t alias_; //< Slave alias. + uint16_t position_; //< Index after alias. If alias is zero, stores the ring position. + uint32_t vendor_id_; //< Slave vendor ID. + uint32_t product_id_; //< Slave product code. + + std::vector<SdoConfigEntry> sdo_config; + +protected: + std::vector<double> * state_interface_ptr_; + std::vector<double> * command_interface_ptr_; + std::unordered_map<std::string, std::string> parameters_; + bool is_operational_ = false; + bool is_alias_and_position_set_ = false; +}; +} // namespace ethercat_interface +#endif // ETHERCAT_INTERFACE__EC_SLAVE_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_sync_manager.hpp b/ethercat_interface/include/ethercat_interface/ec_sync_manager.hpp new file mode 100644 index 0000000..e32e7f5 --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_sync_manager.hpp @@ -0,0 +1,86 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (macbednarczyk@gmail.com) + +#ifndef ETHERCAT_INTERFACE__EC_SYNC_MANAGER_HPP_ +#define ETHERCAT_INTERFACE__EC_SYNC_MANAGER_HPP_ + +#include <ecrt.h> +#include <string> +#include <vector> +#include <limits> + +#include "yaml-cpp/yaml.h" + +namespace ethercat_interface +{ + +class SMConfig +{ +public: + SMConfig() {} + ~SMConfig() {} + + bool load_from_config(YAML::Node sm_config) + { + // index + if (sm_config["index"]) { + index = sm_config["index"].as<uint8_t>(); + } else { + std::cerr << "missing sdo index info" << std::endl; + return false; + } + // type + if (sm_config["type"]) { + if (sm_config["type"].as<std::string>() == "input") { + type = EC_DIR_INPUT; + } else if (sm_config["type"].as<std::string>() == "output") { + type = EC_DIR_OUTPUT; + } else { + std::cerr << "sm " << index << ": type should be input/output" << std::endl; + return false; + } + } else { + std::cerr << "sm " << index << ": missing type info" << std::endl; + return false; + } + // pdo name + if (sm_config["pdo"]) { + if (sm_config["pdo"].as<std::string>() == "rpdo") { + pdo_name = "rpdo"; + } else if (sm_config["pdo"].as<std::string>() == "tpdo") { + pdo_name = "tpdo"; + } + } + // watchdog + if (sm_config["watchdog"]) { + if (sm_config["watchdog"].as<std::string>() == "enable") { + watchdog = EC_WD_ENABLE; + } else if (sm_config["watchdog"].as<std::string>() == "disable") { + watchdog = EC_WD_DISABLE; + } + } + + return true; + } + + uint8_t index; + ec_direction_t type; + std::string pdo_name = "null"; + ec_watchdog_mode_t watchdog = EC_WD_DEFAULT; +}; + +} // namespace ethercat_interface +#endif // ETHERCAT_INTERFACE__EC_SYNC_MANAGER_HPP_ diff --git a/ethercat_interface/include/ethercat_interface/ec_transfer.hpp b/ethercat_interface/include/ethercat_interface/ec_transfer.hpp new file mode 100644 index 0000000..fea0164 --- /dev/null +++ b/ethercat_interface/include/ethercat_interface/ec_transfer.hpp @@ -0,0 +1,53 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#ifndef ETHERCAT_INTERFACE__EC_TRANSFER_HPP_ +#define ETHERCAT_INTERFACE__EC_TRANSFER_HPP_ + +#include <cstdint> +#include <vector> + +#include "ethercat_interface/ec_master.hpp" + +namespace ethercat_interface +{ + +struct EcTransferInfo +{ + const EcMaster::DomainInfo * input_domain; + const EcMaster::DomainInfo * output_domain; + + /** Pointer into the input process domain, equal to + * domain process data pointer + the offset + * defined in the ec_pdo_entry_reg_t data structure + * of a domain_regs array in a DomainInfo data structure. + */ + uint8_t * in_ptr; + + /** Pointer into the output process domain, equal to + * domain process data pointer + the offset + * defined in the ec_pdo_entry_reg_t data structure + * of a domain_regs array in a DomainInfo data structure. + */ + uint8_t * out_ptr; + + /** Number of octets of the exchange data. */ + size_t size; +}; + +} // namespace ethercat_interface + +#endif // ETHERCAT_INTERFACE__EC_TRANSFER_HPP_ diff --git a/ethercat_interface/package.xml b/ethercat_interface/package.xml new file mode 100644 index 0000000..138296c --- /dev/null +++ b/ethercat_interface/package.xml @@ -0,0 +1,20 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_interface</name> + <version>1.2.0</version> + <description>Base implementations of EC interfaces</description> + <maintainer email="mcbed.robotics@gamil.com">Maciej Bednarczyk</maintainer> + <license>Apache-2.0</license> + + <buildtool_depend>ament_cmake</buildtool_depend> + + <depend>pluginlib</depend> + + <test_depend>ament_lint_auto</test_depend> + <test_depend>ament_lint_common</test_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> diff --git a/ethercat_interface/src/ec_master.cpp b/ethercat_interface/src/ec_master.cpp new file mode 100644 index 0000000..c0b1f44 --- /dev/null +++ b/ethercat_interface/src/ec_master.cpp @@ -0,0 +1,586 @@ +// Copyright 2022 ICUBE Laboratory, University of Strasbourg +// +// 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 "ethercat_interface/ec_master.hpp" +#include "ethercat_interface/ec_slave.hpp" + +#include <unistd.h> +#include <sys/resource.h> +#include <pthread.h> +#include <sched.h> +#include <signal.h> +#include <time.h> +#include <sys/mman.h> +#include <string.h> +#include <iostream> +#include <sstream> + +namespace ethercat_interface +{ + +EcMaster::DomainInfo::DomainInfo(ec_master_t * master) +{ + domain = ecrt_master_create_domain(master); + if (domain == NULL) { + printWarning("Failed to create domain"); + return; + } + + const ec_pdo_entry_reg_t empty = {0, 0, 0, 0, 0, 0, nullptr, nullptr}; + domain_regs.push_back(empty); +} + + +EcMaster::DomainInfo::~DomainInfo() +{ + for (Entry & entry : entries) { + delete[] entry.offset; + delete[] entry.bit_position; + } +} + + +EcMaster::EcMaster(const unsigned int master) +{ + master_ = ecrt_request_master(master); + if (master_ == NULL) { + printWarning("Failed to obtain master."); + return; + } + interval_ = 0; + monotonic_clock_ = rclcpp::Clock(RCL_STEADY_TIME); +} + +EcMaster::~EcMaster() +{ + /* + for (SlaveInfo & slave : slave_info_) { + //TODO verify what this piece of code was here for + } + */ + for (auto & domain : domain_info_) { + for (auto & entry : domain.second->entries) { + if (entry.offset != NULL) { + delete[] entry.offset; + entry.offset = NULL; + } + if (entry.bit_position != NULL) { + delete[] entry.bit_position; + entry.bit_position = NULL; + } + if (entry.offset_in_memory != NULL) { + delete[] entry.offset_in_memory; + entry.offset_in_memory = NULL; + } + } + if (domain.second != NULL) { + delete domain.second; + domain.second = NULL; + } + } +} + +bool EcMaster::checkSlaveIdentity(EcSlave * slave) { + + ec_slave_info_t slave_info_; + int err; + + err = ecrt_master_get_slave( + master_, /**< EtherCAT master */ + slave->position_, /**< Slave position. */ + &slave_info_ /**< Structure that will output the information */ + ); + + if (err < 0) { + RCLCPP_ERROR( + rclcpp::get_logger("EthercatDriver"), + "Error : impossible to read slave information on position %u" ,slave->product_id_); + return false; + } + + if ((slave_info_.vendor_id != slave->vendor_id_) || (slave_info_.product_code != slave->product_id_) ) { + RCLCPP_ERROR( + rclcpp::get_logger("EthercatDriver"), + "Error : topology bus - resquested slave module(0x%x, 0x%x), found slave module(0x%x, 0x%x)" + ,slave->vendor_id_ , slave->product_id_, slave_info_.vendor_id , slave_info_.product_code ); + return false; + } + + return true; + +} + +void EcMaster::addSlave(uint16_t alias, uint16_t position, EcSlave * slave) +{ + slave->setAliasAndPosition(alias, position); + addSlave(slave); +} + +bool EcMaster::addSlave(EcSlave * slave) +{ + if (false == slave->isAliasAndPositionSet()) { + //std::string error_message = "Alias and position not set for slave (vendor id=" + std::to_string( + // slave->vendor_id_) + ",product_code=" + std::to_string(slave->product_id_) + ")."; + //throw std::runtime_error(error_message); + RCLCPP_ERROR( + rclcpp::get_logger("EthercatDriver"), + "Alias and position not set for slave (vendor id=0x%x, product_code=0x%x)" + ,slave->vendor_id_ , slave->product_id_ ); + return false; + } + + if (false == checkSlaveIdentity(slave)) { + return false; + } + + + // configure slave in master + SlaveInfo slave_info; + slave_info.slave = slave; + slave_info.config = ecrt_master_slave_config( + master_, + slave->alias_, slave->position_, + slave->vendor_id_, slave->product_id_); + if (slave_info.config == NULL) { + printWarning("Add slave. Failed to get slave configuration."); + return false; + } + + // check and setup dc + + if (slave->assign_activate_dc_sync()) { + struct timespec t; + clock_gettime(CLOCK_MONOTONIC, &t); + //ecrt_master_application_time(master_, EC_NEWTIMEVAL2NANO(t)); + ecrt_slave_config_dc( + slave_info.config, + slave->assign_activate_dc_sync(), + interval_, + //interval_ - (t.tv_nsec % (interval_)), + interval_ /2.0, + 0, + 0); + if (slave->is_reference_clock(reference_clock_postition_)) { + ecrt_master_select_reference_clock(master_, slave_info.config); + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "Slave (0x%x, 0x%x) pos:%u selected as reference clock", slave->vendor_id_,slave->product_id_, reference_clock_postition_ + ); + } + } + + slave_info_.push_back(slave_info); + + // Setup PDOs registered by the slave. + // For each slave, PDOs are grouped by sync manager. + // For each active sync manager of the slave, + // register the associated set of PDOs. + size_t num_syncs = slave->syncSize(); + const ec_sync_info_t * syncs = slave->syncs(); + if (num_syncs > 0) { + // configure pdos in slave + int pdos_status = ecrt_slave_config_pdos(slave_info.config, num_syncs, syncs); + if (pdos_status) { + printWarning("Add slave. Failed to configure PDOs"); + return false; + } + } else { + printWarning( + "Add slave. Sync size is zero for " + + std::to_string(slave->alias_) + ":" + std::to_string(slave->position_)); + } + + // Get all domains and associated pdos that the slave registers + EcSlave::DomainMap domain_map; + slave->domains(domain_map); + for (auto & iter : domain_map) { + // get the domain info, create if necessary + uint32_t domain_index = iter.first; + DomainInfo * domain = NULL; + if (domain_info_.count(domain_index)) { + domain = domain_info_.at(domain_index); + } + if (domain == NULL) { + domain = new DomainInfo(master_); + domain_info_[domain_index] = domain; + } + + registerPDOInDomain( + iter.second, domain, + slave); + } + return true; +} + +int EcMaster::configSlaveSdo( + uint16_t slave_position, SdoConfigEntry sdo_config, + uint32_t * abort_code) +{ + uint8_t buffer[8]; + sdo_config.buffer_write(buffer); + int ret = ecrt_master_sdo_download( + master_, + slave_position, + sdo_config.index, + sdo_config.sub_index, + buffer, + sdo_config.data_size(), + abort_code + ); + return ret; +} + +void EcMaster::registerPDOInDomain( + std::vector<uint32_t> & channel_indices, + DomainInfo * domain_info, + EcSlave * slave) +{ + // expand the size of the domain + uint32_t num_pdo_regs = channel_indices.size(); + size_t start_index = domain_info->domain_regs.size() - 1; // empty element at end + domain_info->domain_regs.resize(domain_info->domain_regs.size() + num_pdo_regs); + + // create a new entry in the domain + DomainInfo::Entry domain_entry; + domain_entry.slave = slave; + domain_entry.num_pdos = num_pdo_regs; + domain_entry.offset = new uint32_t[num_pdo_regs]; + domain_entry.bit_position = new uint32_t[num_pdo_regs]; + domain_info->entries.push_back(domain_entry); + + EcSlave::DomainMap domain_map; + slave->domains(domain_map); + + // add to array of pdos registrations + const ec_pdo_entry_info_t * pdo_regs = slave->channels(); + for (size_t i = 0; i < num_pdo_regs; ++i) { + // create pdo entry in the domain + ec_pdo_entry_reg_t & pdo_reg = domain_info->domain_regs[start_index + i]; + pdo_reg.alias = slave->alias_; + pdo_reg.position = slave->position_; + pdo_reg.vendor_id = slave->vendor_id_; + pdo_reg.product_code = slave->product_id_; + pdo_reg.index = pdo_regs[channel_indices[i]].index; + pdo_reg.subindex = pdo_regs[channel_indices[i]].subindex; + pdo_reg.offset = &(domain_entry.offset[i]); + pdo_reg.bit_position = &(domain_entry.bit_position[i]); + + + // print the domain pdo entry + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "{ %d, %d, 0x%x, 0x%x, 0x%x, 0x%x }", + pdo_reg.alias, + pdo_reg.position, + pdo_reg.vendor_id, + pdo_reg.product_code, + pdo_reg.index, + static_cast<int>(pdo_reg.subindex) + ); + } + + // set the last element to null + ec_pdo_entry_reg_t empty = {0, 0, 0, 0, 0, 0, nullptr, nullptr}; + domain_info->domain_regs.back() = empty; +} + +bool EcMaster::activate() +{ + // register domain + for (auto & iter : domain_info_) { + DomainInfo * domain_info = iter.second; + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(iter.first)); + } + bool domain_status = ecrt_domain_reg_pdo_entry_list( + domain_info->domain, + &(domain_info->domain_regs[0])); + if (domain_status) { + printWarning("Activate. Failed to register domain PDO entries."); + return false; + } + } + // set application time + struct timespec t; + clock_gettime(CLOCK_MONOTONIC, &t); + //clock_gettime(CLOCK_REALTIME, &t); + //ecrt_master_application_time(master_, EC_NEWTIMEVAL2NANO(t)); + ecrt_master_application_time(master_, TIMESPEC2NS(t)); + + // activate master + bool activate_status = ecrt_master_activate(master_); + if (activate_status) { + printWarning("Activate. Failed to activate master."); + return false; + } + + // retrieve domain data + for (auto & iter : domain_info_) { + DomainInfo * domain_info = iter.second; + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(iter.first)); + } + domain_info->domain_pd = ecrt_domain_data(domain_info->domain); + if (domain_info->domain_pd == NULL) { + printWarning("Activate. Failed to retrieve domain process data."); + return false; + } + } + return true; +} + +bool EcMaster::update(uint32_t domain) +{ + bool ret; + struct timespec time_start_; + clock_gettime(CLOCK_MONOTONIC, &time_start_); + // receive process data + ecrt_master_receive(master_); + + DomainInfo * domain_info = domain_info_.at(domain); + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(domain)); + } + + ecrt_domain_process(domain_info->domain); + + // check process data state (optional) + ret = checkDomainState(domain); + + // check for master and slave state change + if (update_counter_ % check_state_frequency_ == 0) { + checkMasterState(); + checkSlaveStates(); + } + + + // send process data + ecrt_domain_queue(domain_info->domain); + struct timespec t; + clock_gettime(CLOCK_MONOTONIC, &t); + ecrt_master_application_time(master_, TIMESPEC2NS(t)); + ecrt_master_sync_reference_clock(master_); + ecrt_master_sync_slave_clocks(master_); + last_time_ = time_start_; + + ecrt_master_send(master_); + + ++update_counter_; + return ret; +} + +bool EcMaster::readData(uint32_t domain) +{ + bool ret; + + struct timespec time_read_; + clock_gettime(CLOCK_MONOTONIC, &time_read_); + + // receive process data + ecrt_master_receive(master_); + + DomainInfo * domain_info = domain_info_.at(domain); + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(domain)); + } + + ecrt_domain_process(domain_info->domain); + + // check process data state (optional) + ret = checkDomainState(domain); + + // check for master and slave state change + if (update_counter_ % check_state_frequency_ == 0) { + checkMasterState(); + checkSlaveStates(); + } + + // read and write process data + for (DomainInfo::Entry & entry : domain_info->entries) { + for (int i = 0; i < entry.num_pdos; ++i) { + (entry.slave)->processData(i, domain_info->domain_pd + entry.offset[i]); + } + } + + ++update_counter_; + return ret; +} + +void EcMaster::writeData(uint32_t domain) +{ + + struct timespec time_write_; + clock_gettime(CLOCK_MONOTONIC, &time_write_); + + last_time_ = time_write_; + DomainInfo * domain_info = domain_info_.at(domain); + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(domain)); + } + + // read and write process data + for (DomainInfo::Entry & entry : domain_info->entries) { + for (int i = 0; i < entry.num_pdos; ++i) { + (entry.slave)->processData(i, domain_info->domain_pd + entry.offset[i]); + } + } + + + // send process data + ecrt_domain_queue(domain_info->domain); + + struct timespec t; + clock_gettime(CLOCK_MONOTONIC, &t); + ecrt_master_application_time(master_, TIMESPEC2NS(t)); + ecrt_master_sync_reference_clock(master_); + ecrt_master_sync_slave_clocks(master_); + + ecrt_master_send(master_); +} + + +double EcMaster::elapsedTime() +{ + std::chrono::duration<double> elapsed_seconds = curr_t_ - start_t_; + return elapsed_seconds.count() - 1.0; // started after 1 second +} + +uint64_t EcMaster::elapsedCycles() +{ + return update_counter_; +} + +bool EcMaster::checkDomainState(uint32_t domain) +{ + DomainInfo * domain_info = domain_info_.at(domain); + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(domain)); + } + + ec_domain_state_t ds; + ecrt_domain_state(domain_info->domain, &ds); + + if (ds.working_counter != domain_info->domain_state.working_counter) { + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Domain: WC %d.", ds.working_counter); + } + if (ds.wc_state != domain_info->domain_state.wc_state) { + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "Domain: State %s.", + ds.wc_state == EC_WC_ZERO ? "ZERO" : + ( + (ds.wc_state == EC_WC_INCOMPLETE) ? "INCOMPLETE" : + (ds.wc_state == EC_WC_COMPLETE) ? "COMPLETE" : "UNKNOWN" + ) + ); + // some slaves have not responding start timeout + if (domain_info->domain_state.wc_state == EC_WC_COMPLETE ) { + ecat_communication_timeout_start_ = true; + time_begin = monotonic_clock_.now(); + } + + if (ds.wc_state == EC_WC_COMPLETE ) { + ecat_communication_timeout_start_ = false; + time_begin = monotonic_clock_.now(); + } + + } + + domain_info->domain_state = ds; + + if (ecat_communication_timeout_start_) { + const rclcpp::Time time_iter_start = monotonic_clock_.now(); + if (time_iter_start - time_begin > ecat_timeout_) { + RCLCPP_ERROR( + rclcpp::get_logger("EthercatDriver"), + "Communication Timeout reached !!"); + return false; + + } + } + + return true; + + +} + + +void EcMaster::checkMasterState() +{ + ec_master_state_t ms; + ecrt_master_state(master_, &ms); + + if (ms.slaves_responding != master_state_.slaves_responding) { + RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"), "%d slave(s).", ms.slaves_responding); + } + if (ms.al_states != master_state_.al_states) { + RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"), "Master AL states: 0x%02X.", ms.al_states); + } + if (ms.link_up != master_state_.link_up) { + RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"), "Link is %s.", ms.link_up ? "up" : "down"); + } + master_state_ = ms; +} + + +void EcMaster::checkSlaveStates() +{ + for (SlaveInfo & slave : slave_info_) { + ec_slave_config_state_t s; + ecrt_slave_config_state(slave.config, &s); + + if (s.al_state != slave.config_state.al_state) { + // this spams the terminal at initialization. + RCLCPP_WARN(rclcpp::get_logger("EthercatDriver"), "Slave: State 0x%02X.", s.al_state); + } + if (s.online != slave.config_state.online) { + RCLCPP_WARN( + rclcpp::get_logger( + "EthercatDriver"), "Slave: %s.", s.online ? "online" : "offline"); + } + if (s.operational != slave.config_state.operational) { + RCLCPP_WARN( + rclcpp::get_logger("EthercatDriver"), + "Slave: (alias: %d, pos: %d, vendor_id: %d, prod_id: %d) --> %soperational.", + slave.slave->alias_, + slave.slave->position_, + slave.slave->vendor_id_, + slave.slave->product_id_, + s.operational ? "" : "NOT "); + slave.slave->set_state_is_operational(s.operational ? true : false); + } + slave.config_state = s; + } +} + +bool EcMaster::checkAllSlavesOperational() +{ + for (SlaveInfo & slave : slave_info_) { + ec_slave_config_state_t s; + ecrt_slave_config_state(slave.config, &s); + if (false == s.operational) { + return false; + } + } + return true; +} + +void EcMaster::stop() +{ + + ecrt_release_master(master_); + +} + +} // namespace ethercat_interface diff --git a/ethercat_interface/src/ec_pdo_channel_manager.cpp b/ethercat_interface/src/ec_pdo_channel_manager.cpp new file mode 100644 index 0000000..5a3dccd --- /dev/null +++ b/ethercat_interface/src/ec_pdo_channel_manager.cpp @@ -0,0 +1,311 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#include <algorithm> +#include <iostream> +// #include <bitset> // For debugging purpose + +#include <rclcpp/rclcpp.hpp> + +#include "ethercat_interface/ec_pdo_channel_manager.hpp" + +namespace ethercat_interface +{ + +const std::vector<std::string> ec_pdo_channel_data_types = { + "unknown", + "bit", + "bool", + "int8", "uint8", + "int16", "uint16", + "int32", "uint32", + "int64", "uint64" +}; + +const std::vector<uint8_t> ec_pdo_channel_data_bits = { + 0, + 0, + 1, + 8, 8, + 16, 16, + 32, 32, + 64, 64 +}; + +std::vector<std::string> all_state_interface_names = { + "unknown" +}; + +std::vector<std::string> all_command_interface_names = { + "unknown" +}; + +size_t typeIdx(const std::string & type) +{ + // Handle the types of the form bitXXX + if (type.find("bit") != std::string::npos) { + return 1; + } + // Handle the standard types + auto it = + std::find(ec_pdo_channel_data_types.begin(), ec_pdo_channel_data_types.end(), type); + if (it != ec_pdo_channel_data_types.end()) { + return std::distance(ec_pdo_channel_data_types.begin(), it); + } + // Handle an unknown type + return 0; +} + +uint8_t type2bits(const std::string & type) +{ + size_t type_idx = typeIdx(type); + // Handle the types of the form bitXXX + if (1 == type_idx) { + try { + std::string n_bits = type.substr(type.find("bit") + 3); + return static_cast<uint8_t>(std::stoi(n_bits)); + } catch (std::invalid_argument & e) { + return 0; + } + } + // Handle the other types + return ec_pdo_channel_data_bits[type_idx]; +} + +std::string id_and_bits_to_type(size_t type_idx, uint8_t bits) +{ + if (type_idx < ec_pdo_channel_data_types.size()) { + if (1 == type_idx) { + return "bit" + std::to_string(bits); + } + return ec_pdo_channel_data_types[type_idx]; + } else { + throw std::out_of_range( + "id_and_bits_to_type: unknown index type (type_idx must be < " + + std::to_string( + ec_pdo_channel_data_types.size()) + ", the size of known types, instead of " + + std::to_string(type_idx) + " )"); + } +} + +#ifndef CLASSM +#define CLASSM EcPdoChannelManager +#else +#error alias CLASSM all ready defined! +#endif // < CLASSM + +CLASSM::EcPdoChannelManager() { +} + +CLASSM::~EcPdoChannelManager() { +} + +ec_pdo_entry_info_t CLASSM::get_pdo_entry_info() +{ + RCLCPP_INFO( + rclcpp::get_logger("EcPdoChannelManager"), + "{0x%x, 0x%x, %d}", + index, + static_cast<uint16_t>(sub_index), + static_cast<int>(pdo_bits()) + ); + + return {index, sub_index, pdo_bits()}; +} + +void CLASSM::setup_interface_ptrs( + std::vector<double> * state_interface, + std::vector<double> * command_interface) +{ + command_interface_ptr_ = command_interface; + state_interface_ptr_ = state_interface; +} + +void CLASSM::ec_update(uint8_t * domain_address) +{ + ec_read_to_interface(domain_address); + ec_write_from_interface(domain_address); +} + + +#undef CLASSM + +double uint8_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_U8(domain_address)); +} + +double int8_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_S8(domain_address)); +} + +double uint16_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_U16(domain_address)); +} + +double int16_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_S16(domain_address)); +} + +double uint32_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_U32(domain_address)); +} + +double int32_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_S32(domain_address)); +} + +double uint64_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_U64(domain_address)); +} + +double int64_read(uint8_t * domain_address, uint8_t /*data_mask*/) +{ + return static_cast<double>(EC_READ_S64(domain_address)); +} + +double bool_read(uint8_t * domain_address, uint8_t data_mask) +{ + return (EC_READ_U8(domain_address) & data_mask) ? 1. : 0.; +} + +double octet_read(uint8_t * domain_address, uint8_t data_mask) +{ + return static_cast<double>(EC_READ_U8(domain_address) & data_mask); +} + +const SingleReadFunctionType ec_pdo_single_read_functions[] = { + NULL, + octet_read, + bool_read, + int8_read, uint8_read, + int16_read, uint16_read, + int32_read, uint32_read, + int64_read, uint64_read, + octet_read +}; + +/*############################*/ +/* Single Write functions */ +/*############################*/ + +void uint8_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_U8(domain_address, static_cast<uint8_t>(value)); +} + +void int8_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_S8(domain_address, static_cast<int8_t>(value)); +} + +void uint16_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_U16(domain_address, static_cast<uint16_t>(value)); +} + +void int16_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_S16(domain_address, static_cast<int16_t>(value)); +} + +void uint32_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_U32(domain_address, static_cast<uint32_t>(value)); +} + +void int32_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_S32(domain_address, static_cast<int32_t>(value)); +} + +void uint64_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_U64(domain_address, static_cast<uint64_t>(value)); +} + +void int64_write(uint8_t * domain_address, double value, uint8_t /*data_mask*/) +{ + EC_WRITE_S64(domain_address, static_cast<int64_t>(value)); +} + +/** @brief Helper function that counts the number of bits in an octet */ +inline +uint8_t count_bits(uint8_t octet) +{ + return __builtin_popcount(octet); +} + +bool check_type(const std::string & type, uint8_t mask) +{ + if ("bool" == type) { + return 1 == count_bits(mask); + } + return true; +} + +/** @brief Modify one bit defined by the mask + * \pre The mask must contain only one bit set to one + */ +void bool_compose(uint8_t * domain_address, double value, uint8_t data_mask) +{ + uint8_t buffer = EC_READ_U8(domain_address); + // Clear the bit + buffer &= ~(data_mask); + if (value) { // Set the bit + buffer |= data_mask; + } + EC_WRITE_U8(domain_address, buffer); +} + +/** Modify only the bits set to one in the mask */ +void octet_compose(uint8_t * domain_address, double value, uint8_t data_mask) +{ + uint8_t buffer = EC_READ_U8(domain_address); + // Clear the bits + buffer &= ~(data_mask); + uint8_t compose_buffer = static_cast<uint8_t>(value) & data_mask; + EC_WRITE_U8(domain_address, buffer | compose_buffer); +} + +/** Modify the whole octet with the result of the applied mask */ +void octet_override(uint8_t * domain_address, double value, uint8_t data_mask) +{ + EC_WRITE_U8(domain_address, static_cast<uint8_t>(value) & data_mask); +} + +const SingleWriteFunctionType ec_pdo_single_write_functions[] = { + NULL, + octet_compose, + bool_compose, + int8_write, uint8_write, + int16_write, uint16_write, + int32_write, uint32_write, + int64_write, uint64_write, + octet_override +}; + +/*###############################*/ +/* End of Single Write functions */ +/*###############################*/ + +} // < namespace ethercat_interface diff --git a/ethercat_interface/src/ec_pdo_group_interface_channel_manager.cpp b/ethercat_interface/src/ec_pdo_group_interface_channel_manager.cpp new file mode 100644 index 0000000..89e9a07 --- /dev/null +++ b/ethercat_interface/src/ec_pdo_group_interface_channel_manager.cpp @@ -0,0 +1,438 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#include <iostream> +#include <bitset> +#include "ethercat_interface/ec_pdo_group_interface_channel_manager.hpp" + +namespace ethercat_interface +{ + +#ifndef CLASSM +#define CLASSM EcPdoGroupInterfaceChannelManager +#else +#error alias CLASSM all ready defined! +#endif // < CLASSM + +CLASSM::EcPdoGroupInterfaceChannelManager() +{ +} + +CLASSM::~EcPdoGroupInterfaceChannelManager() +{ +} + +std::string CLASSM::interface_name(size_t i) const +{ + if (v_data.size() > i) { + if (has_interface_name(i)) { + if (is_command_interface_[i]) { + return all_command_interface_names[interface_name_ids_[i]]; + } else { + return all_state_interface_names[interface_name_ids_[i]]; + } + } else { + return "null"; + } + } + throw std::out_of_range( + "EcPdoGroupInterfaceChannelManager::interface_name " + "unknown interface index : must be < " + + std::to_string(v_data.size()) + "(instead of " + + std::to_string(i) + ")"); +} + +std::string CLASSM::data_type(size_t i) const +{ + if (v_data.size() > i) { + const InterfaceDataWithAddrOffset & d = v_data[i]; + return id_and_bits_to_type(d.data_type_idx, d.bits); + } else { + throw std::out_of_range( + "EcPdoGroupInterfaceChannelManager::data_type unknown " + "interface index : must be < " + + std::to_string(v_data.size()) + " (instead of " + + std::to_string(i) + ") "); + } +} + +std::pair<bool, size_t> CLASSM::is_interface_managed(std::string name) const +{ + for (size_t i = 0; i < v_data.size(); ++i) { + if (name == interface_name(i)) { + return std::make_pair(true, i); + } + } + return std::make_pair(false, std::numeric_limits<size_t>::max()); // not found +} + +size_t CLASSM::channel_state_interface_index(const std::string & name) const +{ + for (size_t i = 0; i < v_data.size(); ++i) { + if (has_interface_name(i) && !is_command_interface_.at(i)) { + if (name == all_state_interface_names.at(interface_name_ids_.at(i))) { + return i; + } + } + } + throw std::out_of_range( + "EcPdoGroupInterfaceChannelManager::channel_state_interface_index '" + + name + "' unknown index for state interface"); +} + +size_t CLASSM::channel_command_interface_index(const std::string & name) const +{ + for (size_t i = 0; i < v_data.size(); ++i) { + if (has_interface_name(i) && is_command_interface_.at(i)) { + if (name == all_command_interface_names.at(interface_name_ids_.at(i))) { + return i; + } + } + } + throw std::out_of_range( + "EcPdoGroupInterfaceChannelManager::channel_command_interface_index '" + + name + + "' unknown index for command interface"); +} + +size_t CLASSM::state_interface_index(size_t i) const +{ + if (v_data.size() > i) { + if (!is_command_interface_[i]) { + return interface_ids_[i]; + } else { + return std::numeric_limits<size_t>::max(); + } + } + throw std::out_of_range( + "EcPdoGroupInterfaceChannelManager::state_interface_index " + "unknown interface index : must be < " + + std::to_string(v_data.size()) + + "(instead of " + std::to_string(i) + ")"); +} + +size_t CLASSM::command_interface_index(size_t i) const +{ + if (v_data.size() > i) { + if (is_command_interface_[i]) { + return interface_ids_[i]; + } else { + return std::numeric_limits<size_t>::max(); + } + } + throw std::out_of_range( + "EcPdoGroupInterfaceChannelManager::command_interface_index " + "unknown interface index : must be < " + + std::to_string(v_data.size()) + + "(instead of " + std::to_string(i) + ")"); +} + +void CLASSM::allocate_for_new_interface() +{ + v_data.push_back(InterfaceDataWithAddrOffset()); + interface_ids_.push_back(std::numeric_limits<size_t>::max()); + is_command_interface_.push_back(false); + read_functions_.push_back(nullptr); + write_functions_.push_back(nullptr); +} + +size_t CLASSM::add_command_interface(const std::string & name) +{ + // Check if the interface is already present + auto managed = is_interface_managed(name); + if (managed.first) { + return managed.second; + } + + // Add the interface + // Stores the index of the interface in all the vectors + size_t id = v_data.size(); + // Resize all the vectors + allocate_for_new_interface(); + is_command_interface_[id] = true; + // Add the name of the interface to the command interface names + size_t name_idx = all_command_interface_names.size(); + all_command_interface_names.push_back(name); + interface_name_ids_.push_back(name_idx); + + // Add the interface to the managed interfaces + managed_.push_back(id); + + return id; +} + +size_t CLASSM::add_data_without_interface() +{ + size_t id = v_data.size(); + allocate_for_new_interface(); + is_command_interface_[id] = false; + interface_name_ids_.push_back(0); + return id; +} + +size_t CLASSM::add_state_interface(const std::string & name) +{ + // Check if the interface is already present + auto managed = is_interface_managed(name); + if (managed.first) { + return managed.second; + } + + // Add the interface + // Stores the index of the interface in all the vectors + size_t id = v_data.size(); + // Resize all the vectors + allocate_for_new_interface(); + is_command_interface_[id] = false; + // Add the name of the interface to the command interface names + size_t name_idx = all_state_interface_names.size(); + all_state_interface_names.push_back(name); + interface_name_ids_.push_back(name_idx); + + // Add the interface to the managed interfaces + managed_.push_back(id); + + return id; +} + +bool CLASSM::load_from_config(YAML::Node channel_config) +{ + // TODO(@yguel@unistra): Use ROS2 logging + // index + if (channel_config["index"]) { + index = channel_config["index"].as<uint16_t>(); + } else { + std::cerr << "missing channel index info" << std::endl; + } + + // sub_index + if (channel_config["sub_index"]) { + sub_index = channel_config["sub_index"].as<uint8_t>(); + } else { + std::cerr << "channel " << index << " : missing channel info" << std::endl; + } + + // data type + std::string data_type; + if (channel_config["type"]) { + data_type = channel_config["type"].as<std::string>(); + data_type_idx_ = typeIdx(data_type); + if (0 == data_type_idx_) { + std::cerr << "channel" << index << " : unknown data type " << data_type << std::endl; + return false; + } + bits_ = type2bits(data_type); + } else { + std::cerr << "channel" << index << " : missing channel data type info" << std::endl; + } + + size_t id = std::numeric_limits<size_t>::max(); + if (channel_config["command_interface"]) { + throw std::runtime_error( + "Global command_interface is not allowed in a grouped " + "interface pdo channel, it must be defined per interface " + "in the data_mapping"); + } + + if (channel_config["state_interface"]) { + auto state_interface_name = channel_config["state_interface"].as<std::string>(); + id = add_state_interface(state_interface_name); + } else { + id = add_data_without_interface(); + } + + v_data[id].data_type_idx = data_type_idx_; + v_data[id].bits = bits_; + read_functions_[id] = ec_pdo_single_read_functions[v_data[id].data_type_idx]; + + // factor + if (channel_config["factor"]) { + if (id != std::numeric_limits<size_t>::max()) { + v_data[id].factor = channel_config["factor"].as<double>(); + } else { + // Error + // TODO(yguel@unistra.fr: log error) + } + } + // offset + if (channel_config["offset"]) { + if (id != std::numeric_limits<size_t>::max()) { + v_data[id].offset = channel_config["offset"].as<double>(); + } else { + // Error + // TODO(yguel@unistra.fr: log error) + } + } + // mask + if (channel_config["mask"]) { + if (id != std::numeric_limits<size_t>::max()) { + v_data[id].mask = channel_config["mask"].as<uint8_t>(); + if (!check_type(data_type, v_data[id].mask) ) { + std::cerr << "channel: " << index << " : mask " << std::bitset<8>(v_data[id].mask) << + " is not compatible with data type " << + data_type << std::endl; + return false; + } + } else { + // Error + // TODO(yguel@unistra: log error) + } + } + + // skip + if (channel_config["skip"]) { + skip = channel_config["skip"].as<bool>(); + // TODO(yguel@unistra: check if skip is relevant in a grouped interface pdo channel) + } + + // Handle data mapping + if (channel_config["data_mapping"]) { + auto data_mapping = channel_config["data_mapping"]; + for (auto map : data_mapping) { + // Reset the id to skip adding data if no interface is defined + id = std::numeric_limits<size_t>::max(); + if (map["command_interface"]) { + auto command_interface_name = map["command_interface"].as<std::string>(); + id = add_command_interface(command_interface_name); + if (map["default_value"]) { + v_data[id].default_value = map["default_value"].as<double>(); + } + } + + if (map["state_interface"]) { + auto state_interface_name = map["state_interface"].as<std::string>(); + id = add_state_interface(state_interface_name); + } + + if (std::numeric_limits<size_t>::max() == id) { + id = add_data_without_interface(); + } + + if (map["addr_offset"]) { + v_data[id].addr_offset = map["addr_offset"].as<size_t>(); + } + if (map["type"]) { + data_type = map["type"].as<std::string>(); + auto type_idx = typeIdx(data_type); + v_data[id].data_type_idx = type_idx; + if (0 == v_data[id].data_type_idx) { + std::cerr << "channel: " << index << " : unknown data type " << data_type << std::endl; + return false; + } + v_data[id].bits = type2bits(data_type); + read_functions_[id] = ec_pdo_single_read_functions[type_idx]; + write_functions_[id] = ec_pdo_single_write_functions[type_idx]; + } + + // factor + if (map["factor"]) { + v_data[id].factor = map["factor"].as<double>(); + } + + // offset + if (map["offset"]) { + v_data[id].offset = map["offset"].as<double>(); + } + + // mask + if (map["mask"]) { + v_data[id].mask = map["mask"].as<uint8_t>(); + if (!check_type(data_type, v_data[id].mask)) { + std::cerr << "channel" << index << " : mask " << std::bitset<8>(v_data[id].mask) << + " is not compatible with data type " << data_type << std::endl; + return false; + } + } + } + } + + return true; +} + +void CLASSM::setup_managed_interfaces() +{ + managed_.clear(); + for (size_t i = 0; i < interface_name_ids_.size(); ++i) { + if (0 != interface_ids_[i]) { + managed_.push_back(i); + } + } +} + +double CLASSM::ec_read(uint8_t * domain_address, size_t i) +{ + InterfaceDataWithAddrOffset & d = v_data[i]; + double last_value = read_functions_[i](domain_address + d.addr_offset, d.mask); + last_value = d.factor * last_value + d.offset; + if (is_state_interface_defined(i) ) { + state_interface_ptr_->at(interface_ids_[i]) = last_value; + } + d.last_value = last_value; + return last_value; +} + +void CLASSM::ec_read_to_interface(uint8_t * domain_address) +{ + for (size_t i = 0; i < managed_.size(); ++i) { + const size_t idx = managed_[i]; + ec_read(domain_address, idx); + if (is_state_interface_defined(idx) ) { + state_interface_ptr_->at(interface_ids_[idx]) = v_data[idx].last_value; + } + } +} + +void CLASSM::ec_write(uint8_t * domain_address, double value, size_t i) +{ + if (RPDO != pdo_type || !allow_ec_write) { + return; + } + + InterfaceDataWithAddrOffset & d = v_data[i]; + + if (!std::isnan(value) && !d.override_command) { + d.last_value = d.factor * value + d.offset; + write_functions_[i](domain_address + d.addr_offset, d.last_value, d.mask); + } else { + if (!std::isnan(d.default_value)) { + d.last_value = d.default_value; + write_functions_[i](domain_address + d.addr_offset, d.last_value, d.mask); + } else { // Do nothing + return; + } + } +} + +void CLASSM::ec_write_from_interface(uint8_t * domain_address) +{ + for (size_t i = 0; i < managed_.size(); ++i) { + const size_t idx = managed_[i]; + if (is_command_interface_defined(idx) ) { + const auto value = command_interface_ptr_->at(interface_ids_[idx]); + ec_write(domain_address, value, idx); + } else { + auto & d = v_data[idx]; + if ( (RPDO == pdo_type) && allow_ec_write && !std::isnan(d.default_value)) { + d.last_value = d.default_value; + write_functions_[idx](domain_address + d.addr_offset, d.last_value, d.mask); + } + } + } +} + +#undef CLASSM + +} // < namespace ethercat_interface diff --git a/ethercat_interface/src/ec_pdo_single_interface_channel_manager.cpp b/ethercat_interface/src/ec_pdo_single_interface_channel_manager.cpp new file mode 100644 index 0000000..be3a7b9 --- /dev/null +++ b/ethercat_interface/src/ec_pdo_single_interface_channel_manager.cpp @@ -0,0 +1,190 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#include <bitset> +#include <iostream> +#include "ethercat_interface/ec_pdo_single_interface_channel_manager.hpp" + +namespace ethercat_interface +{ + +#ifndef CLASSM +#define CLASSM EcPdoSingleInterfaceChannelManager +#else +#error alias CLASSM all ready defined! +#endif // < CLASSM + + +CLASSM::EcPdoSingleInterfaceChannelManager() + : state_interface_index_(std::numeric_limits<size_t>::max()), + command_interface_index_(std::numeric_limits<size_t>::max()), + read_function_(nullptr), + write_function_(nullptr), + state_interface_name_idx_(0), + command_interface_name_idx_(0) +{ +} + +CLASSM::~EcPdoSingleInterfaceChannelManager() +{ +} + +std::pair<bool, size_t> CLASSM::is_interface_managed(std::string name) const +{ + if (has_command_interface_name()) { + bool managed = (name == all_command_interface_names[command_interface_name_idx_]); + if (managed) { + return std::make_pair(true, 0); + } + } + if (has_state_interface_name()) { + bool managed = (name == all_state_interface_names[state_interface_name_idx_]); + if (managed) { + return std::make_pair(true, 0); + } else { + return std::make_pair(false, std::numeric_limits<size_t>::max()); + } + } + return std::make_pair(false, std::numeric_limits<size_t>::max()); +} + +bool CLASSM::load_from_config(YAML::Node channel_config) +{ + // TODO(@yguel@unistra): Use ROS2 logging + // index + if (channel_config["index"]) { + index = channel_config["index"].as<uint16_t>(); + } else { + std::cerr << "missing channel index info" << std::endl; + } + + // sub_index + if (channel_config["sub_index"]) { + sub_index = channel_config["sub_index"].as<uint8_t>(); + } else { + std::cerr << "channel: " << index << " : missing channel info" << std::endl; + } + + // data type + std::string data_type; + if (channel_config["type"]) { + data_type = channel_config["type"].as<std::string>(); + data_type_idx_ = typeIdx(data_type); + if (0 == data_type_idx_) { + std::cerr << "channel: " << index << " : unknown data type " << data_type << std::endl; + return false; + } + bits_ = type2bits(data_type); + read_function_ = ec_pdo_single_read_functions[data_type_idx_]; + write_function_ = ec_pdo_single_write_functions[data_type_idx_]; + } else { + std::cerr << "channel: " << index << " : missing channel data type info" << std::endl; + } + + if (channel_config["command_interface"]) { + auto command_interface_name = channel_config["command_interface"].as<std::string>(); + command_interface_name_idx_ = all_command_interface_names.size(); + all_command_interface_names.push_back(command_interface_name); + // default value + if (channel_config["default"]) { + default_value = channel_config["default"].as<double>(); + } + } + + if (channel_config["state_interface"]) { + auto state_interface_name = channel_config["state_interface"].as<std::string>(); + state_interface_name_idx_ = all_state_interface_names.size(); + all_state_interface_names.push_back(state_interface_name); + } + + // factor + if (channel_config["factor"]) { + factor = channel_config["factor"].as<double>(); + } + // offset + if (channel_config["offset"]) { + offset = channel_config["offset"].as<double>(); + } + // mask + if (channel_config["mask"]) { + mask = channel_config["mask"].as<uint8_t>(); + if (!check_type(data_type, mask)) { + std::cerr << "channel: " << index << " : mask " << std::bitset<8>(mask) << + " is not compatible with data type " << data_type << std::endl; + return false; + } + } + + // skip + if (channel_config["skip"]) { + skip = channel_config["skip"].as<bool>(); + } + + return true; +} + +double CLASSM::ec_read(uint8_t * domain_address, size_t /*i*/) +{ + last_value = read_function_(domain_address, mask); + last_value = factor * last_value + offset; + if (is_state_interface_defined() ) { + state_interface_ptr_->at(state_interface_index_) = last_value; + } + return last_value; +} + +void CLASSM::ec_read_to_interface(uint8_t * domain_address) +{ + ec_read(domain_address); + if (is_state_interface_defined() ) { + state_interface_ptr_->at(state_interface_index_) = last_value; + } +} + +void CLASSM::ec_write(uint8_t * domain_address, double value, size_t /*i*/) +{ + if (RPDO != pdo_type || !allow_ec_write) { + return; + } + if (!std::isnan(value) && !override_command) { + last_value = factor * value + offset; + write_function_(domain_address, last_value, mask); + } else { + if (!std::isnan(default_value)) { + last_value = default_value; + write_function_(domain_address, last_value, mask); + } else { // Do nothing + return; + } + } +} + +void CLASSM::ec_write_from_interface(uint8_t * domain_address) +{ + if (is_command_interface_defined() ) { + const auto value = command_interface_ptr_->at(command_interface_index_); + ec_write(domain_address, value); + } else { + if ( (RPDO == pdo_type) && allow_ec_write && !std::isnan(default_value)) { + last_value = default_value; + write_function_(domain_address, last_value, mask); + } + } +} + +#undef CLASSM + +} // < namespace ethercat_interface diff --git a/ethercat_interface/src/ec_safety.cpp b/ethercat_interface/src/ec_safety.cpp new file mode 100644 index 0000000..37ee8bb --- /dev/null +++ b/ethercat_interface/src/ec_safety.cpp @@ -0,0 +1,273 @@ +// Copyright 2024 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#include "ethercat_interface/ec_safety.hpp" +#include "ethercat_interface/ec_slave.hpp" + +#include <unistd.h> +#include <sys/resource.h> +#include <pthread.h> +#include <sched.h> +#include <signal.h> +#include <time.h> +#include <sys/mman.h> +#include <string.h> +#include <iostream> +#include <sstream> +#include <bitset> + +namespace ethercat_interface +{ + +void EcSafety::checkDomainInfoValidity( + const DomainInfo & domain_info, + const ec_pdo_entry_reg_t & pdo_entry_reg) +{ + if (nullptr == domain_info.domain_pd) { + throw std::runtime_error("Domain process data pointer not set."); + } + if (nullptr == pdo_entry_reg.offset) { + throw std::runtime_error("Offset not set in pdo_entry_reg."); + } +} + +void EcSafety::registerTransferInDomain(const std::vector<EcSafetyNet> & safety_nets) +{ + // Fill in the EcTransferInfo structures + + // For each transfer of each net, + for (auto & net : safety_nets) { + for (auto & transfer : net.transfers) { + EcTransferInfo transfer_info; + transfer_info.size = transfer.size; + RCLCPP_INFO(rclcpp::get_logger("EthercatDriver"), "Transfer size: %ld", transfer.size); + /** + * For the input and the output of the transfer find + * 1. the process domain data pointer + * 2. the offset in the process domain data + * By iterating over the existing DomainInfo and domain_regs vector + * to find the ec_pdo_entry_reg_t whose alias, position, index and subindex + * match the transfer input and output memory entries + */ + for (const auto & key_val : domain_info_) { + const DomainInfo & domain = *(key_val.second); + for (auto & domain_reg : domain.domain_regs) { + // Find match for input + if (domain_reg.alias == transfer.input.alias && + domain_reg.position == transfer.input.position && + domain_reg.index == transfer.input.index && + domain_reg.subindex == transfer.input.subindex) + { + transfer_info.input_domain = &domain; + // 3. Compute the pointer arithmetic and store the result in the EcTransferInfo object + transfer_info.in_ptr = domain.domain_pd + *(domain_reg.offset); + + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "Transfer input: esclave position: %d / index: 0x%x / in offset: %d", + domain_reg.position, + domain_reg.index, + *(domain_reg.offset) + ); + } + // Find match for output + if (domain_reg.alias == transfer.output.alias && + domain_reg.position == transfer.output.position && + domain_reg.index == transfer.output.index && + domain_reg.subindex == transfer.output.subindex) + { + transfer_info.output_domain = &domain; + // 3. Compute the pointer arithmetic and store the result in the EcTransferInfo object + transfer_info.out_ptr = domain.domain_pd + *(domain_reg.offset); + RCLCPP_INFO( + rclcpp::get_logger("EthercatDriver"), + "Transfer output: slave position: %d / index: 0x%x / out offset: %d", + domain_reg.position, + domain_reg.index, + *(domain_reg.offset) + ); + } + } + } + + // Record the transfer + transfers_.push_back(transfer_info); + } + } +} + +void EcSafety::printMemoryFrames(std::ostream & os) +{ + for (auto & kv : domain_info_) { + os << "Domain: " << kv.first << std::endl; + auto & d = kv.second; + size_t size = ecrt_domain_size(d->domain); + // Display the memory + for (size_t i = 0; i < size; i++) { + os << std::hex << static_cast<int>(d->domain_pd[i]) << " "; + } + os << std::endl; + } +} + +uint8_t * EcSafety::getMemoryStart( + const uint16_t position, + const uint16_t index, + const uint16_t subindex) +{ + for (auto & kv : domain_info_) { + auto & d = kv.second; + for (auto & reg : d->domain_regs) { + if (reg.position == position && reg.index == index && reg.subindex == subindex) { + return d->domain_pd + *(reg.offset); + } + } + } + return nullptr; +} + +void EcSafety::printMemoryFrame( + const uint16_t position, + const uint16_t index, + const uint16_t subindex, + const size_t n, + bool binary, + std::ostream & os) +{ + uint8_t * pointer = getMemoryStart(position, index, subindex); + if (pointer != nullptr) { + for (size_t i = 0; i < n; i++) { + if (binary) { + os << std::bitset<8>(pointer[i]) << " "; + } else { + os << std::hex << static_cast<int>(pointer[i]) << " "; + } + } + os << std::endl; + } +} + +void EcSafety::transferAll() +{ + // Proceed to the transfer of all the data declared in transfers_. + for (auto & transfer : transfers_) { + // Copy the data from the input to the output + memcpy(transfer.out_ptr, transfer.in_ptr, transfer.size); + } +} + +bool EcSafety::update(uint32_t domain) +{ + // receive process data + ecrt_master_receive(master_); + + DomainInfo * domain_info = domain_info_.at(domain); + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(domain)); + } + + ecrt_domain_process(domain_info->domain); + + // TODO(yguel) make transfer per domain ? Quid of transfers across domains ? + transferAll(); + + // check process data state (optional) + checkDomainState(domain); + + // check for master and slave state change + if (update_counter_ % check_state_frequency_ == 0) { + checkMasterState(); + checkSlaveStates(); + } + + + for (DomainInfo::Entry & entry : domain_info->entries) { + // read and write process data + for (int i = 0; i < entry.num_pdos; ++i) { + (entry.slave)->processData(i, domain_info->domain_pd + entry.offset[i]); + } + } + + struct timespec t; + + clock_gettime(CLOCK_REALTIME, &t); + ecrt_master_application_time(master_, EC_NEWTIMEVAL2NANO(t)); + ecrt_master_sync_reference_clock(master_); + ecrt_master_sync_slave_clocks(master_); + + // send process data + ecrt_domain_queue(domain_info->domain); + ecrt_master_send(master_); + + ++update_counter_; + + return true; +} + +inline std::string word2Str(uint16_t word) +{ + std::stringstream ss; + ss << "0b" << std::bitset<8>(word); + return ss.str(); +} + +bool EcSafety::readData(uint32_t domain) +{ + // receive process data + ecrt_master_receive(master_); + + DomainInfo * domain_info = domain_info_.at(domain); + if (domain_info == NULL) { + throw std::runtime_error("Null domain info: " + std::to_string(domain)); + } + + ecrt_domain_process(domain_info->domain); + + // TODO(yguel) make transfer per domain ? Quid of transfers across domains ? + transferAll(); + + // check process data state (optional) + checkDomainState(domain); + + // check for master and slave state change + if (update_counter_ % check_state_frequency_ == 0) { + checkMasterState(); + checkSlaveStates(); + } + + // read and write process data + for (DomainInfo::Entry & entry : domain_info->entries) { + // read and write process data + for (int i = 0; i < entry.num_pdos; ++i) { + (entry.slave)->processData(i, domain_info->domain_pd + entry.offset[i]); + } + } + + ++update_counter_; + + return true; +} + +EcSafety::EcSafety(const unsigned int master) +: EcMaster(master) +{ +} + +EcSafety::~EcSafety() +{ +} + +} // namespace ethercat_interface diff --git a/ethercat_interface/test/test_ec_pdo_channel_manager.cpp b/ethercat_interface/test/test_ec_pdo_channel_manager.cpp new file mode 100644 index 0000000..2384f4d --- /dev/null +++ b/ethercat_interface/test/test_ec_pdo_channel_manager.cpp @@ -0,0 +1,387 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 <gtest/gtest.h> +#include <memory> +#include <string> +#include <vector> +#include <iostream> +#include <bitset> + +#include "ethercat_interface/ec_pdo_single_interface_channel_manager.hpp" +#include "ethercat_interface/ec_pdo_group_interface_channel_manager.hpp" +#include "yaml-cpp/yaml.h" + +TEST(TestEcPdoSingleInterfaceChannelManager, LoadFromConfig) +{ + const char channel_config[] = + R"( + {index: 0x6071, sub_index: 0, type: int16, command_interface: effort, default: -5, factor: 2, offset: 10} + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoSingleInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + pdo_manager.load_from_config(config); + + ASSERT_EQ(pdo_manager.index, 0x6071); + ASSERT_EQ(pdo_manager.sub_index, 0); + ASSERT_EQ(pdo_manager.data_type(), "int16"); + ASSERT_EQ(pdo_manager.interface_name(), "effort"); + ASSERT_EQ(pdo_manager.default_value, -5); + ASSERT_EQ(pdo_manager.factor, 2); + ASSERT_EQ(pdo_manager.offset, 10); +} + +TEST(TestEcPdoSingleInterfaceChannelManager, EcReadS16) +{ + const char channel_config[] = + R"( + {index: 0x6071, sub_index: 0, type: int16, command_interface: effort, default: -5, factor: 2, offset: 10} + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoSingleInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + pdo_manager.load_from_config(config); + + uint8_t buffer[16]; + EC_WRITE_S16(buffer, 42); + ASSERT_EQ(pdo_manager.ec_read(buffer), 2 * 42 + 10); +} + +TEST(TestEcPdoSingleInterfaceChannelManager, EcReadWriteBit2) +{ + const char channel_config[] = + R"( + {index: 0x6071, sub_index: 0, type: bit2, mask: 3} + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoSingleInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + pdo_manager.load_from_config(config); + + ASSERT_EQ(pdo_manager.data_type(), "bit2"); + ASSERT_EQ(pdo_manager.mask, 3); + ASSERT_EQ(ethercat_interface::type2bits(pdo_manager.data_type()), 2); + + uint8_t buffer[1]; + EC_WRITE_U8(buffer, 0); + ASSERT_EQ(pdo_manager.ec_read(buffer), 0); + EC_WRITE_U8(buffer, 3); + ASSERT_EQ(pdo_manager.ec_read(buffer), 3); + EC_WRITE_U8(buffer, 5); + ASSERT_EQ(pdo_manager.ec_read(buffer), 1); + + pdo_manager.ec_write(buffer, 0); + ASSERT_EQ(EC_READ_U8(buffer), 4); + pdo_manager.ec_write(buffer, 2); + ASSERT_EQ(EC_READ_U8(buffer), 6); + EC_WRITE_U8(buffer, 0); + pdo_manager.ec_write(buffer, 5); + ASSERT_EQ(EC_READ_U8(buffer), 1); +} + +TEST(TestEcPdoSingleInterfaceChannelManager, EcReadWriteBoolMask1) +{ + const char channel_config[] = + R"( + {index: 0x6071, sub_index: 0, type: bool, mask: 1} + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoSingleInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + pdo_manager.load_from_config(config); + + ASSERT_EQ(pdo_manager.data_type(), "bool"); + ASSERT_EQ(pdo_manager.mask, 1); + ASSERT_EQ(ethercat_interface::type2bits(pdo_manager.data_type()), 1); + + uint8_t buffer[1]; + EC_WRITE_U8(buffer, 3); + ASSERT_EQ(pdo_manager.ec_read(buffer), 1); + EC_WRITE_U8(buffer, 0); + ASSERT_EQ(pdo_manager.ec_read(buffer), 0); + + pdo_manager.ec_write(buffer, 0); + ASSERT_EQ(EC_READ_U8(buffer), 0); + pdo_manager.ec_write(buffer, 5); + ASSERT_EQ(EC_READ_U8(buffer), 1); +} + +TEST(TestEcPdoSingleInterfaceChannelManager, EcReadWriteBit8Mask5) +{ + const char channel_config[] = + R"( + {index: 0x6071, sub_index: 0, type: bit8, mask: 5} + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoSingleInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + pdo_manager.load_from_config(config); + + ASSERT_EQ(pdo_manager.data_type(), "bit8"); + ASSERT_EQ(pdo_manager.mask, 5); // < Set mask 0b00000101 + ASSERT_EQ(ethercat_interface::type2bits(pdo_manager.data_type()), 8); + + uint8_t buffer[1]; + // Should only soft read the bit 5 and 1 that is both in the mask and in the buffer + EC_WRITE_U8(buffer, 7); // < Hard write 0b00000111 + ASSERT_EQ(pdo_manager.ec_read(buffer), 5); + + // Hard write 0, should soft read 0 + EC_WRITE_U8(buffer, 0); + ASSERT_EQ(pdo_manager.ec_read(buffer), 0); + + // Soft write 0, should hard read 0 + pdo_manager.ec_write(buffer, 0); + ASSERT_EQ(EC_READ_U8(buffer), 0); + + // Soft write 3 (with mask applied is 1) should hard read 0b00000001 + pdo_manager.ec_write(buffer, 3); + ASSERT_EQ(EC_READ_U8(buffer), 1); + + // Soft write 7 (with mask applied is 5) should hard read 0b00000101 + pdo_manager.ec_write(buffer, 7); + ASSERT_EQ(EC_READ_U8(buffer), 5); + + // Soft write 5 (with mask applied is 5) should hard read 0b00000101 + pdo_manager.ec_write(buffer, 5); + ASSERT_EQ(EC_READ_U8(buffer), 5); +} + + +// This test is very weird, the expected behaviour is somehow confusing +// since it writes the entire octet, but read only the bits set to 1 in the mask +// and converts the result to 1 or 0 (1 if at least one bit is set to 1) +TEST(TestEcPdoSingleInterfaceChannelManager, EcReadWriteBoolMask5) +{ + const char channel_config[] = + R"( + {index: 0x6071, sub_index: 0, type: bool, mask: 5} + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoSingleInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + ASSERT_EQ(pdo_manager.load_from_config(config), false); + + return; + // ASSERT_EQ(pdo_manager.data_type(), "bool"); + // ASSERT_EQ(pdo_manager.mask, 5); // < Set mask 0b00000101 + // ASSERT_EQ(ethercat_interface::type2bits(pdo_manager.data_type()), 1); + + // uint8_t buffer[1]; + // // Should only soft read the bit 1 that is both in the mask and in the buffer + // EC_WRITE_U8(buffer, 7); // < Hard write 0b00000111 + // ASSERT_EQ(pdo_manager.ec_read(buffer), 1); + + // // Hard write 0, should soft read 0 + // EC_WRITE_U8(buffer, 0); + // ASSERT_EQ(pdo_manager.ec_read(buffer), 0); + + // // Soft write 0, should hard read 0 + // pdo_manager.ec_write(buffer, 0); + // ASSERT_EQ(EC_READ_U8(buffer), 0); + + // // Soft write 3 (with mask applied is 1) should hard read 0b00000001 + // pdo_manager.ec_write(buffer, 3); + // ASSERT_EQ(EC_READ_U8(buffer), 1); + + // // Soft write 7 (with mask applied is 5) should hard read 0b00000101 + // pdo_manager.ec_write(buffer, 7); + // ASSERT_EQ(EC_READ_U8(buffer), 5); + + // // Soft write 5 (with mask applied is 5) should hard read 0b00000101 + // pdo_manager.ec_write(buffer, 5); + // ASSERT_EQ(EC_READ_U8(buffer), 5); +} + + +TEST(TestEcPdoGroupInterfaceChannelManager, LoadConfigTest) +{ + const char channel_config[] = + R"( + { + index: 0xf788, + sub_index: 0x00, + type: bit240, + data_mapping: [ + { + addr_offset: 60, + type: int32, + factor: 3.14, + offset: 2.71, + command_interface: effort + }, + { + addr_offset: 64, + type: int16, + factor: 1.1, + offset: 0.1, + state_interface: position + }, + { + addr_offset: 66, + type: uint8, + mask: 7, + }, + { + addr_offset: 67, + type: bool, + mask: 8, + } + ] + } + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoGroupInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + ASSERT_EQ(pdo_manager.load_from_config(config), true); + + ASSERT_EQ(pdo_manager.number_of_interfaces(), 5); + ASSERT_EQ(pdo_manager.number_of_managed_interfaces(), 2); + + ASSERT_EQ(pdo_manager.data_type(0), "bit240"); + ASSERT_EQ(pdo_manager.interface_name(0), "null"); + ASSERT_EQ(pdo_manager.index, 0xf788); + ASSERT_EQ(pdo_manager.sub_index, 0); + + ASSERT_EQ(pdo_manager.data_type(1), "int32"); + ASSERT_EQ(pdo_manager.interface_name(1), "effort"); + ASSERT_EQ(pdo_manager.data(1).factor, 3.14); + ASSERT_EQ(pdo_manager.data(1).offset, 2.71); + ASSERT_EQ(pdo_manager.v_data[1].addr_offset, 60); + + ASSERT_EQ(pdo_manager.data_type(2), "int16"); + ASSERT_EQ(pdo_manager.interface_name(2), "position"); + ASSERT_EQ(pdo_manager.data(2).factor, 1.1); + ASSERT_EQ(pdo_manager.data(2).offset, 0.1); + ASSERT_EQ(pdo_manager.v_data[2].addr_offset, 64); + + ASSERT_EQ(pdo_manager.data_type(3), "uint8"); + ASSERT_EQ(pdo_manager.interface_name(3), "null"); + ASSERT_EQ(pdo_manager.data(3).mask, 7); + ASSERT_EQ(pdo_manager.v_data[3].addr_offset, 66); + + ASSERT_EQ(pdo_manager.data_type(4), "bool"); + ASSERT_EQ(pdo_manager.interface_name(4), "null"); + ASSERT_EQ(pdo_manager.data(4).mask, 8); +} + + +TEST(TestEcPdoGroupInterfaceChannelManager, ReadWriteBits) +{ + const char channel_config[] = + R"( + { + index: 0x6071, + sub_index: 0x00, + type: bit8, + data_mapping: [ + { + type: bool, + mask: 1, + command_interface: input1 + }, + { + type: bool, + mask: 2, + state_interface: output1 + }, + { + type: bool, + mask: 4, + command_interface: input2 + }, + { + type: bool, + mask: 8, + state_interface: output2 + }, + { + type: bool, + mask: 16, + command_interface: input3 + }, + { + type: bool, + mask: 32, + state_interface: output3 + } + ] + } + )"; + YAML::Node config = YAML::Load(channel_config); + ethercat_interface::EcPdoGroupInterfaceChannelManager pdo_manager; + pdo_manager.pdo_type = ethercat_interface::PdoType::RPDO; + ASSERT_EQ(pdo_manager.load_from_config(config), true); + + ASSERT_EQ(pdo_manager.number_of_interfaces(), 7); + ASSERT_EQ(pdo_manager.number_of_managed_interfaces(), 6); + + ASSERT_EQ(pdo_manager.data_type(0), "bit8"); + ASSERT_EQ(pdo_manager.interface_name(0), "null"); + ASSERT_EQ(pdo_manager.index, 0x6071); + ASSERT_EQ(pdo_manager.sub_index, 0); + + ASSERT_EQ(pdo_manager.data_type(1), "bool"); + ASSERT_EQ(pdo_manager.interface_name(1), "input1"); + ASSERT_EQ(pdo_manager.data(1).mask, 1); + ASSERT_EQ(pdo_manager.v_data[1].addr_offset, 0); + + ASSERT_EQ(pdo_manager.data_type(2), "bool"); + ASSERT_EQ(pdo_manager.interface_name(2), "output1"); + ASSERT_EQ(pdo_manager.data(2).mask, 2); + ASSERT_EQ(pdo_manager.v_data[2].addr_offset, 0); + + ASSERT_EQ(pdo_manager.data_type(3), "bool"); + ASSERT_EQ(pdo_manager.interface_name(3), "input2"); + ASSERT_EQ(pdo_manager.data(3).mask, 4); + ASSERT_EQ(pdo_manager.v_data[3].addr_offset, 0); + + ASSERT_EQ(pdo_manager.data_type(4), "bool"); + ASSERT_EQ(pdo_manager.interface_name(4), "output2"); + ASSERT_EQ(pdo_manager.data(4).mask, 8); + ASSERT_EQ(pdo_manager.v_data[4].addr_offset, 0); + + ASSERT_EQ(pdo_manager.data_type(5), "bool"); + ASSERT_EQ(pdo_manager.interface_name(5), "input3"); + ASSERT_EQ(pdo_manager.data(5).mask, 16); + ASSERT_EQ(pdo_manager.v_data[5].addr_offset, 0); + + ASSERT_EQ(pdo_manager.data_type(6), "bool"); + ASSERT_EQ(pdo_manager.interface_name(6), "output3"); + ASSERT_EQ(pdo_manager.data(6).mask, 32); + ASSERT_EQ(pdo_manager.v_data[6].addr_offset, 0); + + uint8_t buffer[1]; + std::vector<uint8_t> write_tests0 = + { + 0, 1, 2, 4, 8, 16, 32, + 0b00111111, + 0b11000000, + 0b11111111, + 0b00101010, + 0b11010101, + 0b00001111 + }; + + for (size_t n = 0; n < write_tests0.size(); ++n) { + EC_WRITE_U8(buffer, write_tests0[n]); + ASSERT_EQ(pdo_manager.ec_read(buffer), write_tests0[n]); + + std::bitset<8> bits(write_tests0[n]); + for (size_t i = 1; i < 7; i++) { + ASSERT_EQ(pdo_manager.ec_read(buffer, i), bits.test(i - 1)); + } + } +} diff --git a/ethercat_manager/CMakeLists.txt b/ethercat_manager/CMakeLists.txt new file mode 100644 index 0000000..eef818f --- /dev/null +++ b/ethercat_manager/CMakeLists.txt @@ -0,0 +1,51 @@ +cmake_minimum_required(VERSION 3.5) +project(ethercat_manager) + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(ethercat_msgs REQUIRED) + +# EtherLab +set(ETHERLAB_DIR /usr/local/etherlab) +set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) + +find_library(ETHERCAT_LIB ethercat HINTS ${ETHERLAB_DIR}/lib) + +ament_export_include_directories( + include + ${ETHERLAB_DIR}/include +) + +add_executable( + ethercat_sdo_srv_server + src/ethercat_sdo_srv_server.cpp) +target_include_directories( + ethercat_sdo_srv_server + PRIVATE + include + ${ETHERLAB_DIR}/include +) +target_link_libraries(ethercat_sdo_srv_server ${ETHERCAT_LIB}) +ament_target_dependencies(ethercat_sdo_srv_server rclcpp ethercat_msgs) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install(TARGETS + ethercat_sdo_srv_server + DESTINATION lib/${PROJECT_NAME}) + + ## EXPORTS +ament_export_include_directories( + include +) +ament_export_libraries( + ethercat_sdo_srv_server + ${ETHERCAT_LIBRARY} +) +ament_export_dependencies( + rclcpp +) +ament_package() diff --git a/ethercat_manager/include/ethercat_manager/data_convertion_tools.hpp b/ethercat_manager/include/ethercat_manager/data_convertion_tools.hpp new file mode 100644 index 0000000..7e8b28f --- /dev/null +++ b/ethercat_manager/include/ethercat_manager/data_convertion_tools.hpp @@ -0,0 +1,421 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (mcbed.robotics@gmail.com) + +#ifndef ETHERCAT_MANAGER__DATA_CONVERTION_TOOLS_HPP_ +#define ETHERCAT_MANAGER__DATA_CONVERTION_TOOLS_HPP_ + +#include <stdint.h> +#include <string> +#include <stdexcept> +#include <ostream> +#include <iostream> +#include "rclcpp/rclcpp.hpp" + +namespace ethercat_manager +{ + +class SizeException + : public std::runtime_error +{ +public: + explicit SizeException(const std::string & msg) + : std::runtime_error(msg) {} +}; + +struct DataType +{ + const char * name; + uint16_t code; + size_t byteSize; +}; + +static const DataType dataTypes[] = { + {"bool", 0x0001, 1}, + {"int8", 0x0002, 1}, + {"int16", 0x0003, 2}, + {"int32", 0x0004, 4}, + {"uint8", 0x0005, 1}, + {"uint16", 0x0006, 2}, + {"uint32", 0x0007, 4}, + {"float", 0x0008, 4}, + {"string", 0x0009, 0}, // a. k. a. visible_string + {"octet_string", 0x000a, 0}, + {"unicode_string", 0x000b, 0}, + // ... not implemented yet + {"int24", 0x0010, 3}, + {"double", 0x0011, 8}, + {"int40", 0x0012, 5}, + {"int48", 0x0013, 6}, + {"int56", 0x0014, 7}, + {"int64", 0x0015, 8}, + {"uint24", 0x0016, 3}, + // reserved 0x0017 + {"uint40", 0x0018, 5}, + {"uint48", 0x0019, 6}, + {"uint56", 0x001a, 7}, + {"uint64", 0x001b, 8}, + // reserved 0x001c-0x001f + {"sm8", 0xfffb, 1}, // sign-and-magnitude coding + {"sm16", 0xfffc, 2}, // sign-and-magnitude coding + {"sm32", 0xfffd, 4}, // sign-and-magnitude coding + {"sm64", 0xfffe, 8}, // sign-and-magnitude coding + {"raw", 0xffff, 0}, + {} +}; + +static const DataType * get_data_type(const std::string & str) +{ + const DataType * d; + for (d = dataTypes; d->name; d++) { + if (str == d->name) { + return d; + } + } + return NULL; +} + +static const DataType * get_data_type(uint16_t code) +{ + const DataType * d; + for (d = dataTypes; d->name; d++) { + if (code == d->code) { + return d; + } + } + return NULL; +} + +static void buffer2raw(std::ostream & o, const uint8_t * data, size_t size) +{ + o << std::hex << std::setfill('0'); + while (size--) { + o << " 0x" << std::setw(2) << (unsigned int) *data++; + } +} + +static size_t data2buffer( + const DataType * type, const std::string & source, void * target, + size_t targetSize) +{ + std::stringstream str; + size_t dataSize = type->byteSize; + + memset(target, 0, targetSize); + + str << source; + str >> resetiosflags(std::ios::basefield); // guess base from prefix + str.exceptions(std::ios::failbit); + + switch (type->code) { + case 0x0001: // bool + { + int16_t val; // uint8_t is interpreted as char + str >> val; + if (val > 1 || val < 0) { + throw std::ios::failure("Value out of range"); + } + *reinterpret_cast<uint8_t *>(target) = val; + break; + } + case 0x0002: // int8 + { + int16_t val; // uint8_t is interpreted as char + str >> val; + if (val > 127 || val < -128) { + throw std::ios::failure("Value out of range"); + } + *reinterpret_cast<uint8_t *>(target) = val; + break; + } + case 0x0003: // int16 + { + int16_t val; + str >> val; + *reinterpret_cast<int16_t *>(target) = cpu_to_le16(val); + break; + } + case 0x0004: // int32 + { + int32_t val; + str >> val; + *reinterpret_cast<int32_t *>(target) = cpu_to_le32(val); + break; + } + case 0x0005: // uint8 + { + uint16_t val; // uint8_t is interpreted as char + str >> val; + if (val > 0xff) { + throw std::ios::failure("Value out of range"); + } + *reinterpret_cast<uint8_t *>(target) = val; + break; + } + case 0x0006: // uint16 + { + uint16_t val; + str >> val; + *reinterpret_cast<uint16_t *>(target) = cpu_to_le16(val); + break; + } + case 0x0007: // uint32 + { + uint32_t val; + str >> val; + *reinterpret_cast<uint32_t *>(target) = cpu_to_le32(val); + break; + } + case 0x0008: // float + { + float val; + str >> val; + *reinterpret_cast<uint32_t *>(target) = + cpu_to_le32(*reinterpret_cast<uint32_t *>(reinterpret_cast<void *>( &val))); + break; + } + case 0x0009: // std::string + case 0x000a: // octet_string + case 0x000b: // unicode_string + dataSize = str.str().size(); + if (dataSize > targetSize) { + std::stringstream err; + err << "String too large (" + << dataSize << " > " << targetSize << ")"; + throw SizeException(err.str()); + } + str.read(reinterpret_cast<char *>(target), dataSize); + break; + case 0x0011: // double + { + double val; + str >> val; + *reinterpret_cast<uint64_t *>(target) = + cpu_to_le64(*reinterpret_cast<uint64_t *>(reinterpret_cast<void *>(&val))); + break; + } + break; + case 0x0015: // int64 + { + int64_t val; + str >> val; + *reinterpret_cast<int64_t *>(target) = cpu_to_le64(val); + break; + } + break; + case 0x001b: // uint64 + { + uint64_t val; + str >> val; + *reinterpret_cast<uint64_t *>(target) = cpu_to_le64(val); + break; + } + break; + + case 0x0010: // int24 + case 0x0012: // int40 + case 0x0013: // int48 + case 0x0014: // int56 + case 0x0016: // uint24 + case 0x0018: // uint40 + case 0x0019: // uint48 + case 0x001a: // uint56 + { + std::stringstream err; + err << "Non-native integer type " << type->name + << " is not yet implemented."; + throw std::runtime_error(err.str()); + } + + case 0xfffb: // sm8 + case 0xfffc: // sm16 + case 0xfffd: // sm32 + case 0xfffe: // sm64 + { + std::stringstream err; + err << "Sign-and-magitude types not yet" + " implemented for input direction."; + throw std::runtime_error(err.str()); + } + + default: + { + std::stringstream err; + err << "Unknown data type 0x" << std::hex << type->code; + throw std::runtime_error(err.str()); + } + } + + return dataSize; +} + +static void buffer2data( + std::ostream & o, double & value, + const DataType * type, void * data, size_t dataSize) +{ + uint16_t typeCode; + + if (type) { + if (type->byteSize && dataSize != type->byteSize) { + std::stringstream err; + err << "Data type mismatch. Expected " << type->name + << " with " << type->byteSize << " byte, but got " + << dataSize << " byte."; + throw SizeException(err.str()); + } + typeCode = type->code; + } else { + typeCode = 0xffff; // raw data + } + + o << std::setfill('0'); + + switch (typeCode) { + case 0x0001: // bool + { + int val = static_cast<int>(*reinterpret_cast<int8_t *>(data)); + o << "0x" << std::hex << std::setw(2) << val; + value = static_cast<double>(val); + } + break; + case 0x0002: // int8 + { + int val = static_cast<int>(*reinterpret_cast<int8_t *>(data)); + o << "0x" << std::hex << std::setw(2) << val; + value = static_cast<double>(val); + } + break; + case 0x0003: // int16 + { + int16_t val = le16_to_cpup(data); + o << "0x" << std::hex << std::setw(4) << val; + value = static_cast<double>(val); + } + break; + case 0x0004: // int32 + { + int32_t val = le32_to_cpup(data); + o << "0x" << std::hex << std::setw(8) << val; + value = static_cast<double>(val); + } + break; + case 0x0005: // uint8 + { + unsigned int val = static_cast<unsigned int>(*reinterpret_cast<uint8_t *>(data)); + o << "0x" << std::hex << std::setw(2) << val; + value = static_cast<double>(val); + } + break; + case 0x0006: // uint16 + { + uint16_t val = le16_to_cpup(data); + o << "0x" << std::hex << std::setw(4) << val; + value = static_cast<double>(val); + } + break; + case 0x0007: // uint32 + { + uint32_t val = le32_to_cpup(data); + o << "0x" << std::hex << std::setw(8) << val; + value = static_cast<double>(val); + } + break; + case 0x0008: // float + { + uint32_t val = le32_to_cpup(data); + float fval = *reinterpret_cast<float *>(reinterpret_cast<void *>(&val)); + o << fval; + value = static_cast<double>(val); + } + break; + case 0x0009: // string + o << std::string(reinterpret_cast<const char *>(data), dataSize); + break; + case 0x000a: // octet_string + o << std::string(reinterpret_cast<const char *>(data), dataSize) << std::flush; + break; + case 0x000b: // unicode_string + // FIXME encoding + o << std::string(reinterpret_cast<const char *>(data), dataSize); + break; + case 0x0011: // double + { + uint64_t val = le64_to_cpup(data); + double fval = *reinterpret_cast<double *>(reinterpret_cast<void *>(&val)); + o << fval; + value = static_cast<double>(val); + } + break; + case 0x0015: // int64 + { + int64_t val = le64_to_cpup(data); + o << "0x" << std::hex << std::setw(16) << val; + value = static_cast<double>(val); + } + break; + case 0x001b: // uint64 + { + uint64_t val = le64_to_cpup(data); + o << "0x" << std::hex << std::setw(16) << val; + value = static_cast<double>(val); + } + break; + case 0xfffb: // sm8 + { + int8_t val = *reinterpret_cast<uint8_t *>(data); + int8_t smval = val < 0 ? (val & 0x7f) * -1 : val; + + o << "0x" << std::hex << std::setw(2) << static_cast<int>(val); + value = static_cast<double>(static_cast<int>(smval)); + } + break; + case 0xfffc: // sm16 + { + int16_t val = le16_to_cpup(data); + int16_t smval = val < 0 ? (val & 0x7fff) * -1 : val; + + o << "0x" << std::hex << std::setw(4) << val; + value = static_cast<double>(smval); + } + break; + case 0xfffd: // sm32 + { + int32_t val = le32_to_cpup(data); + int32_t smval = val < 0 ? (val & 0x7fffffffUL) * -1 : val; + + o << "0x" << std::hex << std::setw(8) << val; + value = static_cast<double>(smval); + } + break; + case 0xfffe: // sm64 + { + int64_t val = le64_to_cpup(data); + int64_t smval = + val < 0 ? (val & 0x7fffffffffffffffULL) * -1 : val; + + o << "0x" << std::hex << std::setw(16) << val; + value = static_cast<double>(smval); + } + break; + + default: + buffer2raw(o, (const uint8_t *) data, dataSize); // FIXME + break; + } +} + +} // namespace ethercat_manager + +#endif // ETHERCAT_MANAGER__DATA_CONVERTION_TOOLS_HPP_ diff --git a/ethercat_manager/include/ethercat_manager/ec_master_async.hpp b/ethercat_manager/include/ethercat_manager/ec_master_async.hpp new file mode 100644 index 0000000..d1a8a86 --- /dev/null +++ b/ethercat_manager/include/ethercat_manager/ec_master_async.hpp @@ -0,0 +1,175 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (mcbed.robotics@gmail.com) + +#ifndef ETHERCAT_MANAGER__EC_MASTER_ASYNC_HPP_ +#define ETHERCAT_MANAGER__EC_MASTER_ASYNC_HPP_ + +#include <sys/stat.h> +#include <fcntl.h> +#include <sys/ioctl.h> +#include <stdio.h> +#include <ecrt.h> +#include <errno.h> +#include <sstream> +#include <map> +#include <string> +#include "rclcpp/rclcpp.hpp" +#include "ethercat_manager/ec_master_async_io.hpp" + + +namespace ethercat_manager +{ + +class MasterException + : public std::runtime_error +{ +public: + explicit MasterException(const std::string & msg) + : std::runtime_error(msg) {} +}; + +class EcMasterAsync +{ +public: + explicit EcMasterAsync(uint16_t master_index = 0) + { + index_ = master_index; + mcount_ = 0; + fd_ = -1; + } + ~EcMasterAsync() {close();} + + void close() + { + if (fd_ != -1) { + ::close(fd_); + fd_ = -1; + } + } + + enum Permissions {Read, ReadWrite}; + + void open(Permissions perm) + { + std::stringstream deviceName; + + if (fd_ == -1) { // not already open + ec_ioctl_module_t module_data; + deviceName << "/dev/EtherCAT" << index_; + + if ((fd_ = ::open( + deviceName.str().c_str(), + perm == ReadWrite ? O_RDWR : O_RDONLY)) == -1) + { + std::stringstream err; + err << "Failed to open master device " << deviceName.str() << ": " + << strerror(errno); + throw MasterException(err.str()); + } + + getModule(&module_data); + if (module_data.ioctl_version_magic != EC_IOCTL_VERSION_MAGIC) { + std::stringstream err; + err << "ioctl() version magic is differing: " + << deviceName.str() << ": " << module_data.ioctl_version_magic + << ", ethercat tool: " << EC_IOCTL_VERSION_MAGIC; + throw MasterException(err.str()); + } + mcount_ = module_data.master_count; + } + } + + void sdo_download(ec_ioctl_slave_sdo_download_t * data) + { + if (ioctl(fd_, EC_IOCTL_SLAVE_SDO_DOWNLOAD, data) < 0) { + std::stringstream err; + if (errno == EIO && data->abort_code) { + err << "SDO transfer aborted: " << abort_code_map_.find(data->abort_code)->second; + throw MasterException(err.str()); + } else { + err << "Failed to download SDO: " << strerror(errno); + throw MasterException(err.str()); + } + } + } + + void sdo_upload(ec_ioctl_slave_sdo_upload_t * data) + { + if (ioctl(fd_, EC_IOCTL_SLAVE_SDO_UPLOAD, data) < 0) { + std::stringstream err; + if (errno == EIO && data->abort_code) { + err << "SDO transfer aborted: " << abort_code_map_.find(data->abort_code)->second; + throw MasterException(err.str()); + } else { + err << "Failed to upload SDO: " << strerror(errno); + throw MasterException(err.str()); + } + } + } + + void getModule(ec_ioctl_module_t * data) + { + if (ioctl(fd_, EC_IOCTL_MODULE, data) < 0) { + std::stringstream err; + err << "Failed to get module information: " << strerror(errno); + throw MasterException(err.str()); + } + } + +private: + unsigned int index_; + unsigned int mcount_; + int fd_; + + const std::map<uint32_t, std::string> abort_code_map_ = { + {0x05030000, "Toggle bit not changed"}, + {0x05040000, "SDO protocol timeout"}, + {0x05040001, "Client/Server command specifier not valid or unknown"}, + {0x05040005, "Out of memory"}, + {0x06010000, "Unsupported access to an object"}, + {0x06010001, "Attempt to read a write-only object"}, + {0x06010002, "Attempt to write a read-only object"}, + {0x06020000, "This object does not exist in the object directory"}, + {0x06040041, "The object cannot be mapped into the PDO"}, + {0x06040042, "The number and length of the objects to be mapped would" + " exceed the PDO length"}, + {0x06040043, "General parameter incompatibility reason"}, + {0x06040047, "General internal incompatibility in device"}, + {0x06060000, "Access failure due to a hardware error"}, + {0x06070010, "Data type does not match, length of service parameter does" + " not match"}, + {0x06070012, "Data type does not match, length of service parameter too" + " high"}, + {0x06070013, "Data type does not match, length of service parameter too" + " low"}, + {0x06090011, "Subindex does not exist"}, + {0x06090030, "Value range of parameter exceeded"}, + {0x06090031, "Value of parameter written too high"}, + {0x06090032, "Value of parameter written too low"}, + {0x06090036, "Maximum value is less than minimum value"}, + {0x08000000, "General error"}, + {0x08000020, "Data cannot be transferred or stored to the application"}, + {0x08000021, "Data cannot be transferred or stored to the application" + " because of local control"}, + {0x08000022, "Data cannot be transferred or stored to the application" + " because of the present device state"}, + {0x08000023, "Object dictionary dynamic generation fails or no object" + " dictionary is present"}, + {} + }; +}; +} // namespace ethercat_manager +#endif // ETHERCAT_MANAGER__EC_MASTER_ASYNC_HPP_ diff --git a/ethercat_manager/include/ethercat_manager/ec_master_async_io.hpp b/ethercat_manager/include/ethercat_manager/ec_master_async_io.hpp new file mode 100644 index 0000000..0029477 --- /dev/null +++ b/ethercat_manager/include/ethercat_manager/ec_master_async_io.hpp @@ -0,0 +1,62 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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 ETHERCAT_MANAGER__EC_MASTER_ASYNC_IO_HPP_ +#define ETHERCAT_MANAGER__EC_MASTER_ASYNC_IO_HPP_ + +#define EC_IOCTL_TYPE 0xa4 +#define EC_IO(nr) _IO(EC_IOCTL_TYPE, nr) +#define EC_IOR(nr, type) _IOR(EC_IOCTL_TYPE, nr, type) +#define EC_IOW(nr, type) _IOW(EC_IOCTL_TYPE, nr, type) +#define EC_IOWR(nr, type) _IOWR(EC_IOCTL_TYPE, nr, type) +#define EC_IOCTL_VERSION_MAGIC 31 +#define EC_IOCTL_MODULE EC_IOR(0x00, ec_ioctl_module_t) +#define EC_IOCTL_SLAVE_SDO_UPLOAD EC_IOWR(0x0e, ec_ioctl_slave_sdo_upload_t) +#define EC_IOCTL_SLAVE_SDO_DOWNLOAD EC_IOWR(0x0f, ec_ioctl_slave_sdo_download_t) + +typedef struct +{ + uint32_t ioctl_version_magic; + uint32_t master_count; +} ec_ioctl_module_t; + +typedef struct +{ + // inputs + uint16_t slave_position; + uint16_t sdo_index; + uint8_t sdo_entry_subindex; + size_t target_size; + uint8_t * target; + + // outputs + size_t data_size; + uint32_t abort_code; +} ec_ioctl_slave_sdo_upload_t; + +typedef struct +{ + // inputs + uint16_t slave_position; + uint16_t sdo_index; + uint8_t sdo_entry_subindex; + uint8_t complete_access; + size_t data_size; + uint8_t * data; + + // outputs + uint32_t abort_code; +} ec_ioctl_slave_sdo_download_t; + +#endif // ETHERCAT_MANAGER__EC_MASTER_ASYNC_IO_HPP_ diff --git a/ethercat_manager/package.xml b/ethercat_manager/package.xml new file mode 100644 index 0000000..248ff27 --- /dev/null +++ b/ethercat_manager/package.xml @@ -0,0 +1,21 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_manager</name> + <version>1.2.0</version> + <description>Components to interact with EtherCAT slave modules</description> + <maintainer email="mcbed.robotics@gmail.com">Maciej Bednarczyk</maintainer> + <license>Apache-2.0</license> + + <buildtool_depend>ament_cmake</buildtool_depend> + + <depend>pluginlib</depend> + <depend>ethercat_msgs</depend> + + <test_depend>ament_lint_auto</test_depend> + <test_depend>ament_lint_common</test_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> diff --git a/ethercat_manager/src/ethercat_sdo_srv_server.cpp b/ethercat_manager/src/ethercat_sdo_srv_server.cpp new file mode 100644 index 0000000..4ff3d75 --- /dev/null +++ b/ethercat_manager/src/ethercat_sdo_srv_server.cpp @@ -0,0 +1,213 @@ +// Copyright 2023 ICUBE Laboratory, University of Strasbourg +// +// 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. +// +// Author: Maciej Bednarczyk (mcbed.robotics@gmail.com) +// Author: Manuel YGUEL (yguel.robotics@gmail.com) + +#include <iostream> +#include <iomanip> +#include <memory> + +#include "rclcpp/rclcpp.hpp" +#include "ethercat_msgs/srv/get_sdo.hpp" +#include "ethercat_msgs/srv/set_sdo.hpp" +#include "ethercat_manager/ec_master_async.hpp" +#include "ethercat_manager/data_convertion_tools.hpp" + +namespace ethercat_manager +{ +void upload( + const std::shared_ptr<ethercat_msgs::srv::GetSdo::Request> request, + std::shared_ptr<ethercat_msgs::srv::GetSdo::Response> response) +{ + ec_ioctl_slave_sdo_upload_t data; + std::stringstream return_stream, data_stream; + const DataType * data_type = NULL; + double data_value = std::numeric_limits<double>::quiet_NaN(); + response->sdo_return_value = data_value; + + data.sdo_index = request->sdo_index; + data.sdo_entry_subindex = request->sdo_subindex; + data.slave_position = request->slave_position; + + if (!(data_type = get_data_type(request->sdo_data_type))) { + return_stream << "Invalid data type '" << request->sdo_data_type << "'!"; + response->sdo_return_message = return_stream.str(); + response->success = false; + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + return; + } + + data.target_size = data_type->byteSize; + data.target = new uint8_t[data.target_size + 1]; + + EcMasterAsync master(request->master_id); + try { + master.open(EcMasterAsync::Read); + } catch (MasterException & e) { + return_stream << e.what(); + response->success = false; + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + response->sdo_return_message = return_stream.str(); + if (nullptr != data.target) { + delete[] data.target; + } + return; + } + + try { + master.sdo_upload(&data); + } catch (MasterException & e) { + return_stream << e.what(); + response->success = false; + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + response->sdo_return_message = return_stream.str(); + if (nullptr != data.target) { + delete[] data.target; + } + return; + } + + master.close(); + + try { + buffer2data(data_stream, data_value, data_type, data.target, data.data_size); + } catch (SizeException & e) { + return_stream << e.what(); + response->success = false; + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + response->sdo_return_message = return_stream.str(); + if (nullptr != data.target) { + delete[] data.target; + } + return; + } + return_stream << "SDO upload done successfully"; + response->success = true; + response->sdo_return_value_string = data_stream.str(); + response->sdo_return_value = data_value; + response->sdo_return_message = return_stream.str(); + + if (nullptr != data.target) { + delete[] data.target; + } + RCLCPP_INFO(rclcpp::get_logger("ethercat_sdo_srv_server"), return_stream.str().c_str()); +} + +void download( + const std::shared_ptr<ethercat_msgs::srv::SetSdo::Request> request, + std::shared_ptr<ethercat_msgs::srv::SetSdo::Response> response) +{ + ec_ioctl_slave_sdo_download_t data; + std::stringstream return_stream, data_stream; + const DataType * data_type = NULL; + data.complete_access = 0; + data.sdo_index = request->sdo_index; + data.sdo_entry_subindex = request->sdo_subindex; + + data.slave_position = request->slave_position; + if (!(data_type = get_data_type(request->sdo_data_type))) { + return_stream << "Invalid data type '" << request->sdo_data_type << "'!"; + response->success = false; + response->sdo_return_message = return_stream.str(); + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + return; + } + + data.data_size = request->sdo_value.size(); + data.data = new uint8_t[data.data_size + 1]; + + try { + data.data_size = data2buffer( + data_type, request->sdo_value, data.data, data.data_size); + } catch (SizeException & e) { + return_stream << e.what(); + response->success = false; + response->sdo_return_message = return_stream.str(); + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + if (nullptr != data.data) { + delete[] data.data; + } + return; + } catch (std::ios::failure & e) { + return_stream << "Invalid value for type '" << data_type->name << "'!"; + response->success = false; + response->sdo_return_message = return_stream.str(); + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + if (nullptr != data.data) { + delete[] data.data; + } + return; + } + + EcMasterAsync master(request->master_id); + try { + master.open(EcMasterAsync::ReadWrite); + } catch (MasterException & e) { + return_stream << e.what(); + response->success = false; + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + response->sdo_return_message = return_stream.str(); + if (nullptr != data.data) { + delete[] data.data; + } + return; + } + + try { + master.sdo_download(&data); + } catch (MasterException & e) { + return_stream << e.what(); + response->success = false; + RCLCPP_ERROR(rclcpp::get_logger("ethercat_manager"), return_stream.str().c_str()); + response->sdo_return_message = return_stream.str(); + if (nullptr != data.data) { + delete[] data.data; + } + return; + } + + master.close(); + + return_stream << "SDO download done successfully"; + response->success = true; + response->sdo_return_message = return_stream.str(); + + if (nullptr != data.data) { + delete[] data.data; + } + RCLCPP_INFO(rclcpp::get_logger("ethercat_sdo_srv_server"), return_stream.str().c_str()); +} +} // namespace ethercat_manager + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("ethercat_sdo_srv_server"); + + rclcpp::Service<ethercat_msgs::srv::GetSdo>::SharedPtr service_get_sdo = + node->create_service<ethercat_msgs::srv::GetSdo>( + "ethercat_manager/get_sdo", + ðercat_manager::upload); + + rclcpp::Service<ethercat_msgs::srv::SetSdo>::SharedPtr service_set_sdo = + node->create_service<ethercat_msgs::srv::SetSdo>( + "ethercat_manager/set_sdo", + ðercat_manager::download); + + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/ethercat_msgs/CMakeLists.txt b/ethercat_msgs/CMakeLists.txt new file mode 100644 index 0000000..e905d9a --- /dev/null +++ b/ethercat_msgs/CMakeLists.txt @@ -0,0 +1,22 @@ +cmake_minimum_required(VERSION 3.8) +project(ethercat_msgs) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + "srv/SetSdo.srv" + "srv/GetSdo.srv" + DEPENDENCIES +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/ethercat_msgs/package.xml b/ethercat_msgs/package.xml new file mode 100644 index 0000000..b3d6cd9 --- /dev/null +++ b/ethercat_msgs/package.xml @@ -0,0 +1,18 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>ethercat_msgs</name> + <version>1.2.0</version> + <description>Interfaces for the EtherCAT Driver stack</description> + <maintainer email="mcbed.robotics@gmail.com">mcbed</maintainer> + <license>Apache-2.0</license> + + <buildtool_depend>ament_cmake</buildtool_depend> + <buildtool_depend>rosidl_default_generators</buildtool_depend> + <exec_depend>rosidl_default_runtime</exec_depend> + <member_of_group>rosidl_interface_packages</member_of_group> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> diff --git a/ethercat_msgs/srv/GetSdo.srv b/ethercat_msgs/srv/GetSdo.srv new file mode 100644 index 0000000..b86bd08 --- /dev/null +++ b/ethercat_msgs/srv/GetSdo.srv @@ -0,0 +1,10 @@ +int16 master_id +uint16 slave_position +uint16 sdo_index +uint8 sdo_subindex +string sdo_data_type +--- +bool success +string sdo_return_message +string sdo_return_value_string +float64 sdo_return_value diff --git a/ethercat_msgs/srv/SetSdo.srv b/ethercat_msgs/srv/SetSdo.srv new file mode 100644 index 0000000..3487c88 --- /dev/null +++ b/ethercat_msgs/srv/SetSdo.srv @@ -0,0 +1,9 @@ +int16 master_id +int16 slave_position +int16 sdo_index +int16 sdo_subindex +string sdo_data_type +string sdo_value +--- +bool success +string sdo_return_message -- GitLab