From 0efa915c9ccf8e180350699c10950ef2091652ef Mon Sep 17 00:00:00 2001 From: mahp Date: Fri, 19 Mar 2021 14:30:30 +0100 Subject: [PATCH] Added new release of Isaac driver The new release includes several new features, some of them can be seen here: - New controller that is aware of speedscaling - Codelet that serves as an interface for the dashboard server - Added support for integration of teach-pendant, using the URCap system. --- .ci.rosinstall | 4 - .gitignore | 4 +- .travis.rosinstall | 4 - .travis.yml | 20 - BUILD | 199 ++-- README.md | 224 +++- UniversalRobots.hpp | 177 --- apps/BUILD | 25 +- ...huffle_box_behavior_hardware.subgraph.json | 318 +++++ apps/shuffle_box_hardware.py | 124 +- apps/simple_joint_control.ipynb | 272 +++-- controller_stopper/BUILD | 16 + controller_stopper/ControllerStopper.cpp | 77 ++ controller_stopper/ControllerStopper.hpp | 83 ++ controller_stopper/README.md | 10 + ur_controller/BUILD | 42 + ur_controller/JointSegment.cpp | 178 +++ ur_controller/JointSegment.hpp | 156 +++ ur_controller/JointTrajectory.cpp | 91 ++ ur_controller/JointTrajectory.hpp | 86 ++ ur_controller/Pid.hpp | 229 ++++ ur_controller/README.md | 111 ++ ur_controller/ScaledMultiJointController.cpp | 409 +++++++ ur_controller/ScaledMultiJointController.hpp | 290 +++++ ur_controller/apps/BUILD | 13 + ...caled_multi_joint_ur_control.subgraph.json | 110 ++ ur_controller/doc/traj_with_speed_scaling.png | Bin 0 -> 27194 bytes .../doc/traj_without_speed_scaling.png | Bin 0 -> 30599 bytes ur_controller/tests/BUILD | 12 + ur_controller/tests/JointSegment.cpp | 344 ++++++ ur_controller/tests/JointTrajectory.cpp | 249 ++++ ur_controller/tests/Pid.cpp | 189 +++ .../tests/ScaledMultiJointController.cpp | 646 +++++++++++ ur_msg/BUILD | 40 + ur_msg/README.md | 628 ++++++++++ ur_msg/dashboardCommand.cpp | 185 +++ ur_msg/dashboardCommand.hpp | 98 ++ ur_msg/dashboard_command.capnp | 91 ++ ur_msg/speed_slider.capnp | 39 + ur_msg/ur_msg_python.py | 74 ++ ur_robot_driver/CHANGELOG.rst | 22 - ur_robot_driver/CMakeLists.txt | 66 -- ur_robot_driver/DashboardClientIsaac.cpp | 314 +++++ ur_robot_driver/DashboardClientIsaac.hpp | 130 +++ ur_robot_driver/LICENSE | 180 --- ur_robot_driver/README.md | 212 +++- .../UniversalRobots.cpp | 375 ++++-- ur_robot_driver/UniversalRobots.hpp | 398 +++++++ ur_robot_driver/UrclLogHandler.cpp | 88 ++ ur_robot_driver/UrclLogHandler.hpp | 75 ++ ur_robot_driver/apps/BUILD | 33 + .../apps/ur_cb3_robot.subgraph.json | 243 ++++ .../apps/ur_eseries_robot.subgraph.json | 243 ++++ ur_robot_driver/config/ur10_controllers.yaml | 141 --- ur_robot_driver/config/ur10e_controllers.yaml | 141 --- ur_robot_driver/config/ur3_controllers.yaml | 142 --- ur_robot_driver/config/ur3e_controllers.yaml | 141 --- ur_robot_driver/config/ur5_controllers.yaml | 141 --- ur_robot_driver/config/ur5e_controllers.yaml | 141 --- ur_robot_driver/doc/ROS_INTERFACE.md | 1023 ----------------- ur_robot_driver/doc/architecture_coarse.svg | 4 +- ur_robot_driver/doc/component_api.md | 203 ++++ ur_robot_driver/doc/features.md | 34 - .../doc/initial_setup_images/e-Series.jpg | Bin 0 -> 42289 bytes .../doc/initial_setup_images/e-Series.png | Bin 208062 -> 0 bytes ur_robot_driver/doc/install_urcap_cb3.md | 4 +- ur_robot_driver/doc/install_urcap_e_series.md | 15 +- ur_robot_driver/doc/real_time.md | 282 ----- ur_robot_driver/doc/rosdoc.yaml | 4 - ur_robot_driver/doc/sample_applications.md | 177 +++ .../doc/setup_tool_communication.md | 48 - ur_robot_driver/doc/tutorial/cell_3.png | Bin 0 -> 236105 bytes ur_robot_driver/doc/tutorial/cell_4.png | Bin 0 -> 262401 bytes .../doc/tutorial/notebook_after_running.png | Bin 0 -> 310160 bytes ur_robot_driver/hardware_interface_plugin.xml | 7 - .../include/ur_robot_driver/comm/bin_parser.h | 376 ------ .../include/ur_robot_driver/comm/package.h | 74 -- .../ur_robot_driver/comm/package_serializer.h | 134 --- .../include/ur_robot_driver/comm/parser.h | 58 - .../include/ur_robot_driver/comm/pipeline.h | 451 -------- .../include/ur_robot_driver/comm/producer.h | 141 --- .../ur_robot_driver/comm/reverse_interface.h | 162 --- .../ur_robot_driver/comm/script_sender.h | 138 --- .../include/ur_robot_driver/comm/server.h | 104 -- .../ur_robot_driver/comm/shell_consumer.h | 70 -- .../include/ur_robot_driver/comm/stream.h | 158 --- .../include/ur_robot_driver/comm/tcp_socket.h | 151 --- .../include/ur_robot_driver/exceptions.h | 127 -- ur_robot_driver/include/ur_robot_driver/log.h | 43 - .../ur_robot_driver/primary/package_header.h | 84 -- .../ur_robot_driver/primary/primary_package.h | 79 -- .../ur_robot_driver/primary/primary_parser.h | 186 --- .../ur_robot_driver/primary/robot_message.h | 95 -- .../primary/robot_message/version_message.h | 83 -- .../ur_robot_driver/primary/robot_state.h | 107 -- .../primary/robot_state/kinematics_info.h | 91 -- .../primary/robot_state/master_board.h | 117 -- .../primary/robot_state/robot_mode_data.h | 108 -- .../include/ur_robot_driver/queue/LICENSE.md | 28 - .../include/ur_robot_driver/queue/atomicops.h | 738 ------------ .../ur_robot_driver/queue/readerwriterqueue.h | 865 -------------- .../rtde/control_package_pause.h | 89 -- .../rtde/control_package_setup_inputs.h | 105 -- .../rtde/control_package_setup_outputs.h | 120 -- .../rtde/control_package_start.h | 101 -- .../ur_robot_driver/rtde/data_package.h | 238 ---- .../rtde/get_urcontrol_version.h | 106 -- .../ur_robot_driver/rtde/package_header.h | 100 -- .../rtde/request_protocol_version.h | 106 -- .../ur_robot_driver/rtde/rtde_client.h | 155 --- .../ur_robot_driver/rtde/rtde_package.h | 79 -- .../ur_robot_driver/rtde/rtde_parser.h | 159 --- .../ur_robot_driver/rtde/rtde_writer.h | 128 --- .../ur_robot_driver/rtde/text_message.h | 84 -- .../include/ur_robot_driver/types.h | 62 - .../ur_robot_driver/ur/calibration_checker.h | 104 -- .../ur_robot_driver/ur/dashboard_client.h | 100 -- .../include/ur_robot_driver/ur/datatypes.h | 180 --- .../ur_robot_driver/ur/tool_communication.h | 248 ---- .../include/ur_robot_driver/ur/ur_driver.h | 240 ---- .../ur_robot_driver/ur/version_information.h | 60 - ur_robot_driver/package.xml | 55 - .../resources/externalcontrol-1.0.1.urcap | Bin 32062 -> 0 bytes .../resources/externalcontrol-1.0.5.urcap | Bin 0 -> 35287 bytes .../resources/ros_control.urscript | 48 +- ur_robot_driver/resources/rs485-1.0.urcap | Bin 141984 -> 0 bytes .../resources/rtde_output_recipe.txt | 5 +- ur_robot_driver/scripts/tool_communication | 38 - ur_robot_driver/src/comm/server.cpp | 156 --- ur_robot_driver/src/comm/tcp_socket.cpp | 217 ---- .../src/primary/primary_package.cpp | 54 - ur_robot_driver/src/primary/robot_message.cpp | 49 - .../primary/robot_message/version_message.cpp | 61 - .../primary/robot_state/kinematics_info.cpp | 105 -- .../src/rtde/control_package_pause.cpp | 48 - .../src/rtde/control_package_setup_inputs.cpp | 70 -- .../rtde/control_package_setup_outputs.cpp | 92 -- .../src/rtde/control_package_start.cpp | 53 - ur_robot_driver/src/rtde/data_package.cpp | 295 ----- .../src/rtde/get_urcontrol_version.cpp | 57 - .../src/rtde/request_protocol_version.cpp | 57 - ur_robot_driver/src/rtde/rtde_client.cpp | 221 ---- ur_robot_driver/src/rtde/rtde_package.cpp | 53 - ur_robot_driver/src/rtde/rtde_writer.cpp | 202 ---- ur_robot_driver/src/rtde/text_message.cpp | 62 - .../src/ur/calibration_checker.cpp | 47 - ur_robot_driver/src/ur/dashboard_client.cpp | 109 -- ur_robot_driver/src/ur/tool_communication.cpp | 53 - ur_robot_driver/src/ur/ur_driver.cpp | 333 ------ ur_robot_driver/tests/BUILD | 59 + .../tests/external_control_test.py | 140 +++ .../tests/scaled_trajectory_test.py | 172 +++ ur_robot_driver/tests/tool_io_test.py | 85 ++ ur_robot_driver/tests/trajectory_test.py | 157 +++ .../tests/utils/external_control.urp | Bin 0 -> 1219 bytes ur_robot_driver/tests/utils/test_utils.py | 56 + ur_robot_driver/tests/utils/ur_msg.py | 46 + 157 files changed, 8532 insertions(+), 12949 deletions(-) delete mode 100644 .ci.rosinstall delete mode 100644 .travis.rosinstall delete mode 100644 .travis.yml delete mode 100644 UniversalRobots.hpp create mode 100644 apps/shuffle_box_behavior_hardware.subgraph.json create mode 100644 controller_stopper/BUILD create mode 100644 controller_stopper/ControllerStopper.cpp create mode 100644 controller_stopper/ControllerStopper.hpp create mode 100644 controller_stopper/README.md create mode 100644 ur_controller/BUILD create mode 100644 ur_controller/JointSegment.cpp create mode 100644 ur_controller/JointSegment.hpp create mode 100644 ur_controller/JointTrajectory.cpp create mode 100644 ur_controller/JointTrajectory.hpp create mode 100644 ur_controller/Pid.hpp create mode 100644 ur_controller/README.md create mode 100644 ur_controller/ScaledMultiJointController.cpp create mode 100644 ur_controller/ScaledMultiJointController.hpp create mode 100644 ur_controller/apps/BUILD create mode 100644 ur_controller/apps/scaled_multi_joint_ur_control.subgraph.json create mode 100644 ur_controller/doc/traj_with_speed_scaling.png create mode 100644 ur_controller/doc/traj_without_speed_scaling.png create mode 100644 ur_controller/tests/BUILD create mode 100644 ur_controller/tests/JointSegment.cpp create mode 100644 ur_controller/tests/JointTrajectory.cpp create mode 100644 ur_controller/tests/Pid.cpp create mode 100644 ur_controller/tests/ScaledMultiJointController.cpp create mode 100644 ur_msg/BUILD create mode 100644 ur_msg/README.md create mode 100644 ur_msg/dashboardCommand.cpp create mode 100644 ur_msg/dashboardCommand.hpp create mode 100644 ur_msg/dashboard_command.capnp create mode 100644 ur_msg/speed_slider.capnp create mode 100644 ur_msg/ur_msg_python.py delete mode 100644 ur_robot_driver/CHANGELOG.rst delete mode 100644 ur_robot_driver/CMakeLists.txt create mode 100644 ur_robot_driver/DashboardClientIsaac.cpp create mode 100644 ur_robot_driver/DashboardClientIsaac.hpp delete mode 100644 ur_robot_driver/LICENSE rename UniversalRobots.cpp => ur_robot_driver/UniversalRobots.cpp (53%) create mode 100644 ur_robot_driver/UniversalRobots.hpp create mode 100644 ur_robot_driver/UrclLogHandler.cpp create mode 100644 ur_robot_driver/UrclLogHandler.hpp create mode 100644 ur_robot_driver/apps/BUILD create mode 100644 ur_robot_driver/apps/ur_cb3_robot.subgraph.json create mode 100644 ur_robot_driver/apps/ur_eseries_robot.subgraph.json delete mode 100644 ur_robot_driver/config/ur10_controllers.yaml delete mode 100644 ur_robot_driver/config/ur10e_controllers.yaml delete mode 100644 ur_robot_driver/config/ur3_controllers.yaml delete mode 100644 ur_robot_driver/config/ur3e_controllers.yaml delete mode 100644 ur_robot_driver/config/ur5_controllers.yaml delete mode 100644 ur_robot_driver/config/ur5e_controllers.yaml delete mode 100644 ur_robot_driver/doc/ROS_INTERFACE.md create mode 100644 ur_robot_driver/doc/component_api.md delete mode 100644 ur_robot_driver/doc/features.md create mode 100644 ur_robot_driver/doc/initial_setup_images/e-Series.jpg delete mode 100644 ur_robot_driver/doc/initial_setup_images/e-Series.png delete mode 100644 ur_robot_driver/doc/real_time.md delete mode 100644 ur_robot_driver/doc/rosdoc.yaml create mode 100644 ur_robot_driver/doc/sample_applications.md delete mode 100644 ur_robot_driver/doc/setup_tool_communication.md create mode 100644 ur_robot_driver/doc/tutorial/cell_3.png create mode 100644 ur_robot_driver/doc/tutorial/cell_4.png create mode 100644 ur_robot_driver/doc/tutorial/notebook_after_running.png delete mode 100644 ur_robot_driver/hardware_interface_plugin.xml delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/bin_parser.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/package.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/package_serializer.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/parser.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/pipeline.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/producer.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/reverse_interface.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/script_sender.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/server.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/shell_consumer.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/stream.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/comm/tcp_socket.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/exceptions.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/log.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/package_header.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/primary_package.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/primary_parser.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/robot_message.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/robot_message/version_message.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/robot_state.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/robot_state/kinematics_info.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/robot_state/master_board.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/primary/robot_state/robot_mode_data.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/queue/LICENSE.md delete mode 100644 ur_robot_driver/include/ur_robot_driver/queue/atomicops.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/queue/readerwriterqueue.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/control_package_pause.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/control_package_setup_inputs.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/control_package_setup_outputs.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/control_package_start.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/data_package.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/get_urcontrol_version.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/package_header.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/request_protocol_version.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/rtde_client.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/rtde_package.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/rtde_parser.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/rtde_writer.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/rtde/text_message.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/types.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/ur/calibration_checker.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/ur/dashboard_client.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/ur/datatypes.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/ur/tool_communication.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/ur/ur_driver.h delete mode 100644 ur_robot_driver/include/ur_robot_driver/ur/version_information.h delete mode 100644 ur_robot_driver/package.xml delete mode 100644 ur_robot_driver/resources/externalcontrol-1.0.1.urcap create mode 100644 ur_robot_driver/resources/externalcontrol-1.0.5.urcap delete mode 100644 ur_robot_driver/resources/rs485-1.0.urcap delete mode 100755 ur_robot_driver/scripts/tool_communication delete mode 100644 ur_robot_driver/src/comm/server.cpp delete mode 100644 ur_robot_driver/src/comm/tcp_socket.cpp delete mode 100644 ur_robot_driver/src/primary/primary_package.cpp delete mode 100644 ur_robot_driver/src/primary/robot_message.cpp delete mode 100644 ur_robot_driver/src/primary/robot_message/version_message.cpp delete mode 100644 ur_robot_driver/src/primary/robot_state/kinematics_info.cpp delete mode 100644 ur_robot_driver/src/rtde/control_package_pause.cpp delete mode 100644 ur_robot_driver/src/rtde/control_package_setup_inputs.cpp delete mode 100644 ur_robot_driver/src/rtde/control_package_setup_outputs.cpp delete mode 100644 ur_robot_driver/src/rtde/control_package_start.cpp delete mode 100644 ur_robot_driver/src/rtde/data_package.cpp delete mode 100644 ur_robot_driver/src/rtde/get_urcontrol_version.cpp delete mode 100644 ur_robot_driver/src/rtde/request_protocol_version.cpp delete mode 100644 ur_robot_driver/src/rtde/rtde_client.cpp delete mode 100644 ur_robot_driver/src/rtde/rtde_package.cpp delete mode 100644 ur_robot_driver/src/rtde/rtde_writer.cpp delete mode 100644 ur_robot_driver/src/rtde/text_message.cpp delete mode 100644 ur_robot_driver/src/ur/calibration_checker.cpp delete mode 100644 ur_robot_driver/src/ur/dashboard_client.cpp delete mode 100644 ur_robot_driver/src/ur/tool_communication.cpp delete mode 100644 ur_robot_driver/src/ur/ur_driver.cpp create mode 100644 ur_robot_driver/tests/BUILD create mode 100644 ur_robot_driver/tests/external_control_test.py create mode 100644 ur_robot_driver/tests/scaled_trajectory_test.py create mode 100644 ur_robot_driver/tests/tool_io_test.py create mode 100644 ur_robot_driver/tests/trajectory_test.py create mode 100644 ur_robot_driver/tests/utils/external_control.urp create mode 100644 ur_robot_driver/tests/utils/test_utils.py create mode 100644 ur_robot_driver/tests/utils/ur_msg.py diff --git a/.ci.rosinstall b/.ci.rosinstall deleted file mode 100644 index 8ae4ce4..0000000 --- a/.ci.rosinstall +++ /dev/null @@ -1,4 +0,0 @@ -- git: - uri: https://github.com/fmauch/universal_robot.git - local-name: universal_robot - version: calibration_devel diff --git a/.gitignore b/.gitignore index 820cab7..b8a02a7 100644 --- a/.gitignore +++ b/.gitignore @@ -6,4 +6,6 @@ install_manifest.txt *~ .idea .directory -.vscode \ No newline at end of file +.vscode +__pycache__ +ur_client_library \ No newline at end of file diff --git a/.travis.rosinstall b/.travis.rosinstall deleted file mode 100644 index 3afb542..0000000 --- a/.travis.rosinstall +++ /dev/null @@ -1,4 +0,0 @@ -- git: - local-name: universal_robot - uri: 'https://github.com/fmauch/universal_robot.git' - version: calibration_devel diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 4638111..0000000 --- a/.travis.yml +++ /dev/null @@ -1,20 +0,0 @@ -language: generic -services: - - docker - -cache: - directories: - - $HOME/.ccache - -env: - global: - - CCACHE_DIR=$HOME/.ccache - matrix: - - ROS_DISTRO="kinetic" ROS_REPO=ros UPSTREAM_WORKSPACE=file - - ROS_DISTRO="melodic" ROS_REPO=ros UPSTREAM_WORKSPACE=file - - ROS_DISTRO="kinetic" CLANG_FORMAT_CHECK=file CLANG_FORMAT_VERSION=6.0 - -install: - - git clone --depth=1 https://github.com/ros-industrial/industrial_ci.git .ci_config -script: - - .ci_config/travis.sh diff --git a/BUILD b/BUILD index 0fe2996..d8a164d 100644 --- a/BUILD +++ b/BUILD @@ -1,94 +1,109 @@ -load("//engine/build:isaac.bzl", "isaac_cc_module") +load("//bzl:module.bzl", "isaac_cc_module") - filegroup(name = "universal_robots_resources", - data = - [ - "ur_robot_driver/resources/ros_control.urscript", - "ur_robot_driver/resources/rtde_input_recipe.txt", - "ur_robot_driver/resources/rtde_output_recipe.txt", - ], - visibility = ["//visibility:public"], ) +filegroup( + name = "universal_robots_resources", + data = [ + "ur_robot_driver/resources/ros_control.urscript", + "ur_robot_driver/resources/rtde_input_recipe.txt", + "ur_robot_driver/resources/rtde_output_recipe.txt", + ], + visibility = ["//visibility:public"], +) - isaac_cc_module(name = "universal_robots", - srcs = - [ - "UniversalRobots.cpp", - "ur_robot_driver/src/comm/server.cpp", - "ur_robot_driver/src/comm/tcp_socket.cpp", - "ur_robot_driver/src/primary/primary_package.cpp", - "ur_robot_driver/src/primary/robot_message.cpp", - "ur_robot_driver/src/primary/robot_message/version_message.cpp", - "ur_robot_driver/src/primary/robot_state/kinematics_info.cpp", - "ur_robot_driver/src/rtde/control_package_pause.cpp", - "ur_robot_driver/src/rtde/control_package_setup_inputs.cpp", - "ur_robot_driver/src/rtde/control_package_setup_outputs.cpp", - "ur_robot_driver/src/rtde/control_package_start.cpp", - "ur_robot_driver/src/rtde/data_package.cpp", - "ur_robot_driver/src/rtde/get_urcontrol_version.cpp", - "ur_robot_driver/src/rtde/request_protocol_version.cpp", - "ur_robot_driver/src/rtde/rtde_client.cpp", - "ur_robot_driver/src/rtde/rtde_package.cpp", - "ur_robot_driver/src/rtde/rtde_writer.cpp", - "ur_robot_driver/src/rtde/text_message.cpp", - "ur_robot_driver/src/ur/calibration_checker.cpp", - "ur_robot_driver/src/ur/dashboard_client.cpp", - "ur_robot_driver/src/ur/tool_communication.cpp", - "ur_robot_driver/src/ur/ur_driver.cpp", - ], - hdrs = - [ - "UniversalRobots.hpp", - "ur_robot_driver/include/ur_robot_driver/comm/bin_parser.h", - "ur_robot_driver/include/ur_robot_driver/comm/package.h", - "ur_robot_driver/include/ur_robot_driver/comm/package_serializer.h", - "ur_robot_driver/include/ur_robot_driver/comm/parser.h", - "ur_robot_driver/include/ur_robot_driver/comm/pipeline.h", - "ur_robot_driver/include/ur_robot_driver/comm/producer.h", - "ur_robot_driver/include/ur_robot_driver/comm/reverse_interface.h", - "ur_robot_driver/include/ur_robot_driver/comm/script_sender.h", - "ur_robot_driver/include/ur_robot_driver/comm/server.h", - "ur_robot_driver/include/ur_robot_driver/comm/shell_consumer.h", - "ur_robot_driver/include/ur_robot_driver/comm/stream.h", - "ur_robot_driver/include/ur_robot_driver/comm/tcp_socket.h", - "ur_robot_driver/include/ur_robot_driver/exceptions.h", - "ur_robot_driver/include/ur_robot_driver/log.h", - "ur_robot_driver/include/ur_robot_driver/primary/package_header.h", - "ur_robot_driver/include/ur_robot_driver/primary/primary_package.h", - "ur_robot_driver/include/ur_robot_driver/primary/primary_parser.h", - "ur_robot_driver/include/ur_robot_driver/primary/robot_message.h", - "ur_robot_driver/include/ur_robot_driver/primary/robot_message/version_message.h", - "ur_robot_driver/include/ur_robot_driver/primary/robot_state.h", - "ur_robot_driver/include/ur_robot_driver/primary/robot_state/kinematics_info.h", - "ur_robot_driver/include/ur_robot_driver/primary/robot_state/master_board.h", - "ur_robot_driver/include/ur_robot_driver/primary/robot_state/robot_mode_data.h", - "ur_robot_driver/include/ur_robot_driver/queue/atomicops.h", - "ur_robot_driver/include/ur_robot_driver/queue/readerwriterqueue.h", - "ur_robot_driver/include/ur_robot_driver/rtde/control_package_pause.h", - "ur_robot_driver/include/ur_robot_driver/rtde/control_package_setup_inputs.h", - "ur_robot_driver/include/ur_robot_driver/rtde/control_package_setup_outputs.h", - "ur_robot_driver/include/ur_robot_driver/rtde/control_package_start.h", - "ur_robot_driver/include/ur_robot_driver/rtde/data_package.h", - "ur_robot_driver/include/ur_robot_driver/rtde/get_urcontrol_version.h", - "ur_robot_driver/include/ur_robot_driver/rtde/package_header.h", - "ur_robot_driver/include/ur_robot_driver/rtde/request_protocol_version.h", - "ur_robot_driver/include/ur_robot_driver/rtde/rtde_client.h", - "ur_robot_driver/include/ur_robot_driver/rtde/rtde_package.h", - "ur_robot_driver/include/ur_robot_driver/rtde/rtde_parser.h", - "ur_robot_driver/include/ur_robot_driver/rtde/rtde_writer.h", - "ur_robot_driver/include/ur_robot_driver/rtde/text_message.h", - "ur_robot_driver/include/ur_robot_driver/types.h", - "ur_robot_driver/include/ur_robot_driver/ur/calibration_checker.h", - "ur_robot_driver/include/ur_robot_driver/ur/dashboard_client.h", - "ur_robot_driver/include/ur_robot_driver/ur/datatypes.h", - "ur_robot_driver/include/ur_robot_driver/ur/tool_communication.h", - "ur_robot_driver/include/ur_robot_driver/ur/ur_driver.h", - "ur_robot_driver/include/ur_robot_driver/ur/version_information.h", - ], - copts = ["-Ipackages/universal_robots/ur_robot_driver/include"], - data = ["//packages/universal_robots:universal_robots_resources"], defines = ["BAZEL_BUILD"], - visibility = ["//visibility:public"], deps = [ - "//engine/gems/kinematic_tree", - "//packages/composite/gems:parser", - "//packages/map:kinematic_tree", - "@boost//:variant", - ], ) +isaac_cc_module( + name = "universal_robots", + srcs = [ + "ur_robot_driver/UniversalRobots.cpp", + "ur_robot_driver/DashboardClientIsaac.cpp", + "ur_robot_driver/UrclLogHandler.cpp", + "ur_client_library/src/log.cpp", + "ur_client_library/src/default_log_handler.cpp", + "ur_client_library/src/comm/tcp_server.cpp", + "ur_client_library/src/comm/tcp_socket.cpp", + "ur_client_library/src/primary/primary_package.cpp", + "ur_client_library/src/primary/robot_message.cpp", + "ur_client_library/src/primary/robot_state.cpp", + "ur_client_library/src/primary/robot_message/version_message.cpp", + "ur_client_library/src/primary/robot_state/kinematics_info.cpp", + "ur_client_library/src/rtde/control_package_pause.cpp", + "ur_client_library/src/rtde/control_package_setup_inputs.cpp", + "ur_client_library/src/rtde/control_package_setup_outputs.cpp", + "ur_client_library/src/rtde/control_package_start.cpp", + "ur_client_library/src/rtde/data_package.cpp", + "ur_client_library/src/rtde/get_urcontrol_version.cpp", + "ur_client_library/src/rtde/request_protocol_version.cpp", + "ur_client_library/src/rtde/rtde_client.cpp", + "ur_client_library/src/rtde/rtde_package.cpp", + "ur_client_library/src/rtde/rtde_writer.cpp", + "ur_client_library/src/rtde/text_message.cpp", + "ur_client_library/src/ur/calibration_checker.cpp", + "ur_client_library/src/ur/dashboard_client.cpp", + "ur_client_library/src/ur/tool_communication.cpp", + "ur_client_library/src/ur/ur_driver.cpp", + ], + hdrs = [ + "ur_robot_driver/UniversalRobots.hpp", + "ur_robot_driver/DashboardClientIsaac.hpp", + "ur_robot_driver/UrclLogHandler.hpp", + "ur_client_library/include/ur_client_library/comm/bin_parser.h", + "ur_client_library/include/ur_client_library/comm/package.h", + "ur_client_library/include/ur_client_library/comm/package_serializer.h", + "ur_client_library/include/ur_client_library/comm/parser.h", + "ur_client_library/include/ur_client_library/comm/pipeline.h", + "ur_client_library/include/ur_client_library/comm/producer.h", + "ur_client_library/include/ur_client_library/comm/reverse_interface.h", + "ur_client_library/include/ur_client_library/comm/script_sender.h", + "ur_client_library/include/ur_client_library/comm/tcp_server.h", + "ur_client_library/include/ur_client_library/comm/shell_consumer.h", + "ur_client_library/include/ur_client_library/comm/stream.h", + "ur_client_library/include/ur_client_library/comm/tcp_socket.h", + "ur_client_library/include/ur_client_library/exceptions.h", + "ur_client_library/include/ur_client_library/log.h", + "ur_client_library/include/ur_client_library/default_log_handler.h", + "ur_client_library/include/ur_client_library/primary/abstract_primary_consumer.h", + "ur_client_library/include/ur_client_library/primary/package_header.h", + "ur_client_library/include/ur_client_library/primary/primary_package.h", + "ur_client_library/include/ur_client_library/primary/primary_parser.h", + "ur_client_library/include/ur_client_library/primary/robot_message.h", + "ur_client_library/include/ur_client_library/primary/robot_message/version_message.h", + "ur_client_library/include/ur_client_library/primary/robot_state.h", + "ur_client_library/include/ur_client_library/primary/robot_state/kinematics_info.h", + "ur_client_library/include/ur_client_library/queue/atomicops.h", + "ur_client_library/include/ur_client_library/queue/readerwriterqueue.h", + "ur_client_library/include/ur_client_library/rtde/control_package_pause.h", + "ur_client_library/include/ur_client_library/rtde/control_package_setup_inputs.h", + "ur_client_library/include/ur_client_library/rtde/control_package_setup_outputs.h", + "ur_client_library/include/ur_client_library/rtde/control_package_start.h", + "ur_client_library/include/ur_client_library/rtde/data_package.h", + "ur_client_library/include/ur_client_library/rtde/get_urcontrol_version.h", + "ur_client_library/include/ur_client_library/rtde/package_header.h", + "ur_client_library/include/ur_client_library/rtde/request_protocol_version.h", + "ur_client_library/include/ur_client_library/rtde/rtde_client.h", + "ur_client_library/include/ur_client_library/rtde/rtde_package.h", + "ur_client_library/include/ur_client_library/rtde/rtde_parser.h", + "ur_client_library/include/ur_client_library/rtde/rtde_writer.h", + "ur_client_library/include/ur_client_library/rtde/text_message.h", + "ur_client_library/include/ur_client_library/types.h", + "ur_client_library/include/ur_client_library/ur/calibration_checker.h", + "ur_client_library/include/ur_client_library/ur/dashboard_client.h", + "ur_client_library/include/ur_client_library/ur/datatypes.h", + "ur_client_library/include/ur_client_library/ur/tool_communication.h", + "ur_client_library/include/ur_client_library/ur/ur_driver.h", + "ur_client_library/include/ur_client_library/ur/version_information.h", + ], + copts = ["-Ipackages/universal_robots/ur_client_library/include"], + data = ["//packages/universal_robots:universal_robots_resources"], + defines = ["ISAAC_BUILD"], + visibility = ["//visibility:public"], + deps = [ + "//packages/math/gems/kinematic_tree", + "//packages/composite/gems:parser", + "//packages/map:kinematic_tree", + "@boost//:variant", + "//packages/universal_robots/ur_msg:speed_slider_proto", + "//packages/universal_robots/ur_msg:dashboard_command_proto", + "//packages/universal_robots/ur_msg:dashboard_command", + "//packages/universal_robots/controller_stopper:controller_stopper", + "//packages/composite/gems:serializer", + ], +) \ No newline at end of file diff --git a/README.md b/README.md index 357e04a..2bdcb49 100644 --- a/README.md +++ b/README.md @@ -1,58 +1,210 @@ # Universal_Robots_Isaac_Driver -Universal Robots have become a dominant supplier of lightweight, robotic manipulators for industry, as well as for scientific research and education. It is the core value of Universal Robots, to empower people to achieve any goal within automation. -
Universal Robot e-Series family
+Universal Robots have become a dominant supplier of lightweight, robotic manipulators +for industry, as well as for scientific research and education. It is the core +value of Universal Robots, to empower people to achieve any goal within automation. -The goal of this driver is to provide a stable and sustainable interface between UR robots and NVIDIA Isaac-SDK that strongly benefit all parties. +
Universal
+Robot e-Series family
-NVIDIA Isaac-SDK is the main software toolkit for NVIDIA Robotics. Included in the Isaac SDK is the ability to easily write modular applications and deploy them on UR Robots. +The goal of this driver is to provide a stable and sustainable interface between +UR robots and NVIDIA Isaac-SDK that strongly benefit all parties. -The driver is currently not completed, or intended for industrial use without modification. Contribution is welcome on the driver. +NVIDIA Isaac-SDK is the main software toolkit for NVIDIA Robotics. Included in +the Isaac SDK is the ability to easily write modular applications and deploy them +on UR Robots. -
DISCLAIMER: This robot interface is under development and is not yet as robust as wanted. Documentation is missing and things will change.
+If you would like to help **[fill in the Survey](https://share.hsforms.com/19qJ5MI2WQYeDgfi07VAOUQ1kep1)** - +any feedback, suggestion or contribution - is highly appreciated! +Contribution to the driver are welcome. -## Acknowledgement - - This driver is forked from the [Universal Robots ROS Driver](https://github.com/UniversalRobots/Universal_Robots_ROS_Drive), -which is forked from the [ur_modern_driver](https://github.com/ros-industrial/ur_modern_driver). +## Features + +- Works for all **CB3 (with software version >= 3.7) and e-Series (software >= 5.1)** +UR robot or simulator. Simulator can be found on [Universal Robots website](https://www.universal-robots.com/download/?option=41508#section41493). + +- Can be used with **NVIDIA Jetson hardware platform** see [Universal Robots website](https://www.universal-robots.com/plus/urplus-components/plug-ins-interfaces/jetson-agx-xavier-developer-kit/). + +- Transparent **integration of the teach-pendant**. Using the URCaps system, a program +is running on the robot that handles control commands sent from Isaac side. With +this, the robot can be **paused**, **stopped** and **resumed** without restarting +the Isaac driver. + +- Use the robot's **speed-scaling**. When speed scaling is active due to safety +constraints or the speed slider is used, this gets correctly handled on the Isaac +side, as well slowing down trajectory execution accordingly.
+ **Note**: Other Isaaac-controllers can be used with this driver, but may behave + wrong if the speed slider isn't set to 100% or if + speed scaling slows down the robot. Also, pausing can only be used + when ur_controller is used. + +- **Using UR robots without interacting with the teach pendant** It is possible +to interact with the dashboard server through an Isaac Applications. A codelet serves +as an interface between the dashboardserver on the robot and an Isaac application. +A robot program can e.g. be started and stopped through an Isaac application. For +details see documentation on [DashboardClientIsaac](ur_robot_driver/doc/component_api.md#DashboardClientIsaac) +or documentation on [how to use it](ur_msg/README.md#DashboardClientIsaac-usage). + +## How to report an issue + +If you encounter any bugs or incomplete functionality please report them as issues. + +To create an issue on the [Issue Board](https://github.com/UniversalRobots/Universal_Robots_Isaac_Driver/issues/new) +please use the default template. + +## Contents + +This repository contains the **ur_robot_driver** and a couple of helper packages, +such as: + +- **apps**: Sample applications, which can be used for controlling an UR robot. + +- **controller_stopper**: A small external tool that stops and restarts Isaac-controller +based on the robot's state. This can be helpful when the robot is in a state where +it won't accept commands sent from Isaac. - - NVIDIA for making and maintain the [Isaac-SDK](https://www.nvidia.com/isaac) framework and libraries. As well as contributing to making this driver become reality. +- **ur_controller**: Speed-scaling-aware controller introduced with this driver. -## Recommended Prerequisites - - Can be used on a CB3 (with software version >= 3.7) and e-Series (software >= 5.1) UR robot or simulator. Simulator can be found on Universal Robots website here: https://www.universal-robots.com/download/?option=41508#section41493 +- **ur_msg**: Messages created specific to be used within this driver and to communicate +with this driver. See documentation on how to use [ur_msg in applications](ur_msg/README.md#UR-message-usage) - - Can be used with NVIDIA Jetson hardware platform see here: https://www.universal-robots.com/plus/urplus-components/plug-ins-interfaces/jetson-agx-xavier-developer-kit/ +- **ur_robot_driver**: The actual driver package. +## Requirements -Setup -------------- -1. Download Isaac SDK from https://developer.nvidia.com/isaac-sdk, then - follow the documentation to setup and install dependencies. -2. Clone this repository. -3. In Isaac SDK folder, create a symlink "packages/universal_robots" to - this repository: +This driver requires a system setup with Isaac SDK. Isaac currently only supports +Ubuntu 18.04 LTS with NVIDIA graphics card drivers see here [Isaac SDK prerequisites](https://docs.nvidia.com/isaac/isaac/doc/setup.html#prerequisites). + +The driver requires Isaac SDK version 20202.2. Isaac SDK can be downloaded from +[Isaac download](https://developer.nvidia.com/isaac/downloads), then follow [Isaac setup](https://docs.nvidia.com/isaac/isaac/doc/setup.html) +to install dependencies and set it up. + +## Setting up the driver + +**Note:** The Isaac driver is build on top of a [C++ client +library](https://github.com/UniversalRobots/Universal_Robots_Client_Library) that +abstracts the robot's interfaces. This +library needs to be cloned together with the C++ client library repository for the +driver to work. See the following setup guide: + +1. Create a folder to store the driver and client library + +```bash +$ mkdir isaac_driver && cd isaac_driver ``` -isaac/packages/universal_robots -> /home/username/universal_robots + +2. Clone the [Universal_Robot_Client_Library](https://github.com/UniversalRobots/Universal_Robots_Client_Library/tree/boost): + +```bash +$ git clone -b boost https://github.com/UniversalRobots/Universal_Robots_Client_Library.git ``` -4. In Isaac SDK folder, run +3. Clone this repository + +```bash +$ git clone https://github.com/UniversalRobots/Universal_Robots_Isaac_Driver.git ``` -bazel run packages/universal_robots/apps:simple_joint_control + +4. In this repository create a symlink "ur_client_library" to the client library. + +```bash +# /home/username/isaac_driver/Universal_Robots_Isaac_Driver/ur_client_library -> /home/username/isaac_driver/Universal_Robots_Client_Library/ + +$ ln -s /home/username/isaac_driver/Universal_Robots_Client_Library/ /home/username/isaac_driver/Universal_Robots_Isaac_Driver/ur_client_library ``` - This should open a jupyter notebook in browser. Follow instructions - there to manually control joints or digital io channels on the arm. - Remember to update the ip for the arm. -5. A second example repetitively pick and place box between two preset - waypoints. This app assumes a vacuum pump is connected through the - digital io interfaces. Make sure to update the waypoints based on the - actual setup, and make sure the path between the waypoints are - obstacle-free, as the current planner in SDK do not have obstacle - avoidance capability. To run the app: +5. In the Isaac SDK folder create a symlink "packages/universal_robots" to this repository. + +```bash +# /home/username/isaac/sdk/packages/universal_robots -> /home/username/isaac_driver/Universal_Robots_Isaac_Driver +$ ln -s /home/username/isaac_driver/Universal_Robots_Isaac_Driver /home/username/isaac/sdk/packages/universal_robots ``` -bazel run packages/universal_robots/apps:shuffle_box + +## Setup the robot + +For using the *ur_robot_driver* with a real robot you need to install the **externalcontrol-1.0.5.urcap** +which can be found inside the [**resources**](ur_robot_driver/resources/) folder +of this driver. + +**Note**: For installing this URCap a minimal PolyScope version of 3.7 or 5.1 (in +case of e-Series) is necessary. + +For installing the necessary URCap and creating a program, please see the individual +tutorials on how to [setup a CB3 robot](ur_robot_driver/doc/install_urcap_cb3.md) +or how to [setup an e-Series robot](ur_robot_driver/doc/install_urcap_e_series.md). + +Alternatively to use the driver without the URCap you can activate headless_mode, +when starting the driver, see documentation on [headless_mode](ur_robot_driver/README.md#headless-mode). + +## Quick start sample applications + +This driver servers as an interface between Universal Robots and Isaac SDK's application. + +To start any applications, you have to stand in the Isaac SDK folder, see [Nvidias +documentation](https://docs.nvidia.com/isaac/isaac/doc/getting_started.html). This +driver comes with two sample applications, that can be used to control an UR robot. + +For more detailed documentation of launching the applications see the seperate [tutorial](ur_robot_driver/doc/sample_applications.md) + +1. The first [application](/apps/simple_joint_control.ipynb) can be run inside the +Isaac SDK folder, with the following command. Remember that you have +to stand in the `isaac/sdk` folder to launch the application. + + ```bash + $ bazel run packages/universal_robots/apps:simple_joint_control + ``` + + This should open a jupyter notebook in your browser. Follow instructions + there to manually control joints or digital io channels on the arm. + Remember to update the ip for the arm and robot generation. + +2. The second [application](/apps/shuffle_box_hardware.py) repetitively moves between +two preset waypoints. This app assumes a vacuum pump is connected through the digital +io interfaces. Make sure to update the waypoints based on the +actual setup, and make sure the path between the waypoints are obstacle-free. To +run the application, see below. Remember that you have +to stand in the `isaac/sdk` folder to launch the application. + + ```bash + $ bazel run packages/universal_robots/apps:shuffle_box_hardware -- --robot_ip "192.168.56.1" --generation "e-series" --headless_mode false + ``` + + For the parameter robot_ip insert the IP address on which the Isaac driver + can reach the robot. Update generation according to the robot generation + that you are using, generation is one of *e-series or cb3*. The last argument + can be used to enable [headless_mode](ur_robot_driver/README.md#headless-mode) + or not. + +3. Both samples can be run on Jetson. Follow [instructions](https://docs.nvidia.com/isaac/isaac/doc/getting_started.html#deploying-and-running-on-jetson) + to deploy the sample apps. + +4. Follow [Nvidias guide](https://docs.nvidia.com/isaac/isaac/doc/tutorials/building_apps.html) + to build your own applications. + +When running any of the applications above you will see the following error message +in the terminal. + +```bash +2021-04-29 13:07:32.825 ERROR packages/universal_robots/ur_client_library/src/ur/calibration_checker.cpp@50: "The calibration parameters of the connected robot don't match the ones from the given kinematics config file. Please be aware that this can lead to critical inaccuracies of tcp positions. Use the ur_calibration tool to extract the correct calibration from the robot and pass that into the description. See [https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#extract-calibration-information] for details". ``` -6. Both samples can be run on Jetson. Follow instructions in - https://docs.nvidia.com/isaac/isaac/doc/getting_started.html#deploying-and-running-on-jetson - to deploy the sample apps. + +This error message should just be ignored as the calibration feature is not implemented +in the Isaac driver. The driver works perfectly fine despite this error message. + +Once any of the applications are running you can start the robot program with loaded +URCap. From that moment on the robot is fully functional. You can make use of the +Pause function or even Stop the program. Simply press the Play button +again and the ISAAC driver will reconnect. + +Inside the Application terminal running the driver you should see the output `Robot +ready to receive control commands.` + +## Acknowledgement + +- This driver is forked from the [Universal Robots ROS Driver](https://github.com/UniversalRobots/Universal_Robots_ROS_Driver), +which is forked from the [ur_modern_driver](https://github.com/ros-industrial/ur_modern_driver). + +- NVIDIA for making and maintaining the [Isaac-SDK](https://www.nvidia.com/isaac) +framework and libraries. As well as contributing to making this driver become reality. diff --git a/UniversalRobots.hpp b/UniversalRobots.hpp deleted file mode 100644 index 708a2ff..0000000 --- a/UniversalRobots.hpp +++ /dev/null @@ -1,177 +0,0 @@ -// -- BEGIN LICENSE BLOCK ---------------------------------------------- -// Copyright 2020 Universal Robots A/S -// -// 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. - -// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of -// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS -// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR -// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE -// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY -// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, -// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, -// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the -// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an -// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first -// published, e.g. “2020”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice -// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, -// please contact legal@universal-robots.com. -// -- END LICENSE BLOCK ------------------------------------------------ - -#pragma once -#include -#include -#include -#include - -#include "ur_robot_driver/ur/ur_driver.h" -#include "engine/alice/alice_codelet.hpp" -#include "engine/gems/kinematic_tree/kinematic_tree.hpp" -#include "packages/composite/gems/parser.hpp" -#include "messages/composite.capnp.h" - -namespace isaac -{ -namespace universal_robots -{ -// Available control modes for arm. -enum ArmControlMode -{ - kJointPosition, // Control joints position - kJointSpeed, // Control joints speed - kInvalid = -1 // Invalid control mode, returned from an invalid string in JSON -}; - -// Mapping between each ArmControlMode type and an identifying string. -NLOHMANN_JSON_SERIALIZE_ENUM(ArmControlMode, { { kInvalid, nullptr }, - { kJointPosition, "joint position" }, - { kJointSpeed, "joint " - "speed" } }); - -enum class PausingState -{ - PAUSED, - RUNNING, - RAMPUP -}; - -class UniversalRobots : public isaac::alice::Codelet -{ -public: - void start() override; - void tick() override; - void stop() override; - - // Command for arm, parsed based on control mode - ISAAC_PROTO_RX(CompositeProto, arm_command); - - // Command for arm, parsed based on control mode - ISAAC_PROTO_RX(CompositeProto, io_command); - - // Current state, includes joint angles and speed - ISAAC_PROTO_TX(CompositeProto, arm_state); - - // Current io, includes digital inputs and outputs - ISAAC_PROTO_TX(CompositeProto, io_state); - - // Set control mode for arm. - ISAAC_PARAM(ArmControlMode, control_mode, kJointPosition); - // Name of the node containing the map:KinematicTree component. This is used to obtain the names - // of the joints for parsing/creating composite message. - ISAAC_PARAM(std::string, kinematic_tree); - // Name of the joints for parsing/creating composite message. - ISAAC_PARAM(std::vector, misc_names, std::vector({ "timestamp", "speed_fraction" })); - // Entity name for digital output from the arm to devices on the IO interface. - ISAAC_PARAM(std::vector, tool_digital_out_names, - std::vector({ "tool_digital_out_0", "tool_digital_out_1" })); - // Entity name for digital input to the arm from devices on the IO interface. - ISAAC_PARAM(std::vector, tool_digital_in_names, - std::vector({ "tool_digital_in_0", "tool_digital_in_1" })); - - // Driver settings - ISAAC_PARAM(std::string, robot_ip, "127.0.0.1"); - ISAAC_PARAM(std::string, control_script_program, - "packages/universal_robots/ur_robot_driver/resources/" - "ros_control.urscript"); - ISAAC_PARAM(std::string, rtde_input_recipe, - "packages/universal_robots/ur_robot_driver/resources/" - "rtde_input_recipe.txt"); - ISAAC_PARAM(std::string, rtde_output_recipe, - "packages/universal_robots/ur_robot_driver/resources/" - "rtde_output_recipe.txt"); - -private: - ur_driver::UrDriver* ur_driver; - void handle_program_state(bool program_running); - std::thread RTDEMainLoopTrd; - bool rtde_thread_running; - void RTDEMainLoop(); - - struct RobotState - { - double timestamp; - ur_driver::vector6d_t q, qd; - uint64_t actual_dig_in_bits, actual_dig_out_bits; - double speed_fraction; - }; - - std::mutex robotStateMutex; - bool updateRobotState(); - RobotState latestRobotState; - - PausingState pausing_state_; - double pausing_ramp_up_increment_; - double speed_scaling_combined_; - bool updateSpeedScale(ur_driver::rtde_interface::DataPackage* data_pkg); - - // Validates the kinematic tree object is consistent with the hardware model - bool validateKinematicTree(const kinematic_tree::KinematicTree& model); - - // Request a schema for parsing command based on control mode - void initCommandParser(const ArmControlMode mode); - void initIOCommandParser(); - - // Parse command from Composite message - void parseCommand(const ArmControlMode mode); - void parseIOCommand(); - - // Generate the composite schema for publishing state - void initStateSchema(); - void initIOSchema(); - - // Arm state - void publishRobotState(RobotState state); - void publishIOState(RobotState state); - void publishState(); - - // Cache control mode. If control mode changed, need to reset parser schema. - ArmControlMode control_mode_; - // Cache list of joint names used in the kinematic tree - std::vector joint_names_; - - // Acquire time for most recently received position command - std::optional last_command_time_, last_io_command_time_; - - // Parsers for command message - composite::Parser command_parser_; - composite::Parser io_command_parser_; - - // Cache schema for state message - composite::Schema state_schema_; - composite::Schema io_schema_; -}; - -} // namespace universal_robots -} // namespace isaac - -ISAAC_ALICE_REGISTER_CODELET(isaac::universal_robots::UniversalRobots); diff --git a/apps/BUILD b/apps/BUILD index cb33423..f66a025 100644 --- a/apps/BUILD +++ b/apps/BUILD @@ -1,10 +1,22 @@ -load("//engine/build:isaac.bzl", "isaac_jupyter_app", "isaac_py_app") +load("//bzl:py.bzl", "isaac_jupyter_app", "isaac_py_app") +load("//bzl:module.bzl", "isaac_subgraph") + +isaac_subgraph( + name = "shuffle_box_behavior_hardware_subgraph", + modules = [ + "behavior_tree", + "composite", + ], + subgraph = "shuffle_box_behavior_hardware.subgraph.json", + visibility = ["//visibility:public"], +) isaac_jupyter_app( name = "simple_joint_control", data = [ "//apps/assets/kinematic_trees", - "//packages/planner/apps:multi_joint_lqr_control_subgraph", + "//packages/universal_robots/ur_robot_driver/apps:ur_eseries_robot_subgraph", + "//packages/universal_robots/ur_robot_driver/apps:ur_cb3_robot_subgraph", ], modules = [ "sight", @@ -19,8 +31,9 @@ isaac_py_app( srcs = ["shuffle_box_hardware.py"], data = [ "//apps/assets/kinematic_trees", - "//apps/samples/manipulation:shuffle_box_behavior_subgraph", - "//packages/planner/apps:multi_joint_lqr_control_subgraph", + "//packages/universal_robots/apps:shuffle_box_behavior_hardware_subgraph", + "//packages/universal_robots/ur_robot_driver/apps:ur_eseries_robot_subgraph", + "//packages/universal_robots/ur_robot_driver/apps:ur_cb3_robot_subgraph", ], modules = [ "behavior_tree", @@ -29,6 +42,6 @@ isaac_py_app( "universal_robots", ], deps = [ - "//engine/pyalice", + "//packages/pyalice", ], -) +) \ No newline at end of file diff --git a/apps/shuffle_box_behavior_hardware.subgraph.json b/apps/shuffle_box_behavior_hardware.subgraph.json new file mode 100644 index 0000000..28d224f --- /dev/null +++ b/apps/shuffle_box_behavior_hardware.subgraph.json @@ -0,0 +1,318 @@ +{ + "modules": [ + "behavior_tree", + "composite" + ], + "graph": { + "nodes": [ + { + "name": "interface", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "subgraph", + "type": "isaac::alice::Subgraph" + } + ] + }, + { + "name": "sequence_behavior", + "components": [ + { + "name": "NodeGroup", + "type": "isaac::behavior_tree::NodeGroup" + }, + { + "name": "MemorySequenceBehavior", + "type": "isaac::behavior_tree::MemorySequenceBehavior" + } + ], + "disable_automatic_start": true + }, + { + "name": "repeat_behavior", + "components": [ + { + "name": "NodeGroup", + "type": "isaac::behavior_tree::NodeGroup" + }, + { + "name": "RepeatBehavior", + "type": "isaac::behavior_tree::RepeatBehavior" + } + ], + "disable_automatic_start": true + }, + { + "name": "atlas", + "components": [ + { + "name": "CompositeAtlas", + "type": "isaac::composite::CompositeAtlas" + } + ] + }, + { + "name": "joint_follow_path", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "CompositePublisher", + "type": "isaac::composite::CompositePublisher" + }, + { + "name": "CompositeMetric", + "type": "isaac::composite::CompositeMetric" + }, + { + "name": "FollowPath", + "type": "isaac::composite::FollowPath" + } + ], + "disable_automatic_start": true + }, + { + "name": "suction_follow_path", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "CompositePublisher", + "type": "isaac::composite::CompositePublisher" + }, + { + "name": "CompositeMetric", + "type": "isaac::composite::CompositeMetric" + }, + { + "name": "FollowPath", + "type": "isaac::composite::FollowPath" + } + ], + "disable_automatic_start": true + }, + { + "name": "config_cart_to_dolly", + "components": [ + { + "name": "ConfigLoader", + "type": "isaac::alice::ConfigLoader" + } + ], + "disable_automatic_start": true + }, + { + "name": "config_dolly_to_cart", + "components": [ + { + "name": "ConfigLoader", + "type": "isaac::alice::ConfigLoader" + } + ], + "disable_automatic_start": true + }, + { + "name": "config_dolly_lift", + "components": [ + { + "name": "ConfigLoader", + "type": "isaac::alice::ConfigLoader" + } + ], + "disable_automatic_start": true + }, + { + "name": "config_cart_lift", + "components": [ + { + "name": "ConfigLoader", + "type": "isaac::alice::ConfigLoader" + } + ], + "disable_automatic_start": true + }, + { + "name": "config_pickup", + "components": [ + { + "name": "ConfigLoader", + "type": "isaac::alice::ConfigLoader" + } + ], + "disable_automatic_start": true + }, + { + "name": "config_dropoff", + "components": [ + { + "name": "ConfigLoader", + "type": "isaac::alice::ConfigLoader" + } + ], + "disable_automatic_start": true + } + ], + "edges": [ + { + "source": "joint_follow_path/CompositePublisher/path", + "target": "joint_follow_path/FollowPath/path" + }, + { + "source": "joint_follow_path/FollowPath/goal", + "target": "interface/subgraph/joint_target" + }, + { + "source": "interface/subgraph/joint_state", + "target": "joint_follow_path/FollowPath/state" + }, + { + "source": "suction_follow_path/CompositePublisher/path", + "target": "suction_follow_path/FollowPath/path" + }, + { + "source": "suction_follow_path/FollowPath/goal", + "target": "interface/subgraph/io_command" + }, + { + "source": "interface/subgraph/io_state", + "target": "suction_follow_path/FollowPath/state" + } + ] + }, + "config": { + "sequence_behavior": { + "NodeGroup": { + "node_names": [ + "$(fullname config_cart_lift)", + "$(fullname joint_follow_path)", + "$(fullname config_pickup)", + "$(fullname suction_follow_path)", + "$(fullname config_cart_to_dolly)", + "$(fullname joint_follow_path)", + "$(fullname config_dropoff)", + "$(fullname suction_follow_path)", + "$(fullname config_dolly_lift)", + "$(fullname joint_follow_path)", + "$(fullname config_pickup)", + "$(fullname suction_follow_path)", + "$(fullname config_dolly_to_cart)", + "$(fullname joint_follow_path)", + "$(fullname config_dropoff)", + "$(fullname suction_follow_path)" + ] + } + }, + "repeat_behavior": { + "NodeGroup": { + "node_names": [ + "$(fullname sequence_behavior)" + ] + } + }, + "joint_follow_path": { + "CompositePublisher": { + "tick_period": "30Hz", + "atlas": "$(fullname atlas/CompositeAtlas)", + "report_success": true + }, + "FollowPath": { + "tick_period": "10Hz", + "wait_time": 1.0, + "tolerance": 0.1 + } + }, + "suction_follow_path": { + "CompositePublisher": { + "tick_period": "30Hz", + "atlas": "$(fullname atlas/CompositeAtlas)", + "report_success": true + }, + "CompositeMetric": { + "use_config_schema": true, + "schema": { + "entity": ["pump", "valve"], + "measure": "none" + } + }, + "FollowPath": { + "tick_period": "10Hz", + "wait_time": 0.5, + "tolerance": 0.1 + } + }, + "config_cart_lift": { + "ConfigLoader": { + "config": { + "behavior.joint_follow_path": { + "CompositePublisher": { + "path": ["cart_observe", "cart_align", "cart_dropoff"] + } + } + } + } + }, + "config_dolly_lift": { + "ConfigLoader": { + "config": { + "behavior.joint_follow_path": { + "CompositePublisher": { + "path": ["dolly_observe", "dolly_align", "dolly_dropoff"] + } + } + } + } + }, + "config_cart_to_dolly": { + "ConfigLoader": { + "config": { + "behavior.joint_follow_path": { + "CompositePublisher": { + "path": ["cart_align", "cart_observe", "dolly_observe", "dolly_align", "dolly_dropoff"] + } + } + } + } + }, + "config_dolly_to_cart": { + "ConfigLoader": { + "config": { + "behavior.joint_follow_path": { + "CompositePublisher": { + "path": ["dolly_align", "dolly_observe", "cart_observe", "cart_align", "cart_dropoff"] + } + } + } + } + }, + "config_pickup": { + "ConfigLoader": { + "config": { + "behavior.suction_follow_path": { + "CompositePublisher": { + "path": ["suction_on"] + } + } + } + } + }, + "config_dropoff": { + "ConfigLoader": { + "config": { + "behavior.suction_follow_path": { + "CompositePublisher": { + "path": ["suction_off", "valve_off"] + } + } + } + } + } + } +} \ No newline at end of file diff --git a/apps/shuffle_box_hardware.py b/apps/shuffle_box_hardware.py index dd9d5da..011cb5b 100644 --- a/apps/shuffle_box_hardware.py +++ b/apps/shuffle_box_hardware.py @@ -1,14 +1,14 @@ import numpy as np import argparse import json +import time -from engine.pyalice import Application, Cask -from engine.pyalice.Composite import create_composite_message +from isaac import Application, Cask +from packages.pyalice.Composite import create_composite_message ''' Moves a robot arm based on joint waypoints to pickup and dropoff a box between two pre-defined -locations repeatedly. In the UR10 use case it also visualizes 3d pose estimation of KLTSmall -boxes in Sight, though the perception result is not used in motion control. This is tested with -omniverse kit isaac sim. +locations repeatedly. This app assumes a vacuum pump is connected through the digital +io interfaces. This is tested with a robot, without a gripper connected. ''' @@ -20,7 +20,7 @@ def create_composite_waypoint(name, quantities, values): def create_composite_atlas(cask_root, joints): - '''Creates composite atlas cask with waypoints for ur10. Tested with ovkit sim''' + '''Creates composite atlas cask with waypoints for ur10.''' if len(joints) != 6: raise ValueError("UR10 should have 6 joints, got {}".format(len(joints))) @@ -59,11 +59,14 @@ def create_composite_atlas(cask_root, joints): cask.write_message(create_composite_waypoint("suction_off", quantities, SUCTION_OFF_WAYPOINT)) cask.write_message(create_composite_waypoint("valve_off", quantities, VALVE_OFF_WAYPOINT)) - if __name__ == '__main__': # Parse arguments parser = argparse.ArgumentParser(description="Sortbot Demo") parser.add_argument("--cask", help="Path to output atlas", default="/tmp/shuffle_box_waypoints") + parser.add_argument("--generation", help="Robot generation.", choices=["cb3", "e-series"], default="e-series") + parser.add_argument("--robot_ip", help="robot ip", default="192.168.56.101") + parser.add_argument("--headless_mode", help="start driver with headless mode enabled or not", + default=False, type=lambda x: (str(x).lower() == 'true')) args = parser.parse_args() # get kinematic file and joints @@ -79,55 +82,82 @@ def create_composite_atlas(cask_root, joints): create_composite_atlas(args.cask, joints) # Create and start the app - app = Application(name="Shuffle Box Hardware") + app = Application(name="Shuffle Box Hardware", modules=["sight"]) # load bebavior subgraph. this contains the sequency behavior to move the arm between - # waypoints and control suction on/off - app.load("apps/samples/manipulation/shuffle_box_behavior.subgraph.json", prefix="behavior") + # waypoints and control gripper digital output + app.load("packages/universal_robots/apps/shuffle_box_behavior_hardware.subgraph.json", prefix="behavior") behavior_interface = app.nodes["behavior.interface"]["subgraph"] app.nodes["behavior.atlas"]["CompositeAtlas"].config.cask = args.cask - app.load("packages/planner/apps/multi_joint_lqr_control.subgraph.json", prefix="lqr") - - # load multi joint lqr control subgraph - lqr_interface = app.nodes["lqr.subgraph"]["interface"] - kinematic_tree = app.nodes["lqr.kinematic_tree"]["KinematicTree"] - lqr_planner = app.nodes["lqr.local_plan"]["MultiJointLqrPlanner"] - app.connect(behavior_interface, "joint_target", lqr_interface, "joint_target") - kinematic_tree.config.kinematic_file = kinematic_file - lqr_planner.config.speed_min = [-1.0] * len(joints) - lqr_planner.config.speed_max = [1.0] * len(joints) - lqr_planner.config.acceleration_min = [-1.0] * len(joints) - lqr_planner.config.acceleration_max = [1.0] * len(joints) - - # load hardware subgraph - app.load_module("universal_robots") - arm = app.add("hardware").add(app.registry.isaac.universal_robots.UniversalRobots) - arm.config.robot_ip = "10.32.221.190" - arm.config.control_mode = "joint position" - arm.config.tick_period = '125Hz' - arm.config.kinematic_tree = "lqr.kinematic_tree" - arm.config.tool_digital_out_names = ["valve", "pump"] - arm.config.tool_digital_in_names = ["unknown", "gripper"] - - app.connect(arm, "arm_state", lqr_interface, "joint_state") - app.connect(arm, "arm_state", behavior_interface, "joint_state") - app.connect(arm, "io_state", behavior_interface, "io_state") - app.connect(lqr_interface, "joint_command", arm, "arm_command") - app.connect(behavior_interface, "io_command", arm, "io_command") - - # visualize IO in sight - widget_io = app.add("sight_widgets").add(app.registry.isaac.sight.SightWidget, "IO") - widget_io.config.type = "plot" - widget_io.config.channels = [ + + # Load driver subgraph + generation = args.generation + if generation == "e-series": + app.load("packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json", prefix="ur") + elif generation == "cb3": + app.load("packages/universal_robots/ur_robot_driver/apps/ur_cb3_robot.subgraph.json", prefix="ur") + else: + raise Exception("Unknown robot generation") + + # Load components + ur_interface = app.nodes["ur.subgraph"]["interface"] + ur_controller = app.nodes["ur.controller"]["ScaledMultiJointController"] + ur_driver = app.nodes["ur.universal_robots"]["UniversalRobots"] + + # Configs + ur_controller.config.control_mode = "joint position" + ur_driver.config.control_mode = "joint position" + ur_driver.config.robot_ip = args.robot_ip + ur_driver.config.headless_mode = args.headless_mode + ur_driver.config.tool_digital_out_names = ["valve", "pump"] + ur_driver.config.tool_digital_in_names = ["unknown", "gripper"] + + # Edges + app.connect(ur_interface, "arm_state", behavior_interface, "joint_state") + app.connect(ur_interface, "io_state", behavior_interface, "io_state") + app.connect(behavior_interface, "io_command", ur_interface, "io_command") + app.connect(behavior_interface, "joint_target", ur_interface, "joint_target") + + # Sequence nodes + sequence_behavior = app.nodes["behavior.sequence_behavior"] + repeat_behavior = app.nodes["behavior.repeat_behavior"] + nodes_stopped = True + + # Enable sight + widget = app.add("sight").add(app.registry.isaac.sight.SightWidget, "IO") + widget.config.type = "plot" + widget.config.channels = [ { - "name": "hardware/UniversalRobots/gripper" + "name": "ur.universal_robots/UniversalRobots/gripper" }, { - "name": "hardware/UniversalRobots/pump" + "name": "ur.universal_robots/UniversalRobots/pump" }, { - "name": "hardware/UniversalRobots/valve" + "name": "ur.universal_robots/UniversalRobots/valve" } ] # run app - app.run() + app.start() + + try: + while True: + # Make sure urcap is running when starting the nodes + program_running = app.receive("ur.subgraph", "interface", "robot_program_running") + if program_running is None: + time.sleep(1) + else: + if program_running.proto.flag == True and nodes_stopped: + sequence_behavior.start() + repeat_behavior.start() + nodes_stopped = False + elif program_running.proto.flag == False and nodes_stopped == False: + sequence_behavior.stop() + repeat_behavior.stop() + nodes_stopped = True + + except KeyboardInterrupt: + if nodes_stopped == False: + sequence_behavior.stop() + repeat_behavior.stop() + app.stop() \ No newline at end of file diff --git a/apps/simple_joint_control.ipynb b/apps/simple_joint_control.ipynb index d5c742e..e00cdeb 100644 --- a/apps/simple_joint_control.ipynb +++ b/apps/simple_joint_control.ipynb @@ -2,9 +2,20 @@ "cells": [ { "cell_type": "code", - "execution_count": null, + "execution_count": 1, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "'/root/.cache/bazel/_bazel_root/4ba0b84eadbbe44ac95feee54d73b56c/execroot/com_nvidia_isaac_sdk/bazel-out/k8-opt/bin/packages/universal_robots/apps/simple_joint_control.runfiles/com_nvidia_isaac_sdk'" + ] + }, + "execution_count": 1, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "import os\n", "# set the current working directory to the deployed package folder. This is required by isaac.\n", @@ -15,35 +26,45 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "from IPython.display import display\n", "import json\n", "import numpy as np\n", + "import time\n", "\n", - "from engine.pyalice import Application, Codelet\n", - "from engine.pyalice.gui.composite_widget import CompositeWidget\n", + "from packages.pyalice import Application, Codelet, Message\n", + "from packages.pyalice.gui.composite_widget import CompositeWidget\n", "\n", "np.set_printoptions(precision=3)" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']\n" + ] + } + ], "source": [ "# A Python codelet for joint control through widget\n", "class JointPositionControl(Codelet):\n", " def start(self):\n", " self.rx = self.isaac_proto_rx(\"CompositeProto\", \"state\")\n", " self.tx = self.isaac_proto_tx(\"CompositeProto\", \"command\")\n", - "\n", + " \n", " joints = self.config.joints\n", " limits = self.config.limits\n", " measure = self.config.measure\n", + " self.stop_control = 3\n", " self._widget = CompositeWidget(joints, measure, limits)\n", " if self._widget is None:\n", " report_failure(\"Cannot create valid widget\")\n", @@ -72,8 +93,10 @@ " joints.append(link['name'])\n", "print(joints)\n", "\n", - "# Obtain the UR10 IP from UR Console and update this\n", - "UR10_IP = \"10.32.221.190\"" + "# Obtain the IP from UR Console and update this\n", + "IP = \"192.168.56.1\"\n", + "# Robot generation that you are going to control \"e-series\" or \"cb3\"\n", + "GENERATION = \"e-series\"" ] }, { @@ -86,23 +109,56 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], + "execution_count": 5, + "metadata": { + "scrolled": true + }, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "2021-05-04 12:31:28,784 DEBUG Binding PyCodelet command_generator/PyCodelet\n", + "2021-05-04 12:31:28,787 DEBUG Launching isaac core\n", + "2021-05-04 12:31:28,789 DEBUG Launching pycodelet threads\n", + "2021-05-04 12:31:28,795 DEBUG Launching command_generator/PyCodelet\n" + ] + }, + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "db38dbc6409243748d4c1067061abc55", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "VBox(children=(HBox(children=(Label(value='shoulder_pan_joint', layout=Layout(width='150px')), FloatSlider(val…" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ - "app = Application(name=\"simple_joint_control_ur10_hardware\")\n", + "app = Application(name=\"simple_joint_control_ur_hardware\", modules=[\"sight\"])\n", + "\n", + "if GENERATION == \"e-series\": \n", + " app.load(filename=\"packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json\", prefix=\"ur\")\n", + "elif GENERATION == \"cb3\":\n", + " app.load(filename=\"packages/universal_robots/ur_robot_driver/apps/ur_cb3_robot.subgraph.json\", prefix=\"ur\")\n", + "else:\n", + " Exception(\"Unknown robot generation\")\n", "\n", - "# load lqr subgraphcs\n", - "app.load(filename=\"packages/planner/apps/multi_joint_lqr_control.subgraph.json\", prefix=\"lqr\")\n", - "lqr_interface = app.nodes[\"lqr.subgraph\"][\"interface\"]\n", + "# Load components for configuration\n", + "ur_interface = app.nodes[\"ur.subgraph\"][\"interface\"]\n", + "ur_controller = app.nodes[\"ur.controller\"][\"ScaledMultiJointController\"]\n", + "ur_driver = app.nodes[\"ur.universal_robots\"][\"UniversalRobots\"]\n", "\n", "# configs\n", - "app.nodes[\"lqr.kinematic_tree\"][\"KinematicTree\"].config.kinematic_file = kinematic_file\n", - "lqr_planner = app.nodes[\"lqr.local_plan\"][\"MultiJointLqrPlanner\"]\n", - "lqr_planner.config.speed_min = [-0.5] * len(joints)\n", - "lqr_planner.config.speed_max = [0.5] * len(joints)\n", - "lqr_planner.config.acceleration_min = [-0.5] * len(joints)\n", - "lqr_planner.config.acceleration_max = [0.5] * len(joints)\n", + "ur_controller.config.control_mode = \"joint speed\"\n", + "ur_driver.config.control_mode = \"joint speed\"\n", + "ur_driver.config.robot_ip = IP\n", + "ur_driver.config.headless_mode = False\n", "\n", "# add pycodelet for joint position control\n", "widget_node = app.add(\"command_generator\")\n", @@ -110,29 +166,54 @@ "joint_commander.config.joints = joints\n", "joint_commander.config.limits = [[-2*np.pi, 2*np.pi]] * len(joints)\n", "joint_commander.config.measure = 'position'\n", - "app.connect(joint_commander, \"command\", lqr_interface, \"joint_target\")\n", "\n", - "# add ur10 driver codelet\n", - "app.load_module(\"universal_robots\")\n", - "driver = app.add(\"ur\").add(app.registry.isaac.universal_robots.UniversalRobots)\n", - "# configs\n", - "driver.config.kinematic_tree = \"lqr.kinematic_tree\"\n", - "driver.config.control_mode = \"joint position\"\n", - "driver.config.robot_ip = UR10_IP\n", - "driver.config.tick_period = \"125Hz\"\n", "# edges\n", - "app.connect(driver, \"arm_state\", lqr_interface, \"joint_state\")\n", - "app.connect(driver, \"arm_state\", joint_commander, \"state\")\n", - "app.connect(lqr_interface, \"joint_command\", driver, \"arm_command\")\n", + "app.connect(joint_commander, \"command\", ur_interface, \"joint_target\")\n", + "app.connect(ur_interface, \"arm_state\", joint_commander, \"state\")\n", "\n", - "app.start()" + "# Enable sight\n", + "widget = app.add(\"sight\").add(app.registry.isaac.sight.SightWidget, \"simple_joint_control\")\n", + "widget.config.type = \"plot\"\n", + "widget.config.channels = [\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/shoulder_pan_joint\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/shoulder_lift_joint\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/elbow_joint\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/wrist_1_joint\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/wrist_2_joint\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/wrist_3_joint\"\n", + " }\n", + "\n", + "]\n", + "\n", + "# start application\n", + "app.start()\n" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 7, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "2021-04-29 12:23:34,917 DEBUG Stopped command_generator/PyCodelet\n", + "2021-04-29 12:23:34,918 DEBUG Python Codelets All stopped...\n" + ] + } + ], "source": [ "app.stop()" ] @@ -142,66 +223,105 @@ "metadata": {}, "source": [ "UR10 Digital IO Control\n", - "=======" + "=====" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 6, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "2021-05-04 12:53:50,384 DEBUG Binding PyCodelet command_generator/PyCodelet\n", + "2021-05-04 12:53:50,387 DEBUG Launching isaac core\n", + "2021-05-04 12:53:50,388 DEBUG Launching pycodelet threads\n", + "2021-05-04 12:53:50,389 DEBUG Launching command_generator/PyCodelet\n" + ] + }, + { + "data": { + "application/vnd.jupyter.widget-view+json": { + "model_id": "476f9c1bcc2043f6ad42e176546771c8", + "version_major": 2, + "version_minor": 0 + }, + "text/plain": [ + "VBox(children=(HBox(children=(Label(value='tool_digital_out_0', layout=Layout(width='150px')), FloatSlider(val…" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ - "app = Application(name=\"io_control_ur10_hardware\")\n", + "app = Application(name=\"io_control_ur_hardware\", modules=[\"sight\"])\n", "\n", - "# load lqr subgraphcs\n", - "app.load(filename=\"packages/planner/apps/multi_joint_lqr_control.subgraph.json\", prefix=\"lqr\")\n", - "lqr_interface = app.nodes[\"lqr.subgraph\"][\"interface\"]\n", + "if GENERATION == \"e-series\": \n", + " app.load(filename=\"packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json\", prefix=\"ur\")\n", + "elif GENERATION == \"cb3\":\n", + " app.load(filename=\"packages/universal_robots/ur_robot_driver/apps/ur_cb3_robot.subgraph.json\", prefix=\"ur\")\n", + "else:\n", + " Exception(\"Unknown robot generation\")\n", "\n", - "# configs\n", - "app.nodes[\"lqr.kinematic_tree\"][\"KinematicTree\"].config.kinematic_file = kinematic_file\n", - "lqr_planner = app.nodes[\"lqr.local_plan\"][\"MultiJointLqrPlanner\"]\n", - "lqr_planner.config.speed_min = [-0.5] * len(joints)\n", - "lqr_planner.config.speed_max = [0.5] * len(joints)\n", - "lqr_planner.config.acceleration_min = [-0.5] * len(joints)\n", - "lqr_planner.config.acceleration_max = [0.5] * len(joints)\n", - "\n", - "# add ur10 driver codelet\n", - "app.load_module(\"universal_robots\")\n", - "driver = app.add(\"ur\").add(app.registry.isaac.universal_robots.UniversalRobots)\n", - "# configs\n", - "driver.config.kinematic_tree = \"lqr.kinematic_tree\"\n", - "driver.config.robot_ip = UR10_IP\n", - "driver.config.tick_period = \"100Hz\"\n", + "# Load components for configuration\n", + "ur_interface = app.nodes[\"ur.subgraph\"][\"interface\"]\n", + "ur_driver = app.nodes[\"ur.universal_robots\"][\"UniversalRobots\"]\n", "\n", - "# add pycodelet for digitalIO control\n", - "io_names = driver.config.tool_digital_out_names\n", + "io_names = ur_driver.config.tool_digital_out_names\n", + "ur_driver.config.robot_ip = IP\n", "\n", + "# add pycodelet for digitalIO control\n", "widget_node = app.add(\"command_generator\")\n", "io_commander = widget_node.add(JointPositionControl)\n", "io_commander.config.joints = io_names\n", "io_commander.config.limits = [[0, 1]] * len(io_names)\n", "io_commander.config.measure = 'none'\n", - "app.connect(io_commander, \"command\", driver, \"io_command\")\n", - "app.connect(driver, \"io_state\", io_commander, \"state\")\n", + "\n", + "# Edges\n", + "app.connect(io_commander, \"command\", ur_interface, \"io_command\")\n", + "app.connect(ur_interface, \"io_state\", io_commander, \"state\")\n", + "\n", + "# Enable sight\n", + "widget = app.add(\"sight\").add(app.registry.isaac.sight.SightWidget, \"shuffle_box_hardware\")\n", + "widget.config.type = \"plot\"\n", + "widget.config.channels = [\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/tool_digital_out_0\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/tool_digital_out_1\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/tool_digital_in_0\"\n", + " },\n", + " {\n", + " \"name\": \"ur.universal_robots/UniversalRobots/tool_digital_in_1\"\n", + " }\n", + "]\n", "\n", "app.start()" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 7, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "2021-05-04 12:55:22,145 DEBUG Stopped command_generator/PyCodelet\n", + "2021-05-04 12:55:22,146 DEBUG Python Codelets All stopped...\n" + ] + } + ], "source": [ "app.stop()" ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] } ], "metadata": { @@ -213,14 +333,14 @@ "language_info": { "codemirror_mode": { "name": "ipython", - "version": 2 + "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.17" + "pygments_lexer": "ipython3", + "version": "3.6.9" } }, "nbformat": 4, diff --git a/controller_stopper/BUILD b/controller_stopper/BUILD new file mode 100644 index 0000000..729f008 --- /dev/null +++ b/controller_stopper/BUILD @@ -0,0 +1,16 @@ +load("@com_nvidia_isaac_engine//bzl:isaac_engine.bzl", "isaac_cc_library") + +isaac_cc_library( + name = "controller_stopper", + srcs = [ + "ControllerStopper.cpp" + ], + hdrs = [ + "ControllerStopper.hpp" + ], + visibility = ["//visibility:public"], + deps = [ + "@com_nvidia_isaac_engine//engine/alice", + "//messages:basic_proto" + ], +) \ No newline at end of file diff --git a/controller_stopper/ControllerStopper.cpp b/controller_stopper/ControllerStopper.cpp new file mode 100644 index 0000000..6ca16be --- /dev/null +++ b/controller_stopper/ControllerStopper.cpp @@ -0,0 +1,77 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "ControllerStopper.hpp" +#include "engine/alice/backend/backend.hpp" +#include "engine/alice/backend/node_backend.hpp" +#include "engine/alice/node.hpp" + +namespace isaac +{ +namespace controller_stopper +{ +void ControllerStopper::start() +{ + // Try get the controller node + const auto controller_node = try_get_controller(); + if (!controller_node) + { + reportFailure("controller node is not specified."); + return; + } + controller_node_ = node()->app()->getNodeByName(*controller_node); + + // Stop the node as the first thing + node()->app()->backend()->node_backend()->stopNode(controller_node_); + controller_node_stopped_ = true; + + // Setup tick + tickOnMessage(rx_robot_program_running()); +} + +void ControllerStopper::tick() +{ + auto proto = rx_robot_program_running().getProto(); + if (proto.getFlag() && controller_node_stopped_) + { + LOG_DEBUG("starting controller"); + node()->app()->backend()->node_backend()->startNode(controller_node_); + controller_node_stopped_ = false; + } + else if (proto.getFlag() == false && controller_node_stopped_ == false) + { + LOG_DEBUG("stopping controller"); + node()->app()->backend()->node_backend()->stopNode(controller_node_); + controller_node_stopped_ = true; + } +} + +} // namespace controller_stopper +} // namespace isaac \ No newline at end of file diff --git a/controller_stopper/ControllerStopper.hpp b/controller_stopper/ControllerStopper.hpp new file mode 100644 index 0000000..0894306 --- /dev/null +++ b/controller_stopper/ControllerStopper.hpp @@ -0,0 +1,83 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include + +#include "engine/alice/alice_codelet.hpp" +#include "messages/basic.capnp.h" + +namespace isaac +{ +namespace controller_stopper +{ +/*! + * \brief ControllerStopper class is a small helper component that stops and restarts the controller based on a boolean + * message. When the message goes to false, the controller is stopped. If message returns to true the stopped controller + * is restarted. + */ +class ControllerStopper : public isaac::alice::Codelet +{ +public: + /*! + * \brief Handles the setup functionality of this class. This includes collecting the controller node. + */ + void start() override; + /*! + * \brief This functions is run every time the robot_program_running message is published. + * When the message goes to false, the controller is stopped. If message returns to true the stopped controller is + * restarted. + */ + void tick() override; + + /*! + * \brief Receives the robots running state. + */ + ISAAC_PROTO_RX(BooleanProto, robot_program_running); + + /*! + * \brief Name of the node containing the controller node that is sending targets to the driver. + * This node is started and stopped based upon the drivers control status of the robot. + */ + ISAAC_PARAM(std::string, controller); + +private: + // Node containing the controller. + alice::Node* controller_node_; + + // Boolean to represent if the controller is currently stopped + bool controller_node_stopped_; +}; + +} // namespace controller_stopper +} // namespace isaac + +ISAAC_ALICE_REGISTER_CODELET(isaac::controller_stopper::ControllerStopper) \ No newline at end of file diff --git a/controller_stopper/README.md b/controller_stopper/README.md new file mode 100644 index 0000000..9a3dd5b --- /dev/null +++ b/controller_stopper/README.md @@ -0,0 +1,10 @@ +# Controller stopper + +A small helper component that stops and restarts Isaac controller based on a boolean +status message. When the status goes to false, all running controllers except a +set of predefined consistent_controller get stopped. If status returns to true +the stopped controller are restarted. + +The ControllerStopper component is automatically started within the UniversalRobots +codelet. So no configuration is needed to use this node. The component is explained +further in [component api](../ur_robot_driver/doc/component_api.md#ControllerStopper) diff --git a/ur_controller/BUILD b/ur_controller/BUILD new file mode 100644 index 0000000..306b404 --- /dev/null +++ b/ur_controller/BUILD @@ -0,0 +1,42 @@ +load("@com_nvidia_isaac_engine//bzl:isaac_engine.bzl", "isaac_cc_library") +load("//bzl:module.bzl", "isaac_cc_module",) + +isaac_cc_module( + name = "ur_controller", + srcs = [ + "ScaledMultiJointController.cpp", + "JointSegment.cpp", + "JointTrajectory.cpp" + ], + hdrs = [ + "ScaledMultiJointController.hpp", + "JointSegment.hpp", + "Pid.hpp", + "JointTrajectory.hpp" + ], + deps=[ + "//packages/map:kinematic_tree", + "//packages/composite/gems:serializer", + "//packages/composite/gems:parser" + ] +) + +isaac_cc_library( + name = "ur_controller_test", + srcs = [ + "ScaledMultiJointController.cpp", + "JointSegment.cpp", + "JointTrajectory.cpp" + ], + hdrs = [ + "ScaledMultiJointController.hpp", + "JointSegment.hpp", + "Pid.hpp", + "JointTrajectory.hpp" + ], + deps=[ + "//packages/map:kinematic_tree", + "//packages/composite/gems:parser" + ], + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/ur_controller/JointSegment.cpp b/ur_controller/JointSegment.cpp new file mode 100644 index 0000000..8ea7772 --- /dev/null +++ b/ur_controller/JointSegment.cpp @@ -0,0 +1,178 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "JointSegment.hpp" +#include "engine/core/math/types.hpp" + +namespace isaac +{ +namespace ur_controller +{ +namespace +{ +constexpr int linearInterpolation = 1; +constexpr int cubicInterpolation = 2; +constexpr int quinticInterpolation = 3; +} // namespace + +JointSegment::JointSegment() : duration_(0.0), start_time_(0.0) +{ + coefficients_ << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; +} + +JointSegment::JointSegment(const Timeseries::Entry& start_waypoint, + const Timeseries::Entry& end_waypoint) +{ + coefficients_ << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; + initSegment(start_waypoint, end_waypoint); +} + +void JointSegment::initSegment(const Timeseries::Entry& start_waypoint, + const Timeseries::Entry& end_waypoint) +{ + ASSERT(start_waypoint.stamp <= end_waypoint.stamp, "start_waypoint stamp shouldn't be larger than end_waypoint " + "stamp"); + ASSERT(start_waypoint.state.rows() >= linearInterpolation && end_waypoint.state.rows() >= linearInterpolation, "empty" + " stat" + "e"); + ASSERT(start_waypoint.state.rows() == end_waypoint.state.rows(), "start_waypoint and end_waypoint states size " + "mismatch"); + + // Set all coefficients to zero + coefficients_ << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; + + duration_ = end_waypoint.stamp - start_waypoint.stamp; + start_time_ = start_waypoint.stamp; + + if (start_waypoint.state.rows() == linearInterpolation) + { + linearCoefficients(start_waypoint.state, end_waypoint.state, duration_); + } + else if (start_waypoint.state.rows() == cubicInterpolation) + { + cubicCoefficients(start_waypoint.state, end_waypoint.state, duration_); + } + else if (start_waypoint.state.rows() == quinticInterpolation) + { + quinticCoefficients(start_waypoint.state, end_waypoint.state, duration_); + } + else + { + PANIC("To many elements in the state vector"); + } +} + +Vector6d JointSegment::getCoefficients() +{ + return coefficients_; +} + +const double JointSegment::getEndTime() +{ + return start_time_ + duration_; +} + +const double JointSegment::getStartTime() +{ + return start_time_; +} + +void JointSegment::interpolate(const double& stamp, double& pos, double& vel, double& acc) +{ + // We can only interpolate within the waypoints. + ASSERT(start_time_ <= stamp && stamp <= start_time_ + duration_, "Time stamp is not within the boundaries."); + + const double x = stamp - start_time_; + + pos = ((((coefficients_[5] * x + coefficients_[4]) * x + coefficients_[3]) * x + coefficients_[2]) * x + + coefficients_[1]) * x + coefficients_[0]; + vel = (((5.0 * coefficients_[5] * x + 4.0 * coefficients_[4]) * x + 3.0 * coefficients_[3]) * x + + 2.0 * coefficients_[2]) * x + coefficients_[1]; + acc = ((20.0 * coefficients_[5] * x + 12.0 * coefficients_[4]) * x + 6.0 * coefficients_[3]) * x + + 2.0 * coefficients_[2]; +} + +void JointSegment::linearCoefficients(const VectorXd& start, const VectorXd& end, const double& x) +{ + if (x == 0.0) + { + coefficients_[0] = start[0]; + } + else + { + coefficients_[0] = start[0]; + coefficients_[1] = (end[0] - start[0]) / x; + } +} + +void JointSegment::cubicCoefficients(const VectorXd& start, const VectorXd& end, const double& x) +{ + if (x == 0.0) + { + coefficients_[0] = start[0]; + coefficients_[1] = start[1]; + } + else + { + Vector4d powers; + powers << 1.0, x, x * x, x * x * x; + coefficients_[0] = start[0]; + coefficients_[1] = start[1]; + coefficients_[2] = (3.0 * (-start[0] + end[0]) + (-2.0 * start[1] - end[1]) * powers[1]) / powers[2]; + coefficients_[3] = (2.0 * (start[0] - end[0]) + (start[1] + end[1]) * powers[1]) / powers[3]; + } +} + +void JointSegment::quinticCoefficients(const VectorXd& start, const VectorXd& end, const double& x) +{ + if (x == 0.0) + { + coefficients_[0] = start[0]; + coefficients_[1] = start[1]; + coefficients_[2] = 0.5 * start[2]; + } + else + { + Vector6d powers; + powers << 1.0, x, x * x, x * x * x, x * x * x * x, x * x * x * x * x; + coefficients_[0] = start[0]; + coefficients_[1] = start[1]; + coefficients_[2] = 0.5 * start[2]; + coefficients_[3] = (20.0 * (-start[0] + end[0]) + (-12.0 * start[1] - 8.0 * end[1]) * powers[1] + + (-3.0 * start[2] + end[2]) * powers[2]) / (2.0 * powers[3]); + coefficients_[4] = (30.0 * (start[0] - end[0]) + (16.0 * start[1] + 14.0 * end[1]) * powers[1] + + (3.0 * start[2] - 2.0 * end[2]) * powers[2]) / (2.0 * powers[4]); + coefficients_[5] = (12.0 * (-start[0] + end[0]) + 6.0 * (-start[1] - end[1]) * powers[1] + + (-start[2] + end[2]) * powers[2]) / (2.0 * powers[5]); + } +} + +} // namespace ur_controller +} // namespace isaac \ No newline at end of file diff --git a/ur_controller/JointSegment.hpp b/ur_controller/JointSegment.hpp new file mode 100644 index 0000000..f515b8a --- /dev/null +++ b/ur_controller/JointSegment.hpp @@ -0,0 +1,156 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include + +#include "engine/core/math/types.hpp" +#include "engine/gems/algorithm/timeseries.hpp" + +namespace isaac +{ +namespace ur_controller +{ +/*! + * \brief Calculates a segment between two waypoints. The segment is a function describing + * joint position as a function of time. The function can be linear, cubic or quintic. + */ + +class JointSegment +{ +public: + /*! + * \brief Construct a new Joint Segment object + */ + JointSegment(); + + /*! + * \brief Construct a new Joint Segment object with a start_waypoint and end_waypoint. + * This constructor calls initSegment. + * + * Timeseries::Entry is a struct describing a waypoint. + * Struct Entry { + * double Stamp + * VectorXd state + * }; + * An Entry consist of a timestamp and a state which is the current state at that timestamp. + * State is vector with 1, 2 or 3 entries depending on wheter the vector consist of pos, vel and acc. + * This function calls InitSegment. + * + * \param start_waypoint the first waypoint + * \param end_waypoint the second waypoint + */ + JointSegment(const Timeseries::Entry& start_waypoint, + const Timeseries::Entry& end_waypoint); + + /*! + * \brief Calculates the function between the two waypoints. + * + * If State has length 1 linear function will be calculated. + * y = coffiecients_[1]*x + coffiecients_[0] + * coffiecients_[2] = coffiecients_[3] = coffiecients_[4] = coffiecients_[5] = 0. + * + * If State has length 2 cubic function will be calculated. + * y = coffiecients_[3]*x^3 + coffiecients_[2]*x^2 + coffiecients_[1]*x + coffiecients_[0] + * coffiecients_[4] = coffiecients_[5] = 0. + * + * If State has length 3 quintic function will be calculated. + * y = coffiecients_[5]*x^5 + coffiecients_[4]*x^4 + coffiecients_[3]*x^3 + coffiecients_[2]*x^2 + coffiecients_[1]*x + * + coffiecients_[0] + * + * \param start_waypoint the first waypoint + * \param end_waypoint the second waypoint + */ + void initSegment(const Timeseries::Entry& start_waypoint, + const Timeseries::Entry& end_waypoint); + + /*! + * \returns Segment coefficients + */ + Vector6d getCoefficients(); + + /*! + * \returns End time of the segment + */ + const double getEndTime(); + + /*! + * \returns Start time of the segment + */ + const double getStartTime(); + + /*! + * \brief interpolate at a given time stamp. + * + * \param stamp Time stamp to do the interpolation, make sure it is within the boundaries. + * \param pos Variable to store calculated position + * \param vel Variable to store calculated velocity + * \param acc Variable to store calculated acceleration + */ + void interpolate(const double& stamp, double& pos, double& vel, double& acc); + +private: + /*! + * \brief Calculates linear coefficients for the segment. + * + * \param start Start state + * \param end End state + * \param x duration of the segment + */ + void linearCoefficients(const VectorXd& start, const VectorXd& end, const double& x); + + /*! + * \brief Calculates cubic coefficients for the segment. + * + * \param start Start state + * \param end End state + * \param x duration of the segment + */ + void cubicCoefficients(const VectorXd& start, const VectorXd& end, const double& x); + + /*! + * \brief Calculates quintic coefficients for the segment. + * + * \param start Start state + * \param end End state + * \param x duration of the segment + */ + void quinticCoefficients(const VectorXd& start, const VectorXd& end, const double& x); + + // Coefficients + Vector6d coefficients_; + + // Segment start time, end time and duration for a segment + double duration_, start_time_; +}; + +} // namespace ur_controller +} // namespace isaac diff --git a/ur_controller/JointTrajectory.cpp b/ur_controller/JointTrajectory.cpp new file mode 100644 index 0000000..9e56025 --- /dev/null +++ b/ur_controller/JointTrajectory.cpp @@ -0,0 +1,91 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "JointTrajectory.hpp" + +namespace isaac +{ +namespace ur_controller +{ +JointTrajectory::JointTrajectory() = default; + +void JointTrajectory::initTrajectory(const Timeseries& trajectory) +{ + ASSERT(trajectory.empty() == false, "The trajectory shouldn't be empty"); + joint_trajectory_ = trajectory; + + Timeseries::Entry waypoint; + Timeseries::Entry next_waypoint; + // Create a vector of segments + segments_.clear(); + for (unsigned int j = 0; j < trajectory.size() - 1; ++j) + { + waypoint = trajectory.at(j); + next_waypoint = trajectory.at(j + 1); + JointSegment segment(waypoint, next_waypoint); + segments_.push_back(segment); + } + // Last segment is the final position of the trajectory, but with a duration of 0. + waypoint = joint_trajectory_.youngest(); + next_waypoint = joint_trajectory_.youngest(); + JointSegment segment(waypoint, next_waypoint); + segments_.push_back(segment); +} + +void JointTrajectory::interpolate(const double& stamp, double& pos, double& vel, double& acc) +{ + // If we are before trajectory start time or after trajectory end time return position + if (stamp < joint_trajectory_.oldest().stamp) + { + pos = joint_trajectory_.oldest().state[0]; + vel = 0.0; + acc = 0.0; + return; + } + else if (stamp > joint_trajectory_.youngest().stamp) + { + pos = joint_trajectory_.youngest().state[0]; + vel = 0.0; + acc = 0.0; + return; + } + + // Find current segmet and interpolate + ssize_t index = joint_trajectory_.lower_index(stamp); + segments_[index].interpolate(stamp, pos, vel, acc); +} + +const double JointTrajectory::endTime() +{ + return joint_trajectory_.youngest().stamp; +} + +} // namespace ur_controller +} // namespace isaac \ No newline at end of file diff --git a/ur_controller/JointTrajectory.hpp b/ur_controller/JointTrajectory.hpp new file mode 100644 index 0000000..ec7a559 --- /dev/null +++ b/ur_controller/JointTrajectory.hpp @@ -0,0 +1,86 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include "engine/gems/algorithm/timeseries.hpp" +#include "JointSegment.hpp" + +namespace isaac +{ +namespace ur_controller +{ +/*! + * \brief This JointTrajectory Class is used store a trajectory for one joint. + * The trajectory consist of waypoints that consist of time, position, velocity and acceleration. + * It uses JointSegment to calculate the segments between all the waypoints and interpolate between + * two waypoints. + */ + +class JointTrajectory +{ +public: + /*! + * \brief Construct a new Joint Trajectory object + */ + JointTrajectory(); + + /*! + * \brief Storing the new trajectory and creating segment for each waypoint in the trajectory. + * + * \param trajectory trajectory for the joint to follow. + */ + void initTrajectory(const Timeseries& trajectory); + + /*! + * \brief Calculates current position, velocity and acceleration, based on the time_stamp. + * + * \param stamp Current time to interpolate. + * \param pos Variable to store position. + * \param vel Variable to store velocity. + * \param acc Variable to store acceleration. + */ + void interpolate(const double& stamp, double& pos, double& vel, double& acc); + + /*! + * \returns end time of trajectory. + */ + const double endTime(); + +private: + // Trajectory of waypoints for a joint + Timeseries joint_trajectory_; + + // List of segments between the waypoints + std::vector segments_; +}; + +} // namespace ur_controller +} // namespace isaac \ No newline at end of file diff --git a/ur_controller/Pid.hpp b/ur_controller/Pid.hpp new file mode 100644 index 0000000..e52fce8 --- /dev/null +++ b/ur_controller/Pid.hpp @@ -0,0 +1,229 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include +#include "engine/core/math/utils.hpp" +#include "engine/gems/serialization/json_formatter.hpp" + +namespace isaac +{ +namespace ur_controller +{ +/*! + * \brief Pid class used to calculate the control output. This class is used in the + * ScaledMultiJointController to calculate joint speeds. + */ + +template +class Pid +{ +public: + /*! + * \brief Construct a new Pid object + */ + Pid() : last_error_(static_cast(0.0)), i_error_(static_cast(0.0)) + { + setGains(static_cast(0.0), static_cast(0.0), static_cast(0.0), + std::numeric_limits::max(), std::numeric_limits::min()); + } + + /*! + * \brief Initialize the PID controller with gains. + * + * \param p P gain + * \param i I gain + * \param d D gain + * \param i_max Maximum integral error + * \param i_min Minimum integral error + */ + void initPid(const Scalar& p, const Scalar& i, const Scalar& d, const Scalar& i_max, const Scalar& i_min) + { + setGains(p, i, d, i_max, i_min); + reset(); + } + + /*! + * \brief Initialize the PID controller with gains. + * + * \param json Json object storing the gains. + * + * \returns true on succes + */ + bool init(const nlohmann::json& json) + { + const auto p = serialization::TryGetFromMap(json, "p"); + if (p == std::nullopt) + { + return false; + } + Scalar i = serialization::GetFromMapOrDefault(json, "i", 0.0); + Scalar d = serialization::GetFromMapOrDefault(json, "d", 0.0); + Scalar i_clamp = serialization::GetFromMapOrDefault(json, "i_clamp", std::numeric_limits::max()); + Scalar i_max = std::abs(i_clamp); + Scalar i_min = -std::abs(i_clamp); + + setGains(*p, i, d, i_max, i_min); + reset(); + + return true; + } + + /*! + * \brief Get the gains + * + * \param p P gain + * \param i I gain + * \param d D gain + * \param i_max Integral max error + * \param i_min Integral minimum error + */ + void getGains(Scalar& p, Scalar& i, Scalar& d, Scalar& i_max, Scalar& i_min) + { + p = p_gain_; + i = i_gain_; + d = d_gain_; + i_max = i_max_; + i_min = i_min_; + } + + /*! + * \brief Set the gains + * + * \param p P gain + * \param i I gain + * \param d D gain + * \param i_max Integral max error + * \param i_min Integral minimum error + */ + void setGains(const Scalar& p, const Scalar& i, const Scalar& d, const Scalar& i_max, const Scalar& i_min) + { + p_gain_ = p; + i_gain_ = i; + d_gain_ = d; + i_max_ = i_max; + i_min_ = i_min; + } + + /*! + * \brief Get the errors + * + * \param last_error Lastest error + * \param i_error Integral error + */ + void getErrors(Scalar& last_error, Scalar& i_error) + { + i_error = i_error_; + last_error = last_error_; + } + + /*! + * \brief Reset errors + */ + void reset() + { + last_error_ = 0.0; + i_error_ = 0.0; + } + + /*! + * \brief Calculates control output. + * This functions calculates the derivative error, before calculating control output. + * + * \param error Error between target and actual value. + * \param dt Time since last control output was calculated. + * + * \returns control output + */ + Scalar calculate(Scalar error, Scalar dt) + { + if (dt <= 0.0) + { + return 0.0; + } + + Scalar error_dot = (error - last_error_) / dt; + last_error_ = error; + return calculate(error, error_dot, dt); + } + + /*! + * \brief Calculates control output. + * + * \param error Error between target and actual value. + * \param error_dot Derivative error. + * \param dt Time since last control output was calculated. + * + * \returns control output + */ + Scalar calculate(Scalar error, Scalar error_dot, Scalar dt) + { + if (dt <= 0.0) + { + return 0.0; + } + + Scalar p_term, i_term, d_term, cmd; + + // Calculate p term + p_term = p_gain_ * error; + + // Calculate I term + i_error_ += error * dt; + i_term = i_error_ * i_gain_; + + // Clamp I term + i_term = Clamp(i_term, i_min_, i_max_); + + // Calculate derivative term + d_term = d_gain_ * error_dot; + + cmd = p_term + i_term + d_term; + + last_error_ = error; + + return cmd; + } + +private: + Scalar last_error_; + Scalar i_error_; + + // Gains + Scalar p_gain_; + Scalar i_gain_; + Scalar d_gain_; + Scalar i_max_; + Scalar i_min_; +}; + +} // namespace ur_controller +} // namespace isaac \ No newline at end of file diff --git a/ur_controller/README.md b/ur_controller/README.md new file mode 100644 index 0000000..158b723 --- /dev/null +++ b/ur_controller/README.md @@ -0,0 +1,111 @@ +# UR controller + +This package contains a controller, that is special to the UR family. This controller +can handle the the actual speedscaling of the robot, by slowing down trajectory execution. + +## Isaac Api + +This folder contains a controller, not being available in Isaac SDK. The controller +is created to offer a controller that can handle the actual speed scaling of a +UR robot. This controller is meant to be used instead of the [MultiJointcontroller](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-controller-multijointcontroller) +provided by nvidia. + +This folder contains 1 codelet that can be used in applications: + +- **ScaledMultiJointController** This codelets interpolates a trajectory received +from the planner to determine the current command to send. This codelet can output +either a joint position or speed command. It uses the actual speed scaling reported +by UniversalRobots to reduce progress in the trajectory. The component is further +documented in a [standalone document](../ur_robot_driver/doc/component_api.md#ScaledMultiJointController) + +The codelet uses functionality from other classes in this folder, these classes +can be seen below: + +- **Pid** class used to calculate the control output. This class is used in the +ScaledMultiJointController to calculate joint speeds. + +- **JointTrajectory** class is used to store a trajectory of waypoints for one joint. +The waypoints consist of time, position, velocity and acceleration. This Class uses +JointSegment to interpolate between two waypoints. + +- **JointSegment** class calculates a segment between two waypoints. The segment +is a function describing joint position as a function of time. The function can +be linear, cubic or quintic. + +### Subgraph + +This controller comes with a [subgraph](apps/scaled_multi_joint_ur_control.subgraph.json) +that integrates the [MultiJointLqrPlanner](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-planner-multijointplanner), +[ScaledMultiJointController](../ur_robot_driver/doc/component_api.md#ScaledMultiJointController) +and [KinematicTree](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-map-kinematictree) +components. The subgraph provides the following interface edges: + +- **joint_state(input)** "subgraph/interface/joint_state" + +- **joint_target(input)** "subgraph/interface/joint_target" + +- **joint_command(output)** "subgraph/interface/command" + +- **trajectory_executed_succesfully(output)** "subgraph/interface/trajectory_executed_succesfully" + +## Controller description + +This controller works similar to [MultiJointcontroller](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-controller-multijointcontroller) +provided by nvidia. It receives a plan that contains a trajectory for each joint. +It interpolates the received plan and publish the command as either joint speeds +or joint position. + +However, it is extended to handle the robot's execution speed specifically. +Because MultiJointController would interpolate the trajectory with the configured +time constraints (ie: always assume maximum velocity and acceleration configured +in the application), this could lead to significant path deviation due to multiple +reasons: + +- The speed slider on the robot might not be at 100%, so motion commands sent from +ROS would effectively get scaled down resulting in a slower execution. + +- The robot could scale down motions based on configured safety limits resulting +in a slower motion than expected and therefore not reaching the desired target in +a control cycle. + +- Motions might not be executed at all, e.g. because the robot is E-stopped or in +a protective stop + +- Motion commands sent to the robot might not be interpreted, e.g. because there +is no `external_control` program node running on the robot controller. + +- The program interpreting motion commands could be paused. + +The following plot illustrates the problem: + +![Trajectory execution with default multiJointController](doc/traj_without_speed_scaling.png +"Trajectory execution with default multiJointController") + +This graph shows a trajectory with one joint being moved to a target point. The +joint speed is limited to 40% on the teach pendant, speed scaling activates and +limits the joint speed. As a result, the target trajectory (blue) doesn't get executed +by the robot, instead the red trajectory is executed. The green line is the error +between the blue and red line in each control cycle. We can also see that the robot +ends up oscillating around the target joint position. + +All of the cases mentioned above are addressed by the ScaledMultiJointController +versions. Trajectory execution can be transparently scaled down using the speed +slider on the teach pendant without leading to additional path deviations. Pausing +the program or hitting the E-stop effectively leads to speed_scaling being 0 meaning +the trajectory will not be continued until the program is continued. This way, trajectory +executions can be explicitly paused and continued. + +With the ScaledMultiJointController the example motion shown in the previous diagram +becomes: + +![Trajectory execution with scaled_joint_trajectory_controller](doc/traj_with_speed_scaling.png +"Trajectory execution with scaled_joint_trajectory_controller") + +The deviation between trajectory interpolation on the Isaac side and actual robot +execution stays minimal and the robot reaches the setpoint instead of oscillating +around it. + +Under the hood this is implemented by proceeding the trajectory not by a full time +step but only by the fraction determined by the current speed scaling. If speed +scaling is currently at 50% then interpolation of the current control cycle will +start half a time step after the beginning of the previous control cycle. diff --git a/ur_controller/ScaledMultiJointController.cpp b/ur_controller/ScaledMultiJointController.cpp new file mode 100644 index 0000000..d864e98 --- /dev/null +++ b/ur_controller/ScaledMultiJointController.cpp @@ -0,0 +1,409 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "ScaledMultiJointController.hpp" +#include "packages/map/KinematicTree.hpp" +#include "engine/gems/serialization/json.hpp" +#include "engine/gems/serialization/json_formatter.hpp" + +namespace isaac +{ +namespace ur_controller +{ +void ScaledMultiJointController::start() +{ + // Try to get the map::KinematicTree component + const auto maybe_kinematic_tree_node = try_get_kinematic_tree(); + if (!maybe_kinematic_tree_node) + { + reportFailure("KinematicTree node is not specified."); + return; + } + const auto maybe_kinematic_tree_component = + node()->app()->getNodeComponentOrNull(*maybe_kinematic_tree_node); + if (!maybe_kinematic_tree_component) + { + reportFailure("Node %s does not contain KinematicTree component.", maybe_kinematic_tree_node->c_str()); + return; + } + + // Get the kinematic_tree object + const kinematic_tree::KinematicTree& model = maybe_kinematic_tree_component->model(); + const auto& links = model.getActiveLinks(); + joint_names_.clear(); + for (const auto* link : links) + { + joint_names_.push_back(link->name); + } + + // Update states according to number of joints + number_of_joints_ = joint_names_.size(); + controllerState_ = State(number_of_joints_); + robotState_ = State(number_of_joints_); + errorState_ = State(number_of_joints_); + cur_traj_.resize(number_of_joints_); + successful_joints_.resize(number_of_joints_); + plan_parser_.resize(number_of_joints_); + pid_.resize(number_of_joints_); + ff_term_.resize(number_of_joints_); + + control_mode_ = get_control_mode(); + interpolation_scheme_ = get_interpolation_scheme(); + succesful_arm_parse_ = false; + succesful_plan_parse_ = false; + + // Init parsers and schemas. + initPlanParser(); + initStateParser(); + initCommandSchema(); + + // Setup tick + tickPeriodically(); +} + +void ScaledMultiJointController::tick() +{ + if (rx_plan().available()) + { + const int64_t time = rx_plan().acqtime(); + bool isFirstMessage = !plan_time_; + bool unseenMessage = time > *plan_time_; + if (isFirstMessage || unseenMessage) + { + plan_time_ = time; + succesful_plan_parse_ = parsePlan(); + + // Update time data + period_ = 0; + controller_uptime_ = getTickTime(); + tick_time_ = getTickTime(); + } + } + if (rx_current_arm_state().available()) + { + const int64_t time = rx_current_arm_state().acqtime(); + bool isFirstMessage = !arm_time_; + bool unseenMessage = time > *arm_time_; + if (isFirstMessage || unseenMessage) + { + arm_time_ = time; + succesful_arm_parse_ = parseJointStates(); + // initialize joints + if (isFirstMessage && succesful_arm_parse_) + { + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + controllerState_.position[i] = robotState_.position[i]; + controllerState_.velocity[i] = robotState_.velocity[i]; + controllerState_.acceleration[i] = 0.0; + } + } + } + } + if (succesful_plan_parse_ && succesful_arm_parse_) + { + calculateCommand(); + publishCommand(); + } +} + +void ScaledMultiJointController::initPlanParser() +{ + switch (interpolation_scheme_) + { + case linear_interpolation: + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); + plan_parser_[i].requestSchema(std::move(quantities)); + } + return; + case cubic_interpolation: + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kSpeed)); + plan_parser_[i].requestSchema(std::move(quantities)); + } + return; + case quintic_interpolation: + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kSpeed)); + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kAcceleration)); + plan_parser_[i].requestSchema(std::move(quantities)); + } + return; + default: + LOG_WARNING("interpolation shceme not recognized"); + return; + } +} + +void ScaledMultiJointController::initStateParser() +{ + position_state_parser_.requestSchema(composite::Schema(joint_names_, composite::Measure::kPosition)); + velocity_state_parser_.requestSchema(composite::Schema(joint_names_, composite::Measure::kSpeed)); + + std::vector misc_names; + misc_names.push_back(composite::Quantity::Scalar("speed_fraction", composite::Measure::kNone)); + speed_fraction_parser_.requestSchema(composite::Schema(std::move(misc_names))); +} + +bool ScaledMultiJointController::parsePlan() +{ + // Reset plan parser if interpolation scheme changes. + if (interpolation_scheme_ != get_interpolation_scheme()) + { + interpolation_scheme_ = get_interpolation_scheme(); + initPlanParser(); + } + std::vector > parsed_traj(6); + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + if (!plan_parser_[i].parse(rx_plan().getProto(), rx_plan().buffers(), "time", parsed_traj[i])) + { + LOG_WARNING("failed to parse plan for joint %s", joint_names_[i].c_str()); + return false; + } + } + // Initilaize trajectory + initTrajectory(parsed_traj); + return true; +} + +bool ScaledMultiJointController::parseJointStates() +{ + VectorXd current_position(number_of_joints_); + if (!position_state_parser_.parse(rx_current_arm_state().getProto(), rx_current_arm_state().buffers(), + current_position)) + { + LOG_WARNING("Failed to parse joint position from driver"); + return false; + } + VectorXd current_velocity(number_of_joints_); + if (!velocity_state_parser_.parse(rx_current_arm_state().getProto(), rx_current_arm_state().buffers(), + current_velocity)) + { + LOG_WARNING("Failed to parse joint velocity from driver"); + return false; + } + VectorXd speed_fraction(1); + if (!speed_fraction_parser_.parse(rx_current_arm_state().getProto(), rx_current_arm_state().buffers(), + speed_fraction)) + { + LOG_WARNING("Failed to parse speed scaling from driver"); + return false; + } + robotState_.position = current_position; + robotState_.velocity = current_velocity; + speed_fraction_ = speed_fraction[0]; + return true; +} + +void ScaledMultiJointController::initCommandSchema() +{ + std::vector quantities; + if (control_mode_ == kJointPosition) + { + for (unsigned int i = 0; i < number_of_joints_; i++) + { + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); + } + } + else if (control_mode_ == kJointSpeed) + { + for (unsigned int i = 0; i < number_of_joints_; i++) + { + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kSpeed)); + } + } + else + { + LOG_WARNING("invalid control mode"); + return; + } + command_schema_ = composite::Schema(std::move(quantities)); +} + +void ScaledMultiJointController::publishCommand() +{ + // Reset command schema if control mode changes + ArmControlMode mode = get_control_mode(); + if (control_mode_ != mode) + { + control_mode_ = mode; + initCommandSchema(); + } + + if (control_mode_ == kInvalid) + { + LOG_WARNING("invalid control mode"); + return; + } + auto proto_builder = tx_joint_command().initProto(); + composite::WriteSchema(command_schema_, proto_builder); + + // Allocate tensor1d to store state data + Tensor1d state_data(number_of_joints_); + + if (control_mode_ == kJointPosition) + { + for (unsigned int i = 0; i < number_of_joints_; i++) + { + state_data(i) = controllerState_.position[i]; + } + } + else if (control_mode_ == kJointSpeed) + { + for (unsigned int i = 0; i < number_of_joints_; i++) + { + state_data(i) = controllerState_.velocity[i]; + } + } + ToProto(std::move(state_data), proto_builder.initValues(), tx_joint_command().buffers()); + tx_joint_command().publish(); +} + +void ScaledMultiJointController::publishTrajectoryStatus(bool trajectory_status) +{ + auto proto = tx_trajectory_executed_succesfully().initProto(); + proto.setFlag(trajectory_status); + tx_trajectory_executed_succesfully().publish(); +} + +void ScaledMultiJointController::calculateCommand() +{ + // Update time according to current speed scale + period_ = (getTickTime() - tick_time_) * speed_fraction_; + controller_uptime_ = controller_uptime_ + period_; + tick_time_ = getTickTime(); + + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + // Interpolate current trajectory + cur_traj_[i].interpolate(controller_uptime_, controllerState_.position[i], controllerState_.velocity[i], + controllerState_.acceleration[i]); + + errorState_.position[i] = DeltaAngle(controllerState_.position[i], robotState_.position[i]); + errorState_.velocity[i] = controllerState_.velocity[i] - robotState_.velocity[i]; + errorState_.acceleration[i] = 0.0; + + // Check tolerance, if there is an active goal + if (active_goal_) + { + const double end_time = cur_traj_[i].endTime(); + // Done executing last segment in the trajectory + if (controller_uptime_ > end_time) + { + const bool inside_goal_tolerance = insideTolerance(errorState_.position[i]); + if (inside_goal_tolerance) + { + successful_joints_[i] = 1; + } + else if (controller_uptime_ < end_time + get_goal_time()) + { + // Still have time to reach target + } + else + { + LOG_ERROR("Tolerance failed for joint: %s", joint_names_[i].c_str()); + active_goal_ = false; + publishTrajectoryStatus(false); + } + } + } + if (control_mode_ == kJointSpeed && active_pid_) + { + double target = pid_[i].calculate(errorState_.position[i], errorState_.velocity[i], period_); + controllerState_.velocity[i] = controllerState_.velocity[i] * ff_term_[i] + target; + } + // Show data + show(joint_names_[i] + " position error", errorState_.position[i]); + show(joint_names_[i] + " velocity error", errorState_.velocity[i]); + show(joint_names_[i] + " position", controllerState_.position[i]); + show(joint_names_[i] + " velocity", controllerState_.velocity[i]); + show(joint_names_[i] + " acceleration", controllerState_.acceleration[i]); + } + if (active_goal_) + { + unsigned int count = + std::accumulate(successful_joints_.begin(), successful_joints_.end(), static_cast(0)); + if (count == number_of_joints_) + { + active_goal_ = false; + std::fill(successful_joints_.begin(), successful_joints_.end(), false); + publishTrajectoryStatus(true); + } + } +} + +bool ScaledMultiJointController::insideTolerance(const double& error_pos) +{ + // The check is only made if the tolerance is above 0 + const double tolerance = get_tolerance(); + return !(tolerance > 0.0 && std::abs(error_pos) > tolerance); +} + +void ScaledMultiJointController::initTrajectory(std::vector > trajectory) +{ + // Get PID gains + nlohmann::json gains = get_gains(); + + active_pid_ = true; + for (unsigned int i = 0; i < number_of_joints_; ++i) + { + // Initialize trajectory + cur_traj_[i].initTrajectory(trajectory[i]); + + const auto pid_joint = serialization::TryGetFromMap(gains, joint_names_[i]); + if (pid_joint) + { + ff_term_[i] = serialization::GetFromMapOrDefault(*pid_joint, "velocity_ff", 1.0); + if (!pid_[i].init(*pid_joint)) + { + active_pid_ = false; + } + } + else + { + active_pid_ = false; + } + } + active_goal_ = true; + std::fill(successful_joints_.begin(), successful_joints_.end(), false); +} + +} // namespace ur_controller +} // namespace isaac \ No newline at end of file diff --git a/ur_controller/ScaledMultiJointController.hpp b/ur_controller/ScaledMultiJointController.hpp new file mode 100644 index 0000000..3eb3986 --- /dev/null +++ b/ur_controller/ScaledMultiJointController.hpp @@ -0,0 +1,290 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once +#include +#include +#include + +#include "engine/alice/alice_codelet.hpp" +#include "messages/composite.capnp.h" +#include "messages/basic.capnp.h" +#include "packages/composite/gems/parser.hpp" +#include "engine/gems/algorithm/timeseries.hpp" +#include "JointTrajectory.hpp" +#include "Pid.hpp" + +namespace isaac +{ +namespace ur_controller +{ +/*! + * \brief Possible control modes for arm. + */ +enum ArmControlMode +{ + kJointPosition, // Control joints position + kJointSpeed, // Control joints speed + kInvalid = -1 // Invalid control mode, returned from an invalid string in JSON +}; + +/*! + * \brief Possible interpolation schemes. + */ +enum InterpolationScheme +{ + linear_interpolation, // line ax+b + cubic_interpolation, // cubic polynomium - ax^3+bx^2+cx+d + quintic_interpolation, // quintic polynomium - ax^5+bx^4+cx^3+dx^2+ex+f + invalid_interpolation = -1 // Invalid interpolation mode, returned from an invalid string in JSON +}; + +/*! + * \brief Mapping between each ArmControlMode type and an identifying string. + */ +NLOHMANN_JSON_SERIALIZE_ENUM(ArmControlMode, { { kInvalid, nullptr }, + { kJointPosition, "joint position" }, + { kJointSpeed, "joint speed" } }); + +/*! + * \brief Mapping between each Interpolation scheme and an identifying string. + */ +NLOHMANN_JSON_SERIALIZE_ENUM(InterpolationScheme, { { invalid_interpolation, nullptr }, + { linear_interpolation, "linear interpolation" }, + { cubic_interpolation, "cubic interpolation" }, + { quintic_interpolation, "quintic interpolation" } }); + +/*! + * \brief This ScaledMultiJointController class receives a trajectory and calculates the actual joint command + * to publish each iteration. It slows down trajectory execution according to the actual speedscaling of the robot. + */ + +class ScaledMultiJointController : public isaac::alice::Codelet +{ +public: + /*! + * \brief Handles the setup functionality of this class. This includes collecting the kinematic tree node, + * setting up memory according to number of joints and setting up message parsing parameters. + */ + void start() override; + + /*! + * \brief This functions is run cyclic with a fixed frequency. It checks whether a new trajectory message is available + * and whether a new current arm state message is availabe and it calculates and publishes the actual joint command. + */ + void tick() override; + + /*! + * \brief Receives current state of the robot arm, this also includes the actual speedscaling. + */ + ISAAC_PROTO_RX(CompositeProto, current_arm_state); + + /*! + * \brief Receives a plan that contains a trajectory for each joint. If linear interpolation is configured + * the trajectory must contain joint position. If cubic interpolation is configured the trajectory must contain joint + * position and joint speeds. If quintic interpolation is configured the trajectory must contain joint positions, + * joint speeds and joint accelerations. + */ + ISAAC_PROTO_RX(CompositeProto, plan); + + /*! + * \brief Publishes the actual joint command as joint position or joint speeds based upon control_mode. + */ + ISAAC_PROTO_TX(CompositeProto, joint_command); + + /*! + * \brief Publishes the status after a trajectory has been executed. The flag will be true if the joints are within + * the tolerance after trajectory execution and false otherwise. + */ + ISAAC_PROTO_TX(BooleanProto, trajectory_executed_succesfully); + + /*! + * \brief Name of the node containing the map:KinematicTree component. This is used to obtain the names + * of the joints for parsing/creating composite message. + */ + ISAAC_PARAM(std::string, kinematic_tree); + + /*! + * \brief Set the interpolation scheme used to calculate joint commands. + */ + ISAAC_PARAM(InterpolationScheme, interpolation_scheme, quintic_interpolation); + + /*! + * \brief Set the control mode. + */ + ISAAC_PARAM(ArmControlMode, control_mode, kJointPosition); + + /*! + * \brief Time after the last waypoint in the trajectory is published and until the joints should be within the + * tolerance. + */ + ISAAC_PARAM(double, goal_time, 0.0); + + /*! + * \brief Tolerance for arrival. The trajectory is completed when the error for all joints is below this tolerance + * after the last waypoint in the trajectory is published. If the tolerance is 0.0, no check will be made. + */ + ISAAC_PARAM(double, tolerance, 0.0); + + /*! + * \brief PID gains for each joint, used when control mode is kJointSpeed. + */ + ISAAC_PARAM(nlohmann::json, gains, (nlohmann::json{ { "gains", {} } })); + +private: + /*! + * \brief A state storing position, velocity and acceleration for each joint in the robot. + * + * \param size number of joints in the robot. + */ + struct State + { + State() + { + } + + State(const unsigned int size) : position(size), velocity(size), acceleration(size) + { + } + VectorXd position; + VectorXd velocity; + VectorXd acceleration; + }; + + /*! + * \brief Request a schema for parsing arm state and trajectory, trajectory is parsed + * based on interpolation scheme. + */ + void initPlanParser(); + void initStateParser(); + + /*! + * \brief Parse received trajectory and received joint states. + * + * \returns true on succesful parse + */ + bool parsePlan(); + bool parseJointStates(); + + /*! + * \brief Generate composite schema for publishing current command + */ + void initCommandSchema(); + + /*! + * \brief Publish current command and trajectory status. + * + * \param trajectory_status the trajectory status after execution. + */ + void publishCommand(); + void publishTrajectoryStatus(bool trajectory_status); + + /*! + * \brief Calculate the current joint command. + */ + void calculateCommand(); + + /*! + * \brief Test that we are inside the tolerance. + * + * \param error_pos Error between robot position and controller position. + * + * \returns true if inside tolerance. + */ + bool insideTolerance(const double& error_pos); + + /*! + * \brief Initialize a new trajectory for each joint in the robot. + * + * \param trajectory Recevied trajectory. + */ + void initTrajectory(std::vector> trajectory); + + // Current control period, the period is scaled according to the actual speedscaling. + double period_; + + // Controller uptime, updated based on period. + double controller_uptime_; + + // Current time of the tick + double tick_time_; + + // Current speed fraction + double speed_fraction_; + + // Current trajectory object for each joint + std::vector cur_traj_; + + // Controller, robot and error state. + State controllerState_, robotState_, errorState_; + + // Parsers for arm state. + composite::Parser position_state_parser_; + composite::Parser velocity_state_parser_; + composite::Parser speed_fraction_parser_; + + // Parser for trajectory for each joint. + std::vector plan_parser_; + + // Bools feflecting if parsing message was succesful + bool succesful_plan_parse_; + bool succesful_arm_parse_; + + // Cache list of joint names used in the kinematic tree + std::vector joint_names_; + + // Number of joints + unsigned int number_of_joints_; + + // Acquire time for most recently received plan and arm state + std::optional plan_time_; + std::optional arm_time_; + + // Cache composite schema for current joint command + composite::Schema command_schema_; + + // Cache current control_mode and current interpolation scheme + ArmControlMode control_mode_; + InterpolationScheme interpolation_scheme_; + + // Used to store information about, when target position is reached + std::vector successful_joints_; + bool active_goal_; + + // Pid controller + std::vector> pid_; + std::vector ff_term_; + bool active_pid_; +}; + +} // namespace ur_controller +} // namespace isaac + +ISAAC_ALICE_REGISTER_CODELET(isaac::ur_controller::ScaledMultiJointController) \ No newline at end of file diff --git a/ur_controller/apps/BUILD b/ur_controller/apps/BUILD new file mode 100644 index 0000000..88a60c6 --- /dev/null +++ b/ur_controller/apps/BUILD @@ -0,0 +1,13 @@ +load("//bzl:module.bzl", "isaac_subgraph") + +isaac_subgraph( + name = "scaled_multi_joint_ur_control_subgraph", + modules = [ + "map", + "planner", + "lqr", + "//packages/universal_robots/ur_controller:ur_controller", + ], + subgraph = "scaled_multi_joint_ur_control.subgraph.json", + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/ur_controller/apps/scaled_multi_joint_ur_control.subgraph.json b/ur_controller/apps/scaled_multi_joint_ur_control.subgraph.json new file mode 100644 index 0000000..c700730 --- /dev/null +++ b/ur_controller/apps/scaled_multi_joint_ur_control.subgraph.json @@ -0,0 +1,110 @@ +{ + "modules": [ + "map", + "lqr", + "planner", + "//packages/universal_robots/ur_controller:ur_controller" + ], + "graph": { + "nodes": [ + { + "name": "subgraph", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "interface", + "type": "isaac::alice::Subgraph" + } + ] + }, + { + "start_order": -100, + "name": "kinematic_tree", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "KinematicTree", + "type": "isaac::map::KinematicTree" + } + ] + }, + { + "name": "local_plan", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "MultiJointLqrPlanner", + "type": "isaac::lqr::MultiJointLqrPlanner" + }, + { + "name": "MultiJointPlanner", + "type": "isaac::planner::MultiJointPlanner" + } + ] + }, + { + "name": "controller", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "ScaledMultiJointController", + "type": "isaac::ur_controller::ScaledMultiJointController" + } + ] + } + ], + "edges": [ + { + "source": "subgraph/interface/joint_state", + "target": "local_plan/MultiJointPlanner/starting_state" + }, + { + "source": "subgraph/interface/joint_target", + "target": "local_plan/MultiJointPlanner/target_state" + }, + { + "source": "local_plan/MultiJointPlanner/plan", + "target": "controller/ScaledMultiJointController/plan" + }, + { + "source": "controller/ScaledMultiJointController/joint_command", + "target": "subgraph/interface/joint_command" + }, + { + "source": "subgraph/interface/joint_state", + "target": "controller/ScaledMultiJointController/current_arm_state" + }, + { + "source": "subgraph/interface/trajectory_executed_succesfully", + "target": "controller/ScaledMultiJointController/trajectory_executed_succesfully" + } + ] + }, + "config": { + "local_plan": { + "MultiJointPlanner": { + "tick_period": "10Hz", + "kinematic_tree_node_name": "$(fullname kinematic_tree)", + "multi_joint_planner_node_name": "$(fullname local_plan)" + } + }, + "controller": { + "ScaledMultiJointController": { + "tick_period": "500Hz", + "kinematic_tree": "$(fullname kinematic_tree)" + } + } + } +} \ No newline at end of file diff --git a/ur_controller/doc/traj_with_speed_scaling.png b/ur_controller/doc/traj_with_speed_scaling.png new file mode 100644 index 0000000000000000000000000000000000000000..2a3d33bd591a8f42324bf61f58e16cfb9a1c353e GIT binary patch literal 27194 zcmd>m1y@yJ7v`lzMZgP4mlqIGx*HV`R3sHpkPej&=~AQ-1eH!H5eY@QyGv9+y1Tn) zAHJFSX3d&^Fs#K=IQN|M#*XKC_I?RaR+J;WNPQ87LJ{7Rmr+Hbu)RG!3H-BNk=wNJX_rl7Ok(ZN~Q-GcExxKx$C>Pg%Kfq~aYsw|xbv*@zVnp4Ox&6o~ zZfV%jiR{lw)B0|@-=k_}?5h_l97|NC12oXeQ<$Xd({J#wWZB*vaY!@-) zYowHcuX^L+Cv>-v|Jg=fyoH7@iWF>RL3;)N-?t*uQf z7|YR{t@+*H=kuO7(`}JjbX;B0f)-CJ4{NKe$FaYE|Nc#@sB_`^{;xN91X1G7KmPE@ zOgRb~27ecQEAK%;K_Sg+C>eAz~Z$Jg>GZMP4nCUA=m>zP|o44NdHe z;jJzEU%kES>+9bcUz~IoT4*^e|7!?ilH)C)F_ed=^!AcEIy#!w1{5wm6gBhd}?!Kc|`T1PM&D}jyBbPpif~#}m=y8^M zPwG8Vkq=HQ$ZtHkju_O-)K^-%D2o1h&)nb6zD3?r+Xg z30pJj>+3tYx~gTWvNVP=bp636$dSZfYt>(SMULh>dtk%3rpkC9a=p?#~I z!Sg7LtLo^Nb8)%z=1gCQ(=_e(^~ol_7r&Tm>*`>fEH`chJ}YxDesUVbRhjgnH+^q^ zA5BZ!jzcV7y)sM||57oXtVjFSWe28*b8M@aN!Lh!%$s{fwhetqeG+<(2fWbL;$$BLcHh|AzNps1; zwQwg({`TxY&mVz9Cim{$ixYiy(eToR3l|jPML&J~NJj6z)uXWZFq+rraJ4Ei=UG{J zL_}k)4}tSsvftj+2c_q|>4Ye$lRYMQdzwi{OfanoiItTV5v_1_<2#!8T*IQllGBsJ zfjoU2CGmCK$6p`m&vwQu#PA2WAMSjI)zNCT3LZZ>Ts2+(SFpA4C+J^+S-$P`{d2_h z?Xah{srNou9#9`2?q*nz*MiYoPc@^jDJ3XWc^o^P9`9m-v+=^!rqR*F@j5>o<#MO> z*vb{K17XJ%T6o3uue1jWF!~4%tsi!?inE&*87%X$Nn(2&x06T%$Fzl5{dlb*oNJT8M)Dd@YDLxTxl3`N_GDXDXTzAYN z{@ey1{Gy)y?^RLQa95VyY-fFA|Ue6wrgb@%SypO{VbbTHZ2 z-K|c66z(mu85dw zft@}4ZqU#^-*jr>ZN@KaZ;BL1ubq^;BzStKV>+7SW zP900#4;^r#Mk-uQpIUV%-9E>y>$dK5HX@YC@xgXy;oG;k5Y#Nr5z#u;1rHpT@2m`) zq4-`c{8m_$INs`Q9336q-`s;aQ&qPoN=fy)+*JS8{L6!7H}J|$%c%80L5qJz{}MH{ z_uXdOqbJQ5M=Hv&+HdBTPne6j?tFtVCLkEw!LD80Jy2=dmB60Z_C+NnI59DCpvX!$ z-GY!#^mlPtSuEI?@y&es+v(EPn4+FotIC$IkFzujUS3(PJmlnf`ZLLKb%gy{DSxkv zr=-%t(m*~l3ro+>7rhF8jNabfSbK9Rp*gPo3*N+%Nnl2gaG89FuIJ63J^sQzPjug*LP4@JAFYh1mvB)|l}FFI2$=nyS}9v~$iWYBFLT~BQH&E_FXDaH z^~plw^k_5sAGpr>Y6yHWnH4YpeC4D+*FdkVxxBN2S`j)QpUncfoQV?l$TE0mq%SwYKK| zbmMVtS68TFyr{_F&BtG5tgWrn-M4G-8M=SIP`gOM88`1PBPaJEEUX5CgB^Rmyhk#& z@|57q?j)?9o*uZ=TVSRkdAz0eRXzJY#3%U&5A1Sw!D+1fo;i+BPD+PiWaIoOKZJ+J zE!wXPMT775!n*@0xD+EfpJ_q{O*gPUJvlzwn+%17V^sS1n7FTYn+lSn!2w#5ccQxx#W-Wv^ zVb2qBRBpu%b(zC5hMhh593eFT2iIPMMRi&U7cy|e)<~|z%nF$R5?p+I(}7TpRX*#b zqS)npt^IOQ$CY*%=Kge~E=se=k`D3$jC`P^^W^vtV#{YhL{B`@RaI4g9Em>@nTjEG zb90NEeWrsZBa@l`m6ji8MMXyT@rCa4XjLMN&B&P;R;oJtRL7r8MigI}8NZ~Yr026N z0nDWq9*JZ@UH9!PyQ7{`9Weri|9-ys$o_;xNl9s@J^I7Ek%O+T?%!P9F31u4TfIt8 zz8l~{j+O-5oZ9S?Y8oD!eAz?g%qf(Vg7?3#rfa#bA+D zqMcsTCv(@`m5v`H2@86H>GdmAY&%Ru=|4lXG zq-KksZu_>Ts}Jtn!6qPQ*8^|9L?`;Oy82f2`m~hIgv?6Ct`5EP6qp79w8S*&VksETnKHldiGPdll@t@tsXhVhQXGGBaR>C>PU>ZEOOip zrGL1;G0mp_Ey`}Jb^9ZiZo;*PG2IzT4615s(SWDG8P|@ingtgoFY*Iy%?*`G1Qat<^nAFNDy~2Z>k!5F{TEigduP={glICiVX4Yiw-u zz9qQ{3-y$Su#~0?@equ&z1U{*N4ekPLmXJr2!+M$XJvm;CXjeL3w1q@ z|3IQ{#Kpy>9P?GH)sDVq1bbvs`}V>$cJ_9lOtE0WF?3=MMo&B;)un@(H1_rN;hsAe z1Jj94^f+kQcY68qE0wrYUgqPh2uLT~9v&X)U@ayPYK4Y{;1vbH;S$z2Hd^_&oBt%n z^E7H#x(x(V^3=-Qy-N*|n3SB{1Wdw&6XK?^RN;%>Yi)=Afq|`mABh0w$$36hye^RO zWj`ObE6QbifeJ!4>E+9MFMog0_q{}A0J+_!cc>4NpaJ3sq_ni=sM*Sj5q@MOPjr}W z+-QB2rOxr-u;53Wm}4j4%yux)5hrKoXxOPb{+GX-fpU(drllE+70KUDGs6lh&TFD~ z4MzMC2cJljZn`vtR^$#OcqG6BP*ZP0quDOo6D9c*1ciq7C3Axal8UWdk9WLQN8D+5 zNvq(c@he(1y2Y3p7c=oDg7aDH?@TqYaDqBt!hF#XfBz}oc%17P3}(W>{=DY@Q#?8M z`iRh>ES{8A@$%)%@3ZZGhIv73d!15{q%u=Ww^gpgG+juG~1ff63K0U^dC z4)}={T^-2{)TytR7pi(4$9`Hg7p{gEv9PkjV$U4WJIW$gZ~D38;NUz)1;T*%a@-Cg z%;@*X5eY~C|CVsrWtey8JhjhssmWh>dgkWrXF?0aEA^(o?3K1Ame}nksV^w1}WaJ!vr#1 z&%*WSese+KgC?&oq0#&CZN%8?Yimh>f7F|r^MC#N#m~`1s9E3%i@K8*C;29XKs<(AS1S;vJ<$+k>T`9?H74Td}coJZvjivmqjSitv=|rbQ+Kj7&=m$i^o$rx?LIY z$T+nry@1A&QcyGj9ioI)fIMCcGy`G{tS%X7A(1ZUFw5nM10u+b$3Nm^oJV$()^2Di&zYirgJD8jRk zF&LuE01A;3sjyzZaAAtX+LBRD>y<}0*k&)yc1izhxWt+9kFMyF5T|KzSj4!Zi!UL! zo=~5s%^(B8%)(u*h)-FuH7eFPm%$Qz$n&~;~t2l)nYf@G=mdmpaNfLg^DD`>$BQJ+smMJ0OY9q>Yg zcMlX=#O?#YLK1!lQ>gfaw&_HDz%_2}ZbbGo0aenZ`Tf<#-rnA&!J;lo!*+myW~h9Z z?U$qs3|5MXlI|VBQm04xY^tgL^WDkb13!#|2Fe_Bqa|Dm2l7po3JdK(jlhY5?TJ;A z+^=66F6#qPtLLqsUu;_>S1h;$pYw(hDJA9eiOI=_Zf@lOVdHojqhR%sUxL7gXhnL+ zH_!+LKynZLi0IlOGXeoHQ!p}0od+JwX9ogI2gr5rUr0$EF6D!G>AEWjNS}AHFINbx zi5r4Fl4(2J?Pl6}03M`+JZA#GM5Z`%w7(g>^T5TW^vMsS0IYW4@W@E+DJbwaQs#r$ zlW){Qk`GRuZ!sv?oAXReE#)pD@Vu}Wi4g6hz+<977m0@G9z{qaNC}jQ&vHmO-*HuE zb0*d*1|u671%5i~(3h)gg^hy)5=fkg(^}F#Xq69TWZnk6dneFH`QiP0Jrtj5CoQtD z0RM9KOLR6J@7Cj`X3*Ff>3)5}x0w{Z{#%{z=d?+0=8<}DYBQ%=&tl$%iEmhwKZ^Qi z%&ZP2mG0j!UD++l%A+#0Tr+)b22)@LaSucyfM~hwp}JZ4+`#ctQ<-5LeA%w^zgR#B zfmNJhu#1V8A|6;mmu9P~R(Ek}WkCdpo0>8@lf4E(BX~YsD&R-V08rwR7eIvopxWyo zRNKzRJCe}Qv_S|GaoM__cK;K$9*}JSBEGsF`#vNr_mx3$JlI)o18sHAZ5jBbHQcfR zDJqMOM82MM0oh5p>q|27x1DVpy9y0UJbkFTMmmp{rS8GjM&PFXcCC> z`3n~iX%gbraETH~jP0OvENbUIh~xx*vj#L?co4);70LZ6(%H&@kdSncxDj|#(h1(z z_Wr6gkWSpOxqAq#;3Irn@=w6iROVt-zN!9TBZ2wh6h-B!VEnQlw(xuHV1BzzwR_^l z3MxhUxGvh&qkQjBiTv2*y=$AD)oldg71h1Hz8QWsy>%gxessi+lfvQp`Nk`nd{4;Z zf;?CH4ky1a77dsSc^s`uX2>2g#z^T3EtYyp+uHI1M(;a1ak#?id48`8a$lzAcMSMP z@ysN62SCJG+pj|)fmSH&f(`@%d{q7(&X=bJH)?8X5UmnH&R!62g@dHLAo3ajKP+?P zfIW_%`qsT*j+c$J3c=7W=x~ zt{WiI>DR|?PmZ1qjC|Vl*w)|3S{^F-00a;CK~$!MfWW8EvO%J&uFlTJt!_7WR!6%Y za8=Ypwm?c94rO#+fTUGGC|#^90-x1v)ZLQm>BeD3(>}i}Y8#Jj27oYiqpmoq>JXn&9|c6mglf9pv!9IyBBN z>b`*#MW$b!Xy4Ki>07<8Z_iZZdJ2{@wzAR*V8h1Iv1_Y8vFqyA_V#gGB&m5{4jn)+ zB&T$d(0Uyg(T z=cHZv0Gaj-)k9v(n$ zn_!Bw?dL2C%^3na9()Bs2+ATN9!E|f4k9T!`{|#O5%3nU+_#(DGr%6K?d(#ZSOb)S zgqpe)q#uw|Z6!@1kn%t8MpcW%2r@BE`Z~Y-`>kcD#4cClzJSyV%~L2vKQRAZgx7lYh; z4N6xKtW?SzEI^Q|+gTormhzNDK{%}I>x%?|OS#nk1tNhl`JVy;^FWXt@FZ^Ye(pDK z-XQOXaFhh=D>SU=0I3Cpp<2jtUmj1vCz6@EOP&(@+@NS{+RUdb5=7 z=ZS^z>Asw2^MA8xNUtd%kupx)IULke<$RNeK;S+s4}pmRxJ6;?<_3Ue z+!#y+2tOQLiN}7f+q^;tFzAcF->4v|rNT0}tv67xgBYQvGzHElGgxQ=y!sNjd3{I6 zJNPHhtdA3P147}QSr{;oJRT(3s zgb5dylo(SRyA{B=qdZSG6Vrj-Adg3sV_I=1Zmq!*-icQ*$Ie11v{6@o1CBkg1BIVx z2t?G?P-UVtq)qW+eHinRr3mjX!^%iYi;mQBX@Q-j z1frw%!|2}Tm^X0@D2z3flazQzvtdO-ytY&FYEaGr87z(|Od~t)u4Tpl>IHae3_fXq zR81gsc9gzayrd@y0>a|ThnrA5(nlr;Tlf&vkq%g?hXEukyxI8%4HtXAs4yY54Fqg} zPSOq(BreqRXuT=jZGWS&uC5N?moA^9$8kKm?}uvv$y-> zl@!6pDWUI5>{}MT*y2#*eN(CSY=fnDgMyu?sk{>l;x+hIN54tMY6VMR!ZOyFVx*_ zrAIvuIS}OIp7PnT02NyIkA~U~Oq67#UgB54%t?0d2Uo)@c^3CZ^K4`r( zk4=~1?edj{K@ICVMhNQlm@Fp$slcE7a^t(LbC)~<9P!1^Pf~XAg?S1MDCxD^b-z^p z`yei0N*bZj^=VW%Z4ou^YaEDZ?Qw?KI&5^NuAI=lI=>pJ`zGsJBt^^WBZPss{VTna z;7R{C7vDNXxN3vpZckZbky9uQ;ptI^%Tekr+k80=I?Wt4B zh7*#GIk8pF@**o=*A)<<#!GTq8Y9Muu8;2$O3GDNX0P=d zj-}_yvGt#658AaoDQkO^c`vVcy}NN#KPWDnACa)uXsVnR_y;X(`|hM3ga>S^6Spr< zdf`J(b^$$?OkHpB#dNI97pKPtO4;x%V3EN`Zt|cLJg7%piL38QSDMfdUmq>SwD%Js zVuVUP$pY3#_86!(dtu>x3mGS)p?Lt%D?8*WX21PlTRAIYykfUH-u~_y$s*36ibv;Z zO-AC^J<`Z@`dcmN7cX9bS~Kh>iw+xP=O8pN&|A{<<`HbQ@p5$jSQc|w>*@Gqjr6vJ zm+dD2acfXoK=_@xAPux#K#WDSMv$MO+?57_63UG%ZJYm!thzw9R(SsWIuvQJ86_nX zpjbAxxcC5M9?)5VOTGd8Czco+6(tWC6Ur1Q4m zD>#OUwAFZbe?gZY+@Lg^94)UCEIJqxD2<=gmb&7J@p3`ged4hmzq4Xhq@28@WGnz9 zglI1Z{0bqPC?5ifbo=>VNR5DuO3attKf1j0N}#Ww&Fa4wUP zZ3*pyDkGEVNfa+8)_Hid_JzrYFkNkxA6}x!*E?t%RjjBWPHmLu>CmX<{fm41##Y1d z$nx^?>yN%%X1V{-x-b+3yb@X}surP9w>pS&;9%gJ2nu(ea|DX?O{XFT60mZWhdT<& z*|Lz1;<}KcJ>r9~oPZp0xB)o8k~RWMb)E=dUEAFSX@g0P9vyZw`1QRHdTV;#!JVSWU$_Gpl^#(A4Vvvbr;fdL&t%mpUS7|KfpS@f za$V{LVYD)-Xpr`Yi`CkXzPwKn>I_^yp+gu42!IMv+^+%4l3c!A4dQA)2omYrM?VHT z_E_22*pQ?M6>(!{c46VY+`HsxinYzIwK4CtVaE`a$`4K<9$1@s9lDp6|2?5oVpdXv zl{PP2VhAh8iTnA~eK=unV+hhQ1LN(}bgR3d3 z0Co_G2hjQ~QWt@Cma_^zgJc|(ggc`Vl@BS$LMbLJCMG6jRaa)CupuZ}mOyS@!<%6* z#N}u3k2;~zFMFgdpdE%c0Qk0cbj*PC47Ew?E{R!%oh2}QUcL&$&ihZbMcEf7me|sB6TR6bgAsk z5L*e=zs|KrT}ahCzTT8g$QrJciTX(UYJbC6$8BAfh)z`I)-4q16$U3q`w#`5(mj;f zz$&9V*m_OHSM3|`I47&rwZFDoH9|#;? z5iYRWF_&B4)uo>dOX||=px$#=R6*~%A}LKiLBB|Pb%fhABxTPvQqH-5)iclSQ=nAX zpgdj@$i^3_s6r;VI6GC2Ix=oPbCdE_ij=PNRc|6?Q$EXx)4aT6qo=;ko7KY+HEx^d z<0~R+ew^NZ^zqNS%tczr=NN;`;7fA@q$h{Ea_dFa;tH&x#QN*1d$Us6A*`y5nMglk zn~~A2Q2Mo%vXF^YiC!PSp@`ZyKHWL-$TQf_o^hdU*rtE?{(4cjeR_%oTYEe{v4qhp z@i6R;js;YB6_uep^vwNAh=_2|(p8eVm~d74M0j@9y*D6)-9~$LxkoNLxJis%3!8kQfMkLWsfuk}aBwDggKaDl;=v9H;>_ zid|x0V2I&=Q44`FZm@J@F+jdX&_i4yYD_c1!exUiqINNN@n0pTM8?m{E{w;QAd+k9 zz=6P-9BP`zuE#uvjWF5O4X9+QCEvkAYTGHHlK181{q5qDrTusz;)0;@V7%7n2@DK) zydDT-P_ZV1ju#ZzVl8BxC^1J)fc@n=|IDDHL4sD;+6xpZ?cHse)Ug;L;&a3f>{X3= zrR%zsV&n(AMS@ZO1S)6wqSEV>@>F}&vNezFsQl z?_4(=?O9|HPb!COMi{C$Ek95iF%Wy76A8f&lFxyp5RHr#g0yyiah6&}$R>0pZs&^& zL4Z`_8VBNC;$rx;GHrX;NLt!&&fCzhC+ zJ0=a&PQ&J=xU#`61Cx4C82gNkEyNAPEH;p>TDPK#iiGfq>2X2+G7Ft3`1fORRa`@6 zqcTM<*+Q$>8f#_eN!QYY(22jrVUtdIv5ImOEf!GO2fiP<5+{g7n%>$0&KF>GC{WthJQ$YNVB)C@nt+eu_5x`#FMKe zk_YEK7`U%tN*>@P86i0d!l~0r$!y->GXINTZ$Y|)Rw#Kry`=p2ZA4J=KG>SC8>{gK z0rtFc>&NkeKAlNuzk@cioA{$X{!>>R#OxQ(Nu8Wemdw~+QYFBacB5s*A?JAcN*o=T zhOPXAQs5=hFN#ztK*WTuM+E>P&OrCR4=xvNJN(n(VU-w8 zgWuQX@3r@+0ET1o)P6d>?z19sHvYGorM2}YC_}#D zNAHuq!zPCh7_1vOO?bpZ3 z&3x~SDOQu8CqKxuXT!yN0y)O=7M>o_j{$Q8q? zP0v>DKXj;F@=>lREvS*1N`Hi!!G_VgmjuYa{$a3I9Yq#h3VEOGzv17 z0T*xSLDL6x!N!C7@RSbfhFzjI*eAzUurs4Cjy`maXJ#a+v6^`YG;`SPV{@~x_<)ka zYd50+eOu;G-3=3OvGlVX9@~2Hg(fdlgOkWBMnHc;1~Dkzu?;-E(Moru^#Zz+)a9TQ zoZlGgCtyaqdCVc)N5mz?<#g)4wp{?jKEmUaAZ!N*+y~hLiXjgQ|0+RCvw*-KXDJa8 zk&Mp){!>(=?)Y_nViCGZs}ERqYJQdguS1rV%Wi{y@D0GTvK8ZmBT;JL0%=X7%BAym^s~nY- zP|YM-Dd}sGv}>hLD5avT2e7#r8NC)Xp5^|6<~g7iCNC(^HUe@X)gP2ZBTl+JkOMsDRBl@!{xUOsx(H!0kfHy&lb zwBSaUWS@~`l(6exo4GzqzZF@@^tS2K+KSyfqm}A%q+x>!2&O@Wh_3G0T-TlASL?F( z`7EoyW1ctgE#w-eD4GZ>$p8FW69|Us$$skuV1X*Y6(YfrcI&;%1+_9!Mrs; zsY(CTo}7@k^0goR8^!o<;20uzk!J@j4)&?w{=L3)lPi7+|LWDXnOOBEk}z86JdmmP z;dqM6;D(}KahOmnsEg%yTI7&JU&s7M3!vB@v|8Kh4VfPI8U37dEH?KG?_`?`Oj|w# z0df;>f^Fh<9S`__b2_}CP?ErJ2(0;?iHu7-33)ailwaNUt~$B&2Z#-v!yK@r__tR?CGK~xCm_n<)iJyX(*}glw+*?&O`IX^SVB(n12k#^& z8>iz}pxelEsv_^cBYAY0oa>yUW8IS4?&Q5v!`8^pvVf>CC1)TpNM7M+@<*j~V1tU7 zVb)|`?%m_S;xp{WX|Sf}AL;h?tu(@67+BQ7khD4dOgXfZOacA zo0Ps09D6Z2`R_SW^n)+>$}*{5W!6~qo{Z73H3c4~s~2U<{_iu63?0(mOIEUdVIV ztHZ>5zPCmi-v#>mkj2;^+TUDT$`6^Y!RpOy_L%F%r{>QCFgf)E(aknWzzs>ICxh5K_>RLC)^=YO%WSW<1-4XHXflX&{d6`0r)E@Nm7c zTTL5lcRmD+eMw0+kVV$25^)A*2A6pj;MZR?x5&In{KT%g(n}73d>F2TM2{BJLJM!9 z5o`9U=pjO@U$jiOkB*Vdw(kp$5aw2I>6ek{a5N}lFVPbjDcu&a)-8>=nVSswx4a~; ztDyNm+>^?A1>yC)$@>ge<;kxZAmbrMIYpYGSVO=i93gj5d7n+O+6xQxIm9wXk%bOd zxsLKzP8E+1b|R)p%bOp<0MM`P4*uS9*QoGO6J!c67_^*-TW- z`f88%_427kM0=?mm$*$X{RdfWh#p6(o*q!$zft);3G^#fx-?Y(RYsjX65kI)jZ~h$2 zf{pv^)jV~6&_AUtwZT73T!HK1!R_!3Oez(1wuXM@!x!^S#Ue7|4uvc!sHw#lI!!wlLZw0u$vnm0pTB0Gcy!#UIcUFzI^$gT@oms7;#bC+^Wel`oxWPCt+`nb2xc5mIo}uyT}Tt4B<$cNIsUPtZP4wA=`Je*(@m}3%oFwc zgB&V?wzv|2`X?tRNTL2wMW?e6@Zr?-bkS8-R@PZ{1vH!2#KhR)>eX&3?;clCQEFBN z>q{trRkt}uaWvsrSE1EtCkRAv0s|?v%|gpd=}aj?#;;#*b|xSoXq*0tQB`JUt;^F7 znT}c$4m7Tp9xS{}X8~Jmb3qh;?FIm~k2f_!;0dPAOHU=d;K&%KJJD!{UPtM@TGCGIlH?5z}NdG+TEjsMZTFWBS8yhF>gM&0yR;${I%ox0mlj9J!6Vx>q zqK2Th?u^7hDRhef=Q9)$9CCqDE_B*cK|e|p9PLBoftwmRKM`Bf^FCKI-DYjIomgVk zM{}7BYOavs(G(NV$Odp8SQZoL)S$y6#Zu^xDS@_TWJmF!8V+P+Y+OHTZ;`1Vb+XA& zJV^vQ;!n^c;^pbxdG&IbR#*bjs|8`jZP)agYw2!-m%)S+J+R|-FyUrf$Jr{?7);4b zyd&(-IHMSk)KOc{-aoS&Co;@^XAu+c-n|f}3e@*26v|V-ESAWZDNCRq zVr=T(7c!49Ni7%H97WvN4zR|F@H4N=llD7_+A%IaJuiOGPmaMyZ1pE{>zVo@vgAX- z$U*qo>{|Cs)AzB-$vF}-^ml(GT+(j+(a3Y+DK4S9mM}jK59ns>PGgp>zk@i9t^Y7l zm&B~*%CH`*fQJqd%YETeTv-|Rv!Lcze#i;VjCJC0_jvE{`Djl{&FCmHo{h8dcx}$= z_j5OGoc=jtXy~MS8zTUO?15c?zt`Doc`Rw;gt5ZXdYv4gTcYs-Y4z|h+>Ak78R+GH zgUxGVuf9N~`auu$ze1n6=Lm8*QiO=vY$50-4D99MSJsW(?7HeYh_*$d(D(KMdGO%# zMfE7LzVG5Z1-XX*A|>6ER9S8s2KXBxIe1Et=iE6Wdv+<8KCG3YD%2bAtJfNlw`#2C ziQaMmUOc*C2gNx%#sL530{1Pn+dj+Q9;J>*|3J@P;_0oP&j`FJxnIeKf-^VYhihef zEd*(x%!ib@M56A?)L-QwM1&jSucs{fG?jj~(@9pk$jG&&;T|kReNAiLfCYAP0c4Rqn6pC`bhY_A9S%bPIC)ehtwY-aAw<_k>h3!kLPzgt&#!R0cZu!5rjsG|T?-YzLK<>1*F1mYYnveVN?k1t&TzwnfO#iIY4|*!^!+}04=jvwNPjPVy%F37FjAV@c)B1+?cmfHRTY6scIFA^ohORoz z((Ub5A^t6tyt?Z48)wfH`a_|!!1P5IoQHz8x_rhk|Kjk?+3^Mny0%k|Nkfp=v&ijN zEs;$!Z;iy$gZdBB=#Eg!cndg@mZp>_3CD`Gq7-DbYu;Y4p1_s)ct7PdJ;#&3^eoFV z$8H#7L8aFG{>SULK|BMl1}*Bb(1Hc$AZ?(IV+<+~TeV`G*LOp@Hp3vL+9nUIe+Ay^ z*$7dwCD@o2@zQ|Czfch3QOYH@#z;p_)?l9qE+!{KgDXmchFblh(WH{kcW0;SoM+0J z;XoakW4DguL(^ZEL_nkFj7twICdcg1A&RdF@f8L^FG=@DM}WURSpBC518Ka6u7j|M zh=}>`(5UwG<9(TnHw-6W z;qnUlG~e*}LVXV;tl_)E#x-362F=}0x3xVVXh^^_q=fZ!DoJ_p!eeOFP z_5^~h`NQZ!Qz!!~902yCcWGX5!l+hjS1uJ-<5zpR=%Q^F#IEboAME_+_K#cy)nGQg zaL^M4B4n}CItG#)w3CK^*YKSU@E^LyXHq>~`wV6P~0 z>1`g>9saN{*RN-pOUa<|je5{3SjNg!Dl@XTFP*=BqnK2s<~+tzq0rK#TW&_GGh6T`8KR1kT++=ZRs(1Nd8fIOqikxg^UYnsK?g=DTufIuok9u z5>Mc5Ne;Rfgqr~Bv4chbcN`saQEyg{azbjMLYm}Wu2U28un%*`gTzYMSW!}*mGkE@ zBuP519h{y40=ATS-~1%(ww`~ILSMMZB?Dlv5slaOJl;0d_Jkj_Z5pl=4}0VX zU<~>bBzD4dyduB8!x-$U6dyadj+vsvP!mF)zXV_Y_J^u@!uA22?bL%5k`^T|gWZv* z|33OcN3L-DGqVJ*_m>aDtuPp@Mk|NVClL*K`gQ)n!Qxrln_O2|F}8y0*>4<2zGujp zN*ECz{;HDFcFAnf#9-2Dtu7)VNfVATKFJ-0dK{cexX%;jk9)E0&28_cLrV>-iI^)4 zw+dda{Z>l{{POW)6`L27%V7UDO{~$-z5V=4!-Lqe0lq|c@*9tN!R}K(?sb>~ zCb%!HNF;vnMM5HJ+%25w6!+CawbY3|xUoE&Di&E-5>!#l`%&K?Z#o&sYPimPQAtAM z$}oFnLK5f}b-JA3+?e1oK5_3+`ymcQG$Oj-88}>Eal;Ek@-xAmoQT2qAkw7UOjg%5 zZ&oEGsr!nrj0|?z#Uy{+G+mF^LZd%3bnS?0eJEUZA+B_Q3$fuK_kKJ_h#iV=Y4J0@ z%G{0MbIN$htO9^KHd5rGedQju9*K{G|F4%= z=pfEl_{#>pnZ&> z#eJyZLahl-SnkJh3bA5Nrq}c-C5I9`b|zXLwGQBW?h_2TWDNk$FlPTkFa|2*{9qB+ zg9vv0m7$WUnVDbEy3EVR_Yg>`DyR`V{hk_s+ow*mmkfyy!(+bc>&h_C;chGMLSAIs z*n?6I3-tLzsjC+bAxdY;r1F~&oi}Xy*PBA?Z8Q1$beHjWmMKinAM17n{+baKeNb?g zx51hOy%+Obarw& z#U&)@sISYU;#MA!m~`S64H|6alr2SfiR1kFO4Y%FF$mm2(f7eY=D#`5+8}T$l_=i7 ze-XME@rt0x%&Tx6Gs`4Iaqd!H#^ImS2vI-s+sprekDCA_qMXWOZ{ww_{Rxp}9olr) z;BdnGk00$@w*v=pqTav11&2?dHIF^$3&u92F~sNOIQi+cxFBsnhV6)lE7@EK9V{4H z8jkouOXP)x-PI&XT=OU7XQ%cvluT>h;AL=lqJUt$eesPOU1hVzD1Q7?;`m6`O2xUu zqiin|vfX=v1#D>D&_&L%!Xf-Su#wO|g~bT{f^d$aZeAue6}oMR=-wRMlbfqZmnt6S zhU16eWQ};+rYJ~IN-)T5_`@8~5P??&N^~>;36`G@9Kj4$N*OMPleGlL2Lp+xr05H_ zuo=n>o@5skB8+wa^)32{QCm*mjBr@)`R&2FrNsIU<|b+~$<_ zTrlZUcvzqW{0)5zPgw@LxicOKMjBs3Kfe*86Ls{hI%TT3s_=93Qd@vxXvmVe-#wMaXCvbvIQnx6hfjSC`T#%B$A^tzVR z5enM2B#!U)Gip1H<&=&6Gdp`NC?K-+T+S7&ibr$K$LdeN(GsK4+_tHR2YMiDarA4d zWoM|NFVup;10>URRU$Vi^NXej;0@KQauQ|InF}C!u z7^y>ArDTAjGcp9^lU@D_KL2yE)KLgxTs^cq1j?7ptXE4D5A@Q-(kIn9D!p#QGi+L@ zCq{>DrovmN|E1o`a}xoir||Fhzl8m6X^=~Mv@w_y1(;E5wm1HG0PE8HY)m`zNw=tf z@b4>9GBWq&&#u*YkB3SnjTkpMJs(+rogf$N6~u`ollrc+_x{wwQb;gYs=D%*L5Thk zjEJU<8AEdYY{V^{zLM@s^OAH$zYK<%4{Mqjyw$k005qg&sG`{%?}ohHUQBlR7Wwgy zXMyR-=xNPEp=f|CB#g-2+5>r5I&M7)9u@P4j}F}Fm|1Gdoq=))#`(*8!8V22*8NzL zt`ZUH9*?mv?WpY1;kJx(-^um&-+K$&@R8_(3 z$aMmIqU!3`J6pZWgMF^JzTNdgT^ZRpXuP;f^FA>?jxsC3Fxc^PDc6ez@=I;q$aWum3DLVaFlY!Xoi2 zTn2WFbX?zC>TVZOD8!vdqfP1p{Beb^+(PqU1g=DIct=qN2|14X;(&IQ^vbLbnqsjN zktvouj8&waru*~q+Ip2c!Jn+UHmWc(6dW~OqA@7Z-ET(#DJWLw*xy-fXb zJ>(C8Mkmi)KYFF2&z>J0mV|gpn&qzL+~{Zm{fG(rmHI>Px#v)-p*y&O=0V*5{wL!B z)8mtMd~J7Qa_JezpA^B=co#05tqdEi4BKM}EADeb?Cley$;6k#U*Z1y`CTj7-=7kh zTbjwDy1ZgxhHmjXP0rJO$wyyMAFj=JgYDc#HvdMs&fekZRVJJqv$z&7u26;p_hkX- z>NG;emVw-F&`#-EJ^ST)kYoO-!^F2y=%WS>#XN^>bl360%}aDIl|oC$`8c15^;WjW z5*-JE!66>5=Ip%F?eXLZ7%l$^&!M1eO|i{o1}iXXe-v`vkc|zZ8nC^F)Z=&?r;Q{t zjp9X4#A>II4PTGGa&xR?c4^+GPhq_F9RZ^t`G}jEpNFhWD;l{R@QwYj+e(Mt{zXCL zO5&&m7if-O)H`5P(QJ2M+1w18FKZSN8E~!fdPr;0qTtVh*e@8tp8Cfz1FS(h6gi59 z?zp*$6Zv@~$B09iCn8Nc-h4M)o_FL@O8%EnV7)&L2^0y3s^5}0y`rO|;dlZlvyIUq zn290>kZf1-Gd>Jvr%diDy&fb~ONZ(svgxYqMf0d@ua^45po=3WZFL4U*KI#A(4)iAG23WDR>(eS z*iJ;gM09XE_Gyg;$PDRB0hIrvv-6I}y8rjMD3m016Is!4lL&Pi8HpmZp``3tcf-z} z5v54Vo((E8D-kYIU36KIy*JtGLe_bG@89n{&iUt@$9Ww8T@TmwU7z*-yx*_a^J~}7 z=s4-+Q64!;wOx-Br6M%<4Ho+gBUq(cEzqY%2{JasA}QuU91BxrS=V;%Ga5GS6?;3z zZ_Mk)c#G75zRN1Z)QY;wP`~23ulFhwc1#Ps^k&$gCF@TDQwFiwaBdBCZgS5s& zOMP7a6L-Wf4dYG5J)d{;c6NF3h|1MIXINRCOzA_?Or{Qdg#HHyG<{eUXd)?Qmmh90 z$g+tqYO?vf(NnE)Tu|Y7jFq(zv>UACu)O`LpnF;I-J;-f!lKb3Z=ijkv&&u8iSITk?qi zu(PPjsmqnNok|T4Zq~kGdyx`@08&7K2!1r9XflhebaaaQH|-va+H~(8wFUmHf1LnR z#m0OwlE2p~7T(yJXKk%L)Tato)&5MPhlwty9>s(ww96B9G=|&Q13QQ(u=L9L+)__|;~c+m61aT6T(R zR9gLRJmv2ia$;fPu;VM@F3x=?zVd)fC+`MI${Cq&l=QLNy7D<}mp}MBcWwwQb5z01 zVM(0mOU{_-YKl%^?U~?_3w+)8i@J`Fw^C2@v9hM@g@ln4Yrl)7z%$)=PpZp*DB+kwhlPZ5y6ZRIiGkdjBrC0O%y2Ir5YNOn zR6$m}5w<+Vmo=daciL{U%z4Z=5YJ34`aI5IJ3Cm~;oO$EK3Z?WS{CU{o4T{pn@`s9 zF!EC>TZyYM>GEQVmsQf<)^0aYQ<(ir);*n+*LC++2hn#~m2tubbz9D_(rCW-dX9mgBfvngH4%C#$XbRHk3?VpwVd#{u! z%%!DyU~7Vhy1~3f;%dik>SW-z(+ttMOZLK-uho8%!pzUkDGvwVCyM3ZOn`KF1?c?`EtRE3= zjx?+?a1uhnP3=_l5!|^}HQVOa%edKhAyugGq9R!Y_>yK5Dz@{n|SRfv2*D~G|Qlf<|C z>x6~=?}2ya`iwlX&CeCnhzH<`YZ3~~$r%fmM@FLEV3_@r&m`4QoA#LL@R{X1KH}mj z<~Uzs9luGKy;c2z;YMb!-(!>fsFG6uIfH50cvjmCsv$=Yx{(C6fL-%8ElwkF+}sRtD;e?BW3 zazK*l(g)1}bY~9)N?)?}Yb2fB>oTjgJZ=8NW@g^k&7i-N>A7m#r%m&&ima^D{9ylx z?-OK5aIY?Q%xq%Xb&97qG1|FqqTJwP{|;ip`0?3MlNFIImL{{3`)sv^GKGuJ4A`anJ0EH%?ie#OOwSmpR+`;qAyP%tRY8=+s-@ zT!5a~Qzoy=J5b}ZxAnI1=on8fJ3U=LOoPr{4fl94Az2aMteEJaMtMElO)U4XBqIem zN?X$@SNWEB3g;ddHBElw(o$tZnEE`|=cLD2$p((2TfT+7Coj+q|61V_b7gSYd}WN{ z0e{K9eNoK9h(|T>7*&xOKD#0zG3Hv;LE(sRO1xeeoP6P+%M#u4oH63}JH&}md0PGw zaynf557MdX3vzut-wwGZ_I{jE=U5VI_mGt4K9!5E;Ik#E+%;Qdam^iDzqJL$<#Z#T zyCE0k%$ZZeoezY_I++ZUlHHwcM@a~*p76Qp?T}$uUMTZkGoKt^9*EpI+cv!^RN_9@ z+kEMa;@t_0V(quNq@5C;;>(J7q}IqE!f#Ta0>A=$em>Q-T}@)7nnCXK=uf5&8pDE; zJ6$Iz5wbrqLkz^AwZ!Y{#)9ov7D!VgsqCtugS%uIv=+lU3#$w@U-o{zkfg&m+`wdJ z{?KZhMX)RiD8wZb&;b!@^Ba|8EeV98Wuoycs92`JNlM~nzKTZ z67pr8#S@9m*3<%nQ@N2520EhpuKNC;$||P&AB|TWI41U~d6`?MS|~DpLVrc2E08Z>o4?ojytYj>&(ySyWLDtHca*}II-Cw zAU^7LVEp__{adcyt!Km7k()85AwT3I1KRf)Zu6@^Xrc7+62kEm^V32QZ}54))9GJa zI~Ke@xafuTAENf#GP?C{^_(x5=GPKlz1x>5RTeMS8adC%d}y{Z!ZNI{qUTblc*r2{ zz@>@llf9PMHu!3G}_aM3fuZ~Md>gM)`rRKJNm#k_Lg7lx$*4f z`!eB8ee-cSPuTQw)GvP*Ntak|VIz;&vI}i7&B)3nDFzSmRLQGn2u8*{{d-66meO&@ zzT2&e3#-w~6_r&l+;p9U?_SvW=gjP%g@QGG^UVtpsU}8iyr1hk>T>HV<_CA^@n@JM z;DQ6`7(xWPDCVwHF7n<5HM4{9_R(b7;*~!rTND+W!mngGAN6LrzQ$Yc=PD?sc+IQF zRdCmD0~^tNnS9HsE9d1>%Ur4ZXBJn=AC>!!918rfor_JQ=-2!fue_PWofF%{s44P^ z0)o=WC@zPXotYi1x&~yNP2n^>jZtPK2x`1ui>AD=T1qM?%FD+C-T`3DD`4=hk=gc$ z)$m>yldLaRbg4CK$}k^m4f{6H!3o^+gAVtQY)@m}V=T&U33LW6-PQCc?^w6wJu=s| zpFB`n8aZ`WrB%_vhBu5q%s;43jt2rxrNN7zjV7 zA6Y#Xv_Lc1-=77f8MY~x57&%1)`4z|>a)R^!++Zs840(zEpUBP1y+2fvXw^j?Aaa4Gj{&9#sPt#qZ-ylCu zR3MHz883u^GF~D2;m?HED(uCIG0snFq`azqpEGtu|7Q)wC$4ALuJu?-n6e&)Vuf16o zj(kjQ&g35wyUNs!EzgvT954|@Bs-bw_pMBvP(3INka7M70RCde1 zus_jLckMBGbm_cM<#c~swsgWT8Q0E2zf8{=qug+cRnGwX#jqypq-JvJmD_K~f?@~9 z`sKqn&DNN8xHXKjEgJ|$Cmr$uNUdzZJ{!ymfmxX2H9(oouG!4Qv{ytV{b#PzguP_^ zr*?y1U8*Rk+@)M&nKds6y5G;#+Oa=5IT_rFC{RM!Dren_;9Cg=G>=0Q+arN<1%9_# z_8^uDo7m4!3iJD%*-^&hfg%oif+hkqCmI-Nba{D+r_cblz)0b36dVP)ZGET#SeXp zJ-08my&9kO#)sD8S!;cEf)Ayjz?&*5t;n1z@3X(#Q8s`0S+M%}s2-S?d)CkIVjphf z7;anJ@F2cn#Hc0bSW+~} zGn+%n(3q8}sjK6<{Xjl=0(@X+X6CNnC?eTX4&`m<;|ne8F#$c{WW<$-uaLwL+z4Fi zyPIthpkVG+cc0MC^906Jj@oQaFbF|41nDRrbfuQ}*CR{63{7aR-wl`_sb>f*Q~LYw zzc~+xMCY~?6YLyFOjrSX(AE6|Y>Xg%$FemXv6a{pV7{%~(vJv$ zC#qPmv(ga@b+PBNrs~0L_)qFkc8UQMOD>HupBI`tYSh29SA5lAxNAbZIa^o zno4*OQI&(2*OWTevH}}2(3bZJZd1tM&b_K3764upPJiPfaGZqX0l?>Iph03nZg--l zNYFrGayoc>2|jFat<9qjo6>?@Ne9{#(4YzF>FE;MZeDm4s-e7=0Adg_3|udSZhX03 zt8T!6SnL^DI#y3IErw{1050JvQT~j!iMzJ!wLC7BQAE8AC}f)do(CqY6mPl&Mu?cp*u2|Y_}E54 z3lfTQhIjNJP!hkvbI?=~2@B85l!m4BJi@uEQJO2>$zx zB3SU~>z*3ewK-$DxC}LCUb2d>hC2-bW^Aa(7~ zx)3U@M~}9Hi>HEv$-B)R=6S2zPs-R>c75CNix=5L<*6KyJ9=F~4^boBYk1-JwGSuXFlTG}YO;<7C9ub7k89!>tHfIQx zn_+~}jk&od#ihuIaBhMTM|1V(D^`G2EfEdRjkVO<7Cc^t@ZS}H`Dh8tEqaDdY*2mf zlaYyrf!U|I*d!u0Rs-6wERkRUbz(#MB*8ixnr||;M$eZ<9nQ|9dUT!^DX%;UfbVDs zB`};Z#F&8;uBgJrON;0fcs@P$`ORQJhb;k5w_jAW`iyWFh-Q4bR#k*k*ue3}N#fR_ zA||MLdd8kdZ{>02wN;_?PvB7TA(U(`Yj&>z?qqB_a>@%a&^A`KxIhvj+RStb9#&Wj zd10{Hp5^X1Yph4RdQ_0K0=VEqFgfUdc9LvJs}UGlVNp?+rV0rD8Ns-MV)dG=(LGqD zne*CsYBP_eyrPNN`#-IugIp1oKY)=3!k`+rr*-b!;}JE5h7>KX#&rEM%rH#1h@}-1 z1DxwSA}N-*;P*FLW^|Mn2)PrmVa;a*x?}+t)3*K*c`}l6A#0aFE#c(ewM(!6s378O zg4w*s$e~+hsSUs<0uhaCJIYg$O5EMWOe4d7Cqam9;TfGpkBbV?Gb1h*$dM#tXU!k{ z-S$@9CBA4`P=I1;)Ac2RX{@NM><1!PlIQIg0$v6nAMrW^teB#U56)_80u9M}xBjVt zqvKqnLJbES+ew5Vbb}5dcz;57%=HXYumuT9{!5KW3Fxj4XvbYe*KW6`93ozHvG2eE z`-Tg8)Ac%v;%;+S0aCP-ZFQwUX$?O5rqDciMDbi+pL@9lngaqe1X0o%U{67u;`r+Z z2b6;ZX4~Xfu5-b78UZRQa5P2N05mz~X3qRS>lPEhU%#^RB=DcAyj4 z^bF26o~@xof3TVAE^T)mihl=Z7uT(iz98pdXP%g2QcCNPOy@gN|7f7*TL{l}yp7{B zp4CP4xO4(^7t+7;cy=CO8nGc4|E9gk!9mGM*HK*k`Q}Pq1{=_?4H<@QG17L=(8A#f z3Af~D%J*J0GkeCy%X`bvzG8o4xQ@a#OKa;`EE~XN8;`AjLb!A}!jff^Bq&H}coG)@ z9V0r&bqE%%loRjN-|T{UT6?KL5}vsFA2qGfYs@->Hf1GoRn(%{>SK+Tk%m?Qfq_@R zPRb&%IHI;bwwEIKSnR~GXbTK!{yWx^`2WUQVMz@IPS?4&VRLy0b&v$R)fFf3-*xFx z1W*q}Ot$eoh=I8np}7S{vxH_$OY6`bT_~g|HwntiX^;ZJy^3!ru(Pv6@#l%X0Bcws zLMQhV&HjDlan*y%+dz0Qso8HmHO^@UJHsDv;vGg|__f1{&-h^R6?O~^tq`!^w< zCQ9-_+zY@dO%q5Z&!}csuoWg;kOD%E`-Py>q@F230#Z*fdK+>jIrpiDRhM{$5?^Vxo7`2ITO_k-2xHHm&bAqZo7&BFEQ5P>me=&lWE$A)?6tYgqlC gzxsDfzT*AmSIr^sv;j}N=ZWU@No|#k6DEHD0ll-A9smFU literal 0 HcmV?d00001 diff --git a/ur_controller/doc/traj_without_speed_scaling.png b/ur_controller/doc/traj_without_speed_scaling.png new file mode 100644 index 0000000000000000000000000000000000000000..13b79d5c8f182cb4b141358d7bc0758294a75d23 GIT binary patch literal 30599 zcmd?RhdY*U{5O8xHknDXxn+bRMaW8bC?ld!GRms#kB`|A7rp657z$L~M*Ieb1HT=#XI=XIX%@p`}BuT!v=rV0%eD;0tuG}l#ew-AH~ zk06*a3NrYOM9AEfje0for5#VP^dsPD`1ferU|HEV}WIcjkN;_ZEch<49 zaCS9yG)HVqo$amdoUI={;C^cE==8|WmRtOs_&Es?ZYyVJdl^yD|NDV+c8->!s$GH^ z2*QnA$6e8NOI-Nns;{duOt#|rNKI5oP>@J+A^jAiZiDT@bTMDk%Yg?Ejx+WUW;`2T zoQ*sESR|OQXF#HQ^LQ8oqeL(%4Y#1acCV_zF>}{y1?4+>T31RC&!fC2`AKq~PiMxF zRVgP6Wu5?fZY+EinVSAV2=LWX7LOcfU|>jK;m70P%i=jDH~bitU`nJ4Kbl$m|KYNQ zb$9BOm5mMW%&y(t-3Rc4M_88NnU-QoI=UdGG%;&MKHUcouqUWU@8lUi`lChYpkh?S z%ITLo@|~ax?5wY^Cq8@kQ|;2P3JngUs3NPL^aoqyM|J+>6m)dW)|It2e|n-)+h1Scmkx*f?)%HWM_02n zlhipZ&KVdObX#525{e}~v{qIo6A=+Hv9Y;7*43AHpUu22=FGR&-lG1Q&ZNusuCC1u z!Hf)?oOw>RPoGMDEGja6^5n@g)sP^~B$@G_b=tE0uEUXQqC6;lFUMvbz{`vEl&dzgsj$)Rb>=$i+p2}2v^*kwwgNT^8 z@X_~ohAE>pz6!4;ZK(A0^rU2DzKo7?O*TjLOAGMw5;F>D;$nqvr|JrgFD`}^K5WMF z@=j*{opwnXKG@qj@3C&>=IMDgM;E=xX{MvD$e*-pggE{JH75&8aF_fZ_0rOky}iBS z*3vJBy-k~>t|SFt&YHvB_fN|z-PdNi!p_ff7D_wKn2c1qul)V%2h&ngQnFwAS#CIc zwAwC8K}-AG-=Em<{{5cfCwe#)mHEWzz5N1b_#(%9HIluJRrf2$GhPm*!@0!!AD zt<5_yG?acT^M-zv$A(jW>-W{Qga7VVNZ$Qq6*XVP8b&tV{z|1QSzQD&vnxP!_ z&FGcT?f*<>IugL-c0T9f_>$a@Ud5_*-O|x@kfA;1L8^2~Ep`if>UdF|%65g=8F^@skX1khIxV%YJ zR8-XC#W09giS^*Cz6y_x$8WQ;ChO@G8ZuNO3QX#VK3NYQhcy}M;*zpQ7Kck!GH=Av zb8?0U(Q!@8=hrC14zFyD`aX#chyQcEk+k{J62+@sWTEl1%9B|og7ccQ^F`K+R*~;* zTwPs7j4Ds@Du<$02-{7ED8h=Quq{XOTrGI~Luh?rkP$|0`a9VSq1JD1&dU1N=i9SC zx3}HUOaA0^O|^c+e-E}sA3`Xipr*#<-YrfZR`#he_TF8;;^ro0J5m|!INkP0!FPR5 z`)8R0vG?BQ4^B3Dud>a!=Mf5rrzj~Yw`bni+5hQ1gHu-ivmV;i)HIP>I`U;@y#BoN zoYwZ<-Ym;(03~DO>(?)y^yfW#=;-Y1wbW0FJT7KM-@eG=tJsr1kq-t%WU!V2;1c}m z@pzwu-86XD?ag7k^Cqy>Vlr zihx773EACuKIroxQyzk`Hwt0qhO-K8D~hu&78dWa?^l$7C1!38fP<1C;I)ghC3~PD$CD=lb2jxA74a)8EA+0*BR@DVJI#a^6co@ClTmkbIypEnaQSSH9~<`G z9Qs-9eGj3Bh}Ge;1TnYq`%z-Dy!Ty%{_1n;9%<2w7j+T(n*G&~e{({(!`Y?N<>C?( zMPhDbo|5xeKlZR=c}rMQ@(x08?0Zn$>CWY~;%D#d+8*DtaN>vZ?rTxfNX z69*-D%|e*7aW%u5>v$IS?BASe`k%xR4_I`)gfY93?|#4!n$oIfyVW{{R5*ZT{@IC7$>H&hc|BKnI{OmHHuJJ~4 zXbo|zP`RvQc|g47(zu(_vPNZ zntNvwf&*DdLUx%6k?LEOFjfhr`M%s9Fv#`!emaQKxUa7z&O1)2LbQC`HC*_Re8g>% z22BaNIk$#*ntFS67o|~Oho~cF)@?(MEV5@!;=)9b!CGed@yFYyRx|9AWSjLeJI?!phvu=2p4V|!?+qPPC?z1wl9dUpgTA4SPk|w9yV*TI0 zf08%9y&yq6<>EOgA>6X{{$`3iAvCmMW4<3YpN>n}(NTPN{db0(z`1j@U^n1NEgKgy zZ{;{1$WBw2vqCD%-K=hBKX>k2wpN-_-rm{!hKA00w+#*1Hx~w@=bu>p`YeHec4R~! zi>oA$Y{A3u-RakkiRc#~4h|04x8I-i*;~Bi{QDaztYSTw>)7w#lmK!*=oc!@T0Fgc z`7*n-BMF${7chrH%P!6j#x@VZ;#{^#7y<~ZD(dL8b?Rj@K zcLMg)gzoZ46$3kaXzsnz2cy;A@p7J$7M+Q~aC0iGzsD1Snvkn(ldm^^e$tv@1}A0ITnFia^fC{TQVC%5~*+rk}5 zmzlvMnjvbV+3=I?FV01>86!a$<5?ZaKO8S$b#q`IYyo1f;a%BZqBv!^#*b-FFc+6HqzSKYSo>Jd8hGa^Cw9G z_xZi;ZN-cp?sMlfhuO#xz@|z!ZoC-Ddw8YV81)YD*S>t?h$vo_2jKa0eYtNsyG+1F z9L8!f7ax7YEw?6}cfFBgST3$B6kF09L2yLl4aVHu+!PkKps=uqp9rFnmf#7k_dkZ# zjx#bkeI0u+43W3RaEZ;(xEdnmFhLT|rH~ia`u#g200;fz$FZ8fz~}415W3T@ zk|V1lrCC8km|6hvMn*=WhBD0~Bb>-8ldI;vu1?9XzjMAO{JyVGdfbz5L{c#6Cm|uUxWwL584>uGl{>!Ci%%KDP$bHGvjS=iEH0Lqn3yPVm{f+Sp=kNF_8Gt^bjZJhmMP=K z{YL%(i)CDw_S=m2LPA+CkPVmGsX(pusr~oQ8ec8|f&-r(F@iyAzf))N|D>U79q&vl zu1y)$FD_P6QiA2?Rs@WvZ)tFXCtw>2I2@#wz*{*de!SOXhP>QT9Mb~j-?jd{`+=`s zy#h;T0Q*7#SX=R@YXExUrJdeEAd7>F?#tJ&8YE<7FRn-P2lw{&GB+J8+!9cth)PaA zCl9~{LOLJRY1d$Y#)ZKmCvTdrdt@_U4l=VGGR~?9J;b?hoE7eC@8$*yGwdB5k0VB9 zr`0>fd5SE%P8$2{WUg#(p1hHHi-ep!QnvgZWm)42bBvAU15-P_ zzrP<)TwII}1W|DUAa8lzL-@RtHwO<7&(2*Tftt~Lc8%8;Tb+VmXPv$OSr=ZI3gYzm z)YR!ey*a#1;T*!YKg<4pD@#$yycJwJ>T|E`^Jgk#=*eECxe3%Ljz1WVAICzni=B5f zDg@{rQcxgUB%&)n>>+VAW=G~gYf_JFT`{Bx=>FNiE=9)_QzFu ztS+*m2whWCQ~B5IOZc@>5)0(}fwY zy*PJTFGiHnIsgA+bjIcIWc&e&KnnCeF3!2iBlJ<^>{(L?#(i6p^b9PFjEcl<9UZt^ zw~lklx|smW@j}+q)6>nv1Gc=WH;tYl)=eFu!9hOY;laQp&=&{`qw%~%Smh2-w6Nf} z9jy)nOs$)H_lGsJ1s_)YBtM?)WkLcZTw<8;!0_-J8TNGSR|o)oeSIjffZambi9fJf zH!dDt8m=9Pz7nIbf1d{{&UqN3_P+_Jmqr0WLA>1DwY{b%44|Y{f<*Kw|IH;kv@A~$ zg9R72R7Y}JfY}I8N~`_-Jxhaw3YZ#7;1_g)v`qk$JXcCngw&ODwFl}1s4FFPg0A3j z5$7>)nctuos$=FH}|=6#(66?U|Yy?QwRk0AWH7vRwI?t%Hiz6FjgAmOn`(O z$Qa<~xuIfVb`Fm5g@sTk$R`2!mCM(dwH{yWn1!EtB_wX|B`astfv0Lin1;HCgoMNd zO8TL#gZ+I30kj0vk|LD4DQvSlYqLE$Is)L0^{uUxfL+Vn{ywN4YW@A_=STBnKnh@B zCwkxO(bXIsUPcB(HX-C-B_x=r0*T;ze0&^1fMd~ym+Amc^PVg zAc)ux2MSEJa&&j9msnU>C}?P|?W|6ZL(1$o_T_*T>Z?xq&Rg!i_p}$#Gw>XGd4@eX zyywp|0JDW4W##2p(zHwfj3am`L{fpq0qlG2_qR-R-isR^yRT7@1>RmzT-^9t;t7Jl z$lrZ#LcR+xcbc8~!*Q@Po6?hdh4_CHAMqC-9S3r%xStyN?7B=FsFdcdL1sTmCT7Pe z<}A2UM_%hXig8_jEhB^#dO=e45g;)}@$I{JGak#pflQ?M9x~8z$$L3!WiTjZiXUFh zXx-{R0Wku$q%r>dL!7#LC?PnQ;c@X@Sa$*-nimR3`#Sr7o4K%JVp;(K0agl^942tE z0^D~?tj_>F!RK?Zp@+tlzfgTW=}NflnrHv?=}D*_qtPcpKw|>4oq)8gM8Tt(D8+*i z0BsQEdg&RGI6^2$FJNeM<-nV;c26s)Cza^)5q2PK3`ks`@-o_%H~) z1j~2=QaM&wSk27Li~uHZ%+k^_DkkRi%a<>49v+|Rl_5uZx6tC6b%?+R%a8U3y0zN}aV*s-y zkZ*?K^`I0-Qwm(WW@h#leYvgW(f;ytz+625gCxSE^SgfiI+l;`8U;@SEM5aZ(`$x? ziBc|qV&;C97iH^Yg#%`j>2K)o*Rvj}G%)<^d>z8vRdzWKU44Ch!eEhQ$iRSpq5Zg$ z_J6u(#wRAyZML8&`Z73Z@WHVBmSLrv_QG)K&F$UY7b`3Fz)J)6gp#-LK_IXO$KeNe zALF(Cq_q9k7WxPKZag181R%~_w6se5TQ#ff*yBo-+smcpCPexaq?*X>|9&1xu}!Ak zn%;XtMM=p3&ebnnVmB&}mi@qfrOQ19LKUN!DCGcq$Ec{Lrsl9XB(W$B=6MpnuxHL( zr{D>IR2?sA^IG#)e%0pd?Jna%>_$!~RZ3why>>npeEM_( zsFMDi(%bLvU`0gK+2{}lsF#=xS$F`uokj?rTT4|dm4HZ&Ay^@y8?�(K4Q`l=t2x z0G;-S9q@2UXYnIQhVk;=pF5=$_E-E@*4KNh$+$~wf9-yWk4LJpu{Q`MHYxknmmXmo z8iJKV*#vM&GB?Bf^F?t=&vG*OgpS7}RCPQiZG7Mkvo641RaR92=b9^b2S_c*zE~NV zyPhAQ2oW@{uH1A1ln3?8gNF~J;^Lk|x=IBEA>(ohP<~eUzLfXw#b^HhrZzT7^HtA2 z>6F^uw;2S`jQ~@)|7{aMX!e?nj123>pC3R)_-lGf8}GG){a(qvlX18BF-m&Kqu!Tf zdY6rjEh+vO7D`9Es*RICM3R74EQ&1@)wgu{*c28PLe&w~S!ijTBJD&LEpW3h*n6%! z?I&5!souw_mN!jCKbK*- zIW7F&m-QiAjBHZNiEDu1J#uD$lZacssoq!r(7m;xoudm|)c`r46wD=Q3j#~A`Q^(M zdLxSKjg`#IP6K5AloA{o z+Pf(@I52=jUNAI%3$!bgK1?4!estU*n#oGq2R!Qjh+P_`Zs36v!21l52#Jf|+AFS6 zKiJ(!yYoH@7~Zk5F|X$B$}-HaCvICy_Zym;9zYc~v>U-G_d0)f|KPv@Fn!X)u4-E- z8No0hbjHs1Jp>zAp1;21ye%eX87`7N)wSX$Y&=>J z*riC+MSlP-(wn104kOn?ybJ?E&7>BOp`fJfVG;iX=>+hq!%PRuK7{4%?a7Fq3Rk-r zVLe(z%%bB|N1`+%_=AeIwMbJKTM*R8lhHTjF^HR+TP@%WAkXTcmUp(GSFo9CiBeTl zy9$-(-`Nyj)WT55d0Mt%zBm<>pD(H_#6-&}O8|DJ(q6F0xW;EF{{U(|Dd#zQ`Q16* z_2p46=!kefx`)z8H9iMoz<^oylwZW20&7OTK|B&r;2sQ@%%g#vhET zSb+fg0;z$4gCh)hvhfhn>h9#p`S}nC{1Xt9%b*M3SIys6f3R0OR`*fXt88J~lZBbt zr2ky1=~d|qWg2W_-}vgAuH&w~%CS?rm>J9{K!wQA`T8Dt`Bv9PE57ivw9J|TEcS8k zTV@Cl0`ve>)AjO=hA3&3TAmm{K~`whgGH+lYa5$ufL|H`gS?kh$-NT-aa+6E%N@M_ zEHHoqz(3}G?*yL+C@n38sMnofzW)I#4v0g;RDfSlun$3^u`z^s?T4mOvA>g^;p3$o(&?2ni4rc^8RfZkCd&x}{NX{z&bgJ@09AYOg`hyU9g(q) z4)wpIM~8ZlL8t&jj{p9B27tsl^o{_x!?!V&>dCSOU?-Y_C#V+Hr=WWj0__Eg%v)#v z^yLcEa>;+VaDMU{qkY`D`$BE6L`4@C7H|M88^9E=l{-#5cR~t_u=-h62n{YqaIka$ zfDZuh3~iO#jh_2YHwXIxa#BRZ&147W{!y0bc$wRp3)xy%2+u|ue72UNTX|xIkNtIf z8F$^xtYtIb_>}{bNh4AEm$B3IJSUVWOw)gUpZZc?4;?Xnb}4&B&yKb>Drn`k_RoI* z_HArp;u#$>#fMVe2M4Rzz2||8p%nsTZbmurDyp4s_^qC_gkCwd#~r0wOmnLh^egd`|RSk zyWw|f1bHnPyCrq}cTdQn&zoaKHRRoGZ8t9CuH(wTCR`x58T#Z0^grxw7$huHC@*&`ikoia6MlVzj&(|75(+7epS;t=2cs4eL`cNCvW zMkY`iRtj?6D{b4dw(%P?Nwv9`dRsW5;O?p4OME=|b?32B-|7CeJMBTrywSJG$)#J* z&6<8FBdpghFxCR&2_dhpukYlQD_5X|Qfz#|v?hBA`h|dHhx(z1*+doHVg{hh&!EVH zM^26ddWc{2jJ*SSu0D^K`EXqL0%MuWu`+iZc>#fT_S3w?Enbm1SvHX{{Z+Q0q(E{w9Jc+-{JN(@$Ip)V}f#BH? zPF9J?gN5^9m6BAXCTYltljZHA9$gcp%?*>6vjW__h-2Mm2Gqid-S_eGdv|?|hc}&- zhecNvf+JR&KLp`{i9+KL(ATH=_)NdOy*TG@$<|_2*~WwmnzV z@9Aemh~{T^4UITVcmA+fxG@Y=UXT0r6Yn~LS)eNM5k$DpGi-0@jrD2l40RgiT{)#i zSI}FJkG^}hLYa}#ul?2ZNb_qYi}oA$YJXhYJpH*$_RM9OHXet|_Xdl$WR;LX1I0UW z3)&qWB;w*JF>8DDN}GAp8wDRpL{hxv-^bwMH^u3-kSEXP0=hhC3IwDQ-q5j7YCNw2L zS1Nf~IQ9mVdb}#vaC~)xMUI2jF7sx2kr_&)V;lX`i9vY8J>=fbs{3hM;X4?GYJm%1 zk|^;;cKz?E*^k9BUR}a$KO$QBp;vp)ZhCoA;3ko&siPw~cXU>_)>si8URGJhD2Wfh z8o{M8MQ>v*V!y;r&%_t~rNVXkYHl2J&$nCr#pZ1-K@oIXImgFl1-Jr}_tO!RwQcSF zK6k#gMv|2?(6VI~HNpWg0yQ#2EU-tI3zlutC#4_%Ao}b|?y(+ueN@f!ckg49U1tMY z8i@|Gu%_q+RQAf7~S=T25-~q0_FX42o~?2jy3hl~uI2G92ymz6!s7 zJu0QBAhNwjJz3;cHcvXX>jPsgbn?d0HYc>K#+R1Dp>mmkb|}80q9W%iZ~6nF3ykp! zT=5sLYpxc2eEG)3Ycqk}T|_Kw=KAtzwzi|&kI2L%zc9Axg_s>&}&m3XCz+#!)JG$cxu%p(}e^T5u|S{1I}e4SpD zR76jgV(usGZMKRoL2O%b`thG)hVtsnH8r)#MjX!LVIN3sqN=S&sHs^`zshxTeZ?rh zyXCvV_XlZ7fU2WywI!-)Fn7{`NtnoRD=NET{Nr?t8q{a!ANLCC1f?-ScN&jJfXRr- zTCg5l>zY3B7Gk15j-9IvBP`k;2(Ygnut$bV$WXjlUP{xU&#AFq@K-?fms&%3Rd zZ13#U0l0z&n0|rDmAo#rgZKTNhX1Qq%m5292$YUMM)E>N9h;pE0(SQcXdj>x-|r&{ zQ3JZ8eiap$6O)p9KANi~0*prr9H(!nzrILm*_qhWR0Ka{+^0*QEqA4}`mTJ=dv=Ul z;7?})uYmU))Uu8ffni~ZGU~XuDwX8jgn-B*qOh+c@<&&-VV<=h8_=qFY6H2S1sR)} zc}~S7WCC@r;Qh}Rp>}$1TK~Kb>JsR%^!aR#)%in#-vsctxS5Rl6dsV@7&Nd8N=lk6 zQ@o!~O_?Q0dT#t71)_3cq>2stRiLz>gn9)AIhP7uFDch0v}NT_9MR9})YEU2iOZks z(3EhGDtm(B#c!zXez{0Kyz7cYht>U}rDz+Hr)w4T3y)@W38=D~Yo1$D!v$fca?PF*W8yB}qb`^I0A(86NM=067jt;iU9H*%`<-G_U9UX>@7l5VB&^Sc6B_&VZ zxpN1aM1Gt4kYizq-+6ljIEVffAl$oIc|aviKofy%_c6gJ>;|dx9Cx&WsA$6e?R;DO zb4QP(-L2VO51bjjIuh10VswZ(f2|_0(Ds)MFtQWvqBS_EGZPaNQI3`!8uGKULHkcH z$Y0C6g>D->yK^J?{h7E*ZjbN}B2Y<5pD9&mDQ^U>mdt9dgJsP3D0<5#l+6-PMj*r^ ztg%W_M``*x9}5fp?&kJYhlhrugvj4IaxSZg=`7byD4l@w08--wXp=C=-@ktWP$zFD zg5{3^x-R(m@!7JIhfH!|(;bu*<28ak0tQKsGbDRTzV z0>q=<0;QGrOEqorru65}JF-b4rxZpM!{`}+;*^E8{qpVGap<}Pfa5`}8pJ8*ff}&e z!A3ujSND@fYMBkHJS0$s5wwBRfPpwA<17dpVe;h3F$67Uik~n8t@qq@)SDSic2Gq* z?5vu{cvr>``5vxuRqo8Z0o@xZsG zSLZ+rLuL(}c@i)&>Kr%+Fg`M7W@e!FP;O|p3iKsFBVwSxIAj)thk%YYq(Sw8wn5c7 zXqkAf{dMJ+=cJ&HIVK;$dA5J&LVN&8d2`;~vzC}kkIibE2pz-!fb0mdD%l2@lw#(s zG@$o@R{8=Z**FwW@QMjC7t@(Nw&~}7sPX%1ylLx{_J1v{!|!V|EWX2w^#?~Fi;ay9 z1c}ZhaHr4>Q3As$wD`)ZfA8KK^j=np8|T&y--T8#ccm(P?9V3_zSFWAK#9JZ>I1m@ zN8bI*pPux00;SK?5}`n(_Npym?@1pr-Og54C+&pqQ0JC9WwI>Az=9F*qi2wt{>C?U zuw}k;ba*qog;m#4yud72#P@HY9~&?BB`U&{d)I^blM`<(w}+P<9rja%b-od>lk!@W zD6bP^h++`KoW^=sw;mr`F)jD(+!}4qb))$+B3E8Q&Aoi!St-xY5S0cQ083=QBQEyz zgNO&dSn`}W;W#s%M*6xI#-r~z6R9m({y-D!^bOYb!NqIko)tvqDJe5*xn z#&egl05yO7Fyt!EV!2`&f3SzScTal#NsQsbu-!Dheeq+(u4HAaNWvT?G#||RUcQ_< z$AyTw{P#1oehh-i$6QtYcm`X^)7Wo~=r}{ODeb@HStVYED6loIPCM=}b8)2_EAUF( zz^#)oDhi$8ApwrqiKDBdqxXq7?z#QKsg-&<$JND4qo;Cs&p|eqP>WMI`dND~l%8Qa zjFNjgy~he#C>Y>GLD-XqwmG4XhoE5{HR3AIOW^2fxmxomS+zAK?xkGlAz{DBI`*5gaxX86l@Hz~ zcPvzu!jIg5E_5WXs#xv>slKrY7E7dXxXoLAuz3%9B1|gb>~)uyD~UlLwkQqOR1c|7 zE9Vv;aO>kRKSD%AGsK)i^Y)Ya@=G^ZEiz@>V)gZeF^TF*xWL#)6!>pxh|~TZG}qE3b3UW7v7w!$$Ii)Je(Ng1nO6 zL`C^QcVrR>6$&aUB1HE;T}p7b#+Q6*Xr4f7p;^&0lW_kSu$+Y;k+Vs6J3916#caZQ zc{mVeVNh1T9unr?U#_F39r5Rfx@K;3MWwxc+Y+mXn5>#XCtZ~$|DM3sYhfKSxBUuG z5L2lm*HwV^fTmKUrK4VrkN4s{v?peEKY&t8Q*<0K1@sXEp^s=4VQ}wW29()^@bJDJ zYoiSYmbQ+B+FuolVXUa^xWNd%ozEFo{FxABFhQPdNSG;M1^r?HLL_Ix@9Xs`O zVZDM3+9QxIqLk8FwzNLv{NEPH6;)N$ye+5WwfotiVz9Qhre|TH1f~~JymRNIX0mLs zw(>nYf7Skm;Mxoo$7Z^W#cF;MF`L&SzUxuyM8O1g0(6kj=wW3gh<0dNIWp&m?T-KBHc~ zAELc5a@I0YN(xEwdhk{`n2;O+b}w$;cA~7Jf){KK)RNEMzZV8EA|Arm)r_7K*?BA% zEI`PS>U(skdh@0VWE;>X7ZFLXX8V>Hs62 z<1d)^?f;XGnEMc{g6p!J8%@YifpWflV6EIqapRAN9oDX9pXk$L=y)kUz-r|sMzQjz z&${=F+Bww)rUqv>Fe+^xV&Kh`)erFkTZc3(U#21mFQ_42=uU9Ri+CcjH>4>Wtim~> zVr5nQLA`X9FEKe0lQ3(cDK?!M0yd6sD2n$Z zd3O`p_P!IZ?PMw`n z`)}l0#e>}DszJx412!po!CKatKxPJ>lnPh!$3I}2INVNsU@A=mY>A%OL+ zntrk&C%mBJApy6*1JVS-9a8iy(G5-o+J#@j{Riy^L`{O{j7WTTug3|fi~W00Gf6kT zP0nadSb*|$`m7U(&kj51u69=WLR8Vs`%wDW*tUtf{Fmz9rlLtI`p#_%OC+}_cJ5y{ z1T~1Ta62K2fk_maSRV5`#P}jhKaY(mlAm){sdpu+ZXZ0*%Wt#3Agp#ycHnI=x@*tI zG`SZr7pZ{$t~zw!O=sR)RonTQ5yTL!fW*t)E}+MbaD4b=UCr8_%{fi3wmv)ej_+kp#E;JlLRI9+>S z4ze3mHAv$`qRcZk4}Vo16EPBLH}=BVHz_bMIsChVll(tDav5h>5o2%CY+c8h z>&@Z+Ht+|e!1Uuh!fLcfM2c3~i5P3}GjR;bz@7@OkqkQXLJTFgv5bncvQtC8%0*TT zkuR|o9G>g{);2#Jim_MMMOn; zC02}fL7#WT zSrzw|%OV8WfjC%pP$On#$pf7 z&%e0?t?VEmdD$TMb@cB*PHbsu>8{pPQ@fyRg^QsZE+y8>Co*qCy!Tjhw2N5@gvjZh z4CqkvNL}cMF2}Y+a52j7)@m`0l z%p-sjtwqLW$U;w-%>f7z5o+PVjD9Qjycciac2U^`;LM`KJ)4rN zwVf46xlSE*br?{WcDf`IUc?2_`Tclr?mi&KDXc?&5G)3#o-d=$LqD2u?9-_qVcR0SVt_jUTm1Nwvt`mYXGGeSLfOL6?{sbPWtlY;>H6!ag^Y{A@Wr(E@%|p3@!| zQhaUyeIn%FC!mbT$x+O_f$w>0mneT$Z?k)7Z8i#}zL?t%S zZ>WO;S<%*{Q&BFv7wr#aQ+0`|JXq4|cGjkSoM>1P zyXr>)WPl0$(X};ruh%}CcORptM|>&nC6U)bu}INY1mT7hx;CfHEr}HlPPZTIv8C17 zRb#$=!{047gD#HlvwstObmUXMnNo4NJ1@zPO($n+MHC6;vU?l$9G)I@)W)D46;nj( zG+M2!zh?&}!P5QI8%$6w6JG+*S%{Z%PM)%{^6*vsNS2+P04RxpW|@vn$aarOdKCQJfM+fxdbR&S_e=#dqLrO zlZQCmHF7l8-pVt?&~n91`y5dJ9Eeb8BWsV7_$KcJmx=#f?)wmR86OY;y)rUu)m$6Z0P`^<7%Gz$n1_gLEk3Dz9?p)z@=ibNN=rk_ z!)z-wAM%&FiblSsa&yOMykRX!OB|`G^EZdpvv~3E?#>mv6nT7L+Tm>(A7~FD1)oTo z!X>nLakxfw{ls&~>8Ab@!Gj=+-||<@;Q_|jm{<~r(_Kevyy&5F#xh^y8M81}mh7nS zS$;&;k_o%jCiwe*WE`_5OCE@0vU^Jp>q_RWlr z+oX1|=KT5EcN!mMeJcG}d9Xr8u&hz7`};+PMDILYQf==OOB`na!=E4efk$r^{daS6 z^1+kH@lmx`c!?)w301y0++Fndrwub`C%31!d`rjAt~zS^@8lqWh8S`%5;I*$c2QB{qVvCo5gHLg!RXr85`MP7 zsJjsu9Cd}z$Ms}8aH1hbG=H{jd6azSYxH!1Snac;1_p-dz$2OCQQ9odo6Fxa9f?#k zZ;&M#0op;ySZqdc1o`1UBWx`YC~|tqQJDYZh#t0hLiQ9IN0p0ws=RCmkFTtBJ53Ag z5nZxvahS#suNz7;Xt$!S5Xvur>D`;Nekv*E^iCv#g;+55-`!?toK$u=l%;1P)xSsl zt75)x=^ZVg& z>$fbbG?iv850Arn4;rZAnz(%T{eX8(5EM#(X}M;x^Rpy3+36EBHFdHOa`Lh0o9p`L zVL2@ND966{K9-QQ{Yii$4ZMPaExqIPv4U?TTP>^d4z`?^NB5SALA+e(h)sX_6&j1# z*@AG0X&e-*s7@Jx51i=wD%CYYaEB+Kt82ge! zb)r@s%9-2z0@g^rsG6J}K?M=J>yLo7WCy8qEqa2hOW|nB-4=%%z!q&J(V)c3MCYqs7^y4d4U<>RAvokaXt;=#|i4+#V+KL{Z#0VB-5)m|*y>~SEe2SBZ_|+Y-~OwaqGYOe2+)BF5(+qo)N?1rs{hAoP5zNc^R+-nVzj z^;~2WhJ+OJ_04?FEi4vVYLSHXKTG$=UKyJih*FN#91(>uw*wF8c%XpA3Y|bl*8{-( zSVF7xoL2FFoI?A5gcUQ10G!fttZVTw06%*gTLr=RNBczA@87j=uS2kv^*kaF)&tO) zX*?DxuuBn{H{ZTwIoIDvIyZ8kjtQi`wdlZB&9vOYYPNk~v^>I|+gh532>#J`M7U_A z{3Ss(9}R0Gb1r{p0Sz6a+TA6pfBrj735#v3LvL2fB-&hvnpP6PCnVH%Bzy!P#TUEq z2%pBLXED7wAN%RkCnDb_!%J@b;(_-o@G24bw%CmVjb%Coq(2XnoLrlFWtSp?KuEr2 zeOwWgwt`e*#9C=uW59K1>*l<~WMI?TZ;BooX19JG9IOpx`N+;nH86BiMiPttb{lR% zP-gB%tkA}{wE+6L+Kn%S(3$b8CbOCb=hjz6*)9?N{j2!x6%w`dqxz|d+B_MqABcr>a9B8ih&jGBdcccK|0#7Woqje(#bcG(Fyy@$lgO1PVs-RM=-q8Xq1Kcmv_@guHnjm9T&to+XM z2!UlmCp-pcQ=E-}DhH@7i=Uq~dImx+sQ%%=IAFjihG~(*pBdyP+VSTDq2IW+GLEnC zOq;}F(`UVP0n+^MzY8ENd9@ZaMnlb?9(|{$r^my2(R~oLZ^JnmR2Bri3KLMkzoU(9 zu{JZuC>)8j2eKZ@d7O}PBq=D2Qmdh7h`Mqnfc{JGl@q#fI0qG+^yV8I&u&9+FAz>? zoOJur^8SXJnm?R@gCoA>a~BgbiOKPjHfBM;!q@@_@=Cou%fngad1QrdVGe>KORef#?1T~u=+XxTuN;NRSyq$fmn}=a~!?|^6at)2}sG~A5`^0 zbj{G&%9Yy$)v;*a}vZG`DujOnC)F|361KQMO!IKQjWw}Okc#faG{nrGELuXwY0sYY<70)*-M^4{2g1yDbVUUG0s;ehE?ztVCsk0z zH4w+BTo7czPVYgaP#I( zRKdG90&OUDrjt@J4g2;3@D+gLl zV&w?VFi5EhIJG1Bx~t>eaud3%=HBFl<^6d7Lps;LE*z-qYUEC3u! z^zS@qrakw4C4yNRA^qyt{a1NXR0v^CcnNW7=X6n@8(M0w!-oC3DX@}n77)D zA|?y^wN1+T4iKg4nA%BJKqL2#*01G*;b)RW89o);3K!wAp#HpAVU<^Bk5O}4M}h@r zo4n8Z+l zc;f2^-{trNYL5;^kLu)8Ja0~0GpXPLofcW`_sf2M%7E(1ON(OP*K>=5^ICbS!+u3h zKx6F6jYTUB%QZn9ms1rnMaT&ThF4MWd1$2S zb6jaS`>SVVd85kLu9`BC%G~oD14Fq}`OGOr28U{$ERzF|A~3y^$z>iA)IM$DB(F6nM9BShfFA`XGcrC_BM~$2zLHUfi#E#JIoC=;nSU z-$?o;9E4d4r&45S?cQ07d^%?nM^*c2q$ZrBXuw7gi|tG&(!z;4v98Uz$7(_Oah!>%5o8GHpGtwIhwScL1{^=U%c0S5>k)_h z(V;7Uiv1Kt$7}PFy{)cbRV?;pnB&)2MaM57Beivt_1<-cAqPLZ2-C1$ED($(6i-Z; z>^K%B{U)++pjZoyQsMMtm2eb!Lm-&Zl`diS--A*Rq5A#t_C!;hh+oW!vLl~t{qu}B zrQDCd)07zgbHK>Z%JlOy`HBZ^kU!)sZBVLnx{di!mtNP@F~K5&4O5=9fiQW`@m zcEcqJUSG1cBNM4z=AU_VUc)((ZXiaC@JbLL;C#r^*-{p0lS8-ucPVt`q|c|RcDAps zEbpv|IiwFRjdEF+u($JLv4bk4+}-6)mLN541EuU4gO5{ZOXr76Md4`f?@~BeB7Hvd zf9}jmQF?%tU8mn)OOZ~7jr$mMj}F83{0j7R^vmpdp7ed-!D1&$hWB=NC+6qp-#TME zUuBMumPwtu+-LoM>n85Bp2Iwmn2^v5P_GujAtFGUsJsDzIf81(AW^fS{G;st-p=ey zw2&_TPOjrcbnQe-If;_ROo?DV7a#W$K);bS3Ms|XGqXY0gDPdx0=l%r$Q zeZDF$2vawNkZY&Cw@Z}*)v1p<6DgY`t_B~cXZaoD1y8NgMP5*>&A!?49o}=@5Ta(Y zC>ix(bG}naP|bTwq}A}Xv9az2lf|Chv0C>vsP+YKkr=u2H5Y-Ic7hpC%!teF&)e5V z@>o=;(5-B_-jHWtX!U^+e;U3E@?}2zEdCS))w4^Z9e)jBG$$CXtZ-mJo%V>83=Iht z&gVlE;f~^e7u4yF&KcA8^h7EsI4}PBgwF56zYCvQQ;wc)U&`HD-su0zsEC6V*MY&` zoipl~n(CVGtJ~cen5 zmlJWMsRXvy3ZsdGnYQ;S=xQ33E1uR(G@2A$8LjRN1s{}FM?cZlyRzJ!Hsk$9QY+6e z+!AVsS%^Us7MsgK#y;oi<}0QLYsl$d_aBhX^>;mjX*EcrFPb3j)Ul_+6&M+L&-$Wu zy!+zl$+M}CZ)cgq*}_?Lxs|DT8S87B!|OT{EGm3`v!>7|-$E~>XME)u^V%6}6|gJp zX^EO40ZHA}#UV{JE_9~BPKLeRIF$Pf=d#QS>VAJ0Gk-C7XE}wSnw$yOGzJ#MT=NF2 zr&pHedLm;;=oF|mUQ3;Y#gux5uE*b+qq<;5tpaXv5f*FvaU!q7a&WcL#3OK*)zj#D zV{NueHP}`*zMA+uOhP~4Ki%_PhfEAnvTEphsA@jXuaO*Pp*=GCOp@aBxMXib2OXU= z3r43AF{Wh}Rnk8Nf61kej8Wh&((@VUG1_i_$ea%z?bB^56IM5KwY|5s^e9!_N&?f;F^Tjnxm457>=<3?pj zDU>o~rVM44c`Rj!$V`Mn5;D(YZ88&*d2jPP&)cw_^}Odg*E#3+$M2u>{_(z-m;LPf zxrcSHd)?plSume+p!d1M-v+p?@w$$|6rhmjF>pp$wGAlvRj>zhu`nbOxzWG zeBE-+nV+15luCT~{(Wker6o&FPE%3nd-vac*=y5r<_BM*JhgMLRFNJXrh2+&TEL`P zgvs9GA1fTFnaRO@g3b3(n7`NK*wA}h*uWp!E`&V(M(>w|T~_JCr?#`8meMKur4OhX zEk*b=Ln_ibDPKaDYF*9RPa`d4*IXlx7MO2%2%o-#d|I@~LgCpr_rbE(m^?iiRtot; z6dT*jQyg@@4f5q?u&LWE9H}Pmu2#&BVLd-G-Bwi84@LU?NfYHjX$QI?&!B2iYiW=K z=kvVuV5fu|rd>HD@?I)KBfjcrqBmqlWu|i)PK3J5JcITVHRQ8L;;!)yPY}h|G!Y zukdChu({s9SI&$=bal11?(EEA3dk*(+ZEohw3tbKj-CG&%l{_lFC=H&Vnrfj>r z&0Mihpkw>Nv~tJk6%dE9ynJ=?lg;pRGBY!iL${*QI{5)>twyBp|NRqH=IP}Dn#05I zf`?02gTf`6{8QY17Fxp#d_Z2nlvfQhHWQY&#&HdbdsF9%M)OkKmyG}=w`keL5gFpW z{zj_NsK!I%)6bGOQM?%Z=FGNFZ_{fy&k+87e&O&{Nj%r3)5>9D!`}P)5*Jb-gF0oT z5~W{e%L)JvZUF)E#0~^|kQ2roY1J0{qri-sgSx-eR`XiS4)?D9mO)_~Yr4bWuork!VBGyYZ#z zA_?m#oQyo(&C431>72F6wPL}RH;3Qa6j()C(>N%IV?@Za70QXBn;;4Uo?4$^S>?UQ#<|dVPA`0hyU(rQv-W!;Zk|jUx#z8iN#SbHcH>s-%GD}7&kQsDia~Q& zuguEawbm1HpA<4Ei}Oa3eQ61|#Cd6HwCUK{)ipHU>#f%Hk;I>@t*wOwoX4yRBk?Bn znJFJYnRUX>Zmdo|zA>dvzIr=01Mm1@)WqV>7Ofn1O|;J7P|&*~u*08p7Y=JJLl6JS zy8h<<8AaOA`r%#~?}1&N5m6u61OBS6CG(LPhoma6Fa-uGQOi*d(p=_-sOjV`j+Cb7saYD_A2AJe? zm=mq$xu?j^?xYLb;lpFmj|i6@$3DLuai~0fK^9d&tv&`RW zyMD@>H~spaw@-BS_oMM#R38ewN%MrfV`x3kpa@vPAHMtk?lvGNz})RuqAwQ{dC`EL$*#WH-?Pn~_6d>1FjDneFg=dypQYeeg0Hf{HWlxA8(s%%OBp%2hDjJVbv+HOB~oq2%}bGYp+k-B{}u; z7W<8({d`;2wau=zHO$O3mXhtY=SqRJX{oM@J<~^e*NG=TTehC^dL-Gm=I59&hT_o4 zW!km(-pam-e0ecp)I)rGH7jLuRS@?6qq0P!(~8_>DtGps7UH%x(XfN8g1x-jXk>ba z)6VCZr=#v!XUpp-7~F}J1iTDZF-Y7 z2;fp6TLZ)10>7l^-|7atY%QQbt&O^ZACw}e)zn7s*|nVUEBgH1y{E(|yFRawIqkG8 z?aJhf?rZ`Cj_y3A-tP}&SOWajRHa2dCM{J9!GV=1lY?eT*h>=76=ix7P7QGv6xvVP z4BxD9jD6ZBWYpx<5fWm=ec|HEiIZ=yZe}Hj@%Oeb=+LfRs?W(Zr_tgF4VUn_+eIf^ zVLwgGE>6(k4Fo6l3)^)XhO#H8mxe72rzZQfUmhKp5WJk8*7?MmSLtc9YP)+j4j+2{ zsJpFlJ9S)^VsK|jJdTghGhi*QjK1>f)4dMWWeNh$_%ng|4aQz4>8|2bXVxi=hBr*4 zIo%pNQ^maAvR-WPJ9fHG@KmbyM?-Qe=@Y_K{RbsaphGqD zsNNi&S>NyJPgrX^aaeuGxIMs^ofaH4Li6#Y7sCtsh^b=dMaUv_`cRj4>yu^A{qj{g zC!zRziK$wG*<9EN`HADy#wGeCbWPMD7N5}ljMV0Gae=hf7q5y*RcWDxf9jjUz3z5N z%L=M-bLwUsl?C`I=??|b%p8#kU+@0hPp@Bd=3e5=(1hJV*7BcybwQV8?CtxU+*CsGep301S7$EJ4Qy@jd<%S3Cao2_oiiF`TT)51_VY7?4u1Gf$hqL4C-1`{$4U5oWY?&XF-K z8brD(IctwRE9_x%^0C-K=W>yBY>>(q#Gk(bF7eWHt`N{07^IL&)27pINjhUnsv5*vc9|_{=<+pU@+A#;)N#&rF|g<>Bu) zb5Y&&yk}`DWRWKU*(hGR&)Rp5=>2;XyRWs-Tt5|BHur7pMJJbzPoomc`OGey*@{<= zTISt6roxt7ziE#e79ZYHja+UiPQV3}r%NKu8i_;(^om=)`;t+SIb0>L4O+~c=GYxQ zwLGNDDy(U~oTL=^h7}$r{b;#?LES52Hbj1JGyVPAt8tbv*}LJ>vfx`l00!x&hH;FD zcjchkDmaW}=402_9FN9(6J*SL987M3xzJ|wcymepu0zO#@V$H^k*j(g4FT`6hBG&g z2&=j9kjM+ji%q13w`1$z7$xm268>*L_m@RGc@aMX*jEll1#%t!=68P%ISzF!1 z4E)!YTZp}kI?X%3p}>$m85A_q;O(mrQvM!W^TRffUT|zYP}K9d^J5!bjc-($+RXH- z;jj8s)efOhUoUj2zSyICYHOQ2X3E)2ZUgA}n&;xU75v`?h{j03LC>@R)C2TFC#a}E zqZ$-a^%q4-ZVzgQ(|SB>Lp}YdIjwBw6vC!vnJ}T}kHGyXIp+h^8d#MIx9QJ~!T;&q zHQb~;wY6kbYUFFZrXvP?$xOB& zU#TCwEQ;&uInE?#0VWgNCXI%hPP0E_1vOIZOU#bdlKj-=M71ed7Yb{9Q*8Iejs{9y z7pgJMx0Ju_wfTi-Ql-cfq)_L46PjZu^#s5KnSv{A8j;RDH{5T%yG*7OLhMfpXSf-w zdUdpkRjnRVjf2=|tSd>XT}>_dbMd>4I2$o?yXMW9l&1QzcdNMim3%!`I5EH>@{!!p zpXwF6mdM|^%n&(DVIX3Y8@ZT=m)SU0?s0k}WiFfl<2tDXQ_h6&Ic2#kksLUV(&UlW z^xUYNFbHhJtDLdutf$`WDIjMe#&4P#E_B#RcoG)+io}eR19I7a$;j7|)E`jbEHox> zTqaz}vV8fO-0B&@e^;+By!Uh_Vo_Jrpdlwcc3$tfebrhXa%aod#+2bcWD;jS3J{vY zl(6@>#z+~;e(mPKKHo}i40cTE|5l@1GSL^L8m20ouB4cQw4=r6kjA{@$}KnEyC|xr zM{`4c`uP1tje^f5M0w!4uIBoLyY^R;)sOM`GY#0MHfA~Us#B@U*{w^7TepvhMs3&S zl}Seil_Q5gwHMQ8Af7+CGQ#xi4~j=Uz@UmlasYk0L5VTohhGY*h~>uwE5#z3t!!M^ z#KQ``jd;IG#FOXd60UZ20cUl6+GSxJ4nF)2vElv>A4?n{KVO+53(c zx8K6-ZD2*7L>x$B=t=QFvm?q&uY_3K+V6J%mlI4fe=qWQtCeJKz?Q;T-KHNK^PXp5S98Qr5F- zZnHxo89tbuSLkDE_m*;w zRAB%r1r=Ljq}=8xDA+MYiMD17^>{&xib~@>=Oq3M%+-V%atus0tZ9#ue@o||rTHVk zq!S;PL>?|{t`$f>2M~f0x|V;j8BHX*FI1DFHoFIk}leKf&tgq3}STbZoH)ONhL3#m{MEmuI_7 zc>mOWqz|TPfyv~sEUs{Rj~=mviD1DZNz{^Gt9@*D31?fION&26va@6*#3FUJHKvF= z(S(uQNIt2_Tvpl35lyjTRUZ&1uEA3tdeMEv08S=oqiJ^(X%3sQ!+9D92AG|Nx{g=S zo8(C{kl?)3OL%_ato`(=mC3 zMuX0Y&xp;ba5mv;$D1MxBN@iu6}3TxS3^dBW_~v+yk;P`P{^dHe!Tq1nx4&{PvZP< zW0a4fkM*G$7mj@o3zIgo35lEV;C#ruJNUgsU2@zbg%c$bEsluESr@iWr|hQS)c4}; z4GAkxVJALZWIr}t%+|}I*XqcUnp&l!;!}(JF!PD%$af(eaadIpH?F|c9UN<7|70Lj zG+J?0QHcm*z>9z1M-r>cKJ7d`$sJ%KVtpji`cAm1yF3j=Zgu5#W0%n1bswP|*Bb1J zebU0sEj9YX%6g=AfzY}N)#rcX`*-iDiLc7zPn5rCK@U#uIXJNl1UDTirG$Q&Z~wAo z&?n(NsLty9+3u*;ZD7j?8$-9juNWTai4uX6tKm9TE?^(mnoBRj+K$yPeILx;_B zd0{TPq0%?3G8|&GK6^y3UOA%MI(uc@pJ6p0ChEWIyQM{=!7O4}B24DK^IHFMW^+=6?oFXr$gje`8 zJ&3R1mA^ysZ{ybrrTtWFx3>F13_G~lpMF~4@d;q)|*)lkd#z zr2M%=+QeFe_jc4a{G}OA9i0z_9^=1bHT4x93y*m|#{zep9r1-(>n?E)LQkpifO<$( zI6)In^kUK6u)Bl*0{!FSS0&FolIx_LQXgg4dDlGjyj<6G)HyzYVRf0w;kpHw`NkN5WzWf!ROw2=9!D~pFfXnJUxrS3=kTP zT~6qm?jSHA4NKgj|#^B&5w z2_Hz({Gd^5Pb$bmE*UIlgM-@`sY&Y-CdgQy=a}r0B56u3l8j= zXGRWjJOUh{-x|L?xKw+W*ly|0?zC`(lT zeo-_&9nzy}xZ7PB&RFij0WF*Cm+k~#PtH=Mz?Q=ntv`m3e-5( zIQ!sikQ6gUJ#XTClLV=lDh#&q;%jm z1E@6MBpE$;oN{n2io}12r)@LUe!RUF+`ebRut=%sRI*3PS3>lP3Ri4nN&H8O)Hzb& z>*ho4Z?gUVUecRdN!)T$$wBH|qv4pzrpArS65WL1 z4zhaCX+jDg#jkL7DnHD4D#RW^%v{ws;a$4Q zaM}BwYa7kj)$u%BoMhqOhUJj%WY$e|onQbNCrn=Z5|N1P^ zMZRF-C}0&yL9Q&R98w0 zlt=iW)!#8l&%|^a*i;~5t(}*GxG^^XSLDOO!!w~@1_>uUN)}PIYWhU>7~z7&(fq^5 zL}teRThqSZC9KQb-W5-iO3>bru=U%2*a86^a}BvVFb zuTa+Mtlg<~A6}eN=eypgDgNQeA-J+>Y+Rm0q>+?L_KDhhPvx~}e%IlC>J}@Abt-zD z|54F48^1FpX83jgW@*jNn6p1qz6S~=*jj4bT@MrPE-h)t8`l}X z+B|t~jM-kn#05eNucJ?#)jWIq?mceNixGQMdx^FVEe=dV;p$<$qSw~#irhWjCYR?w z%I>mZA?n2vFj*>5WpX@hbHytelk~UMyvPI-o8d{7*d*9rlJ_SWJldyib{hoqtTz59{oSL`+F@SrrfN zEEhc$YQChGna<#gEcmL~+Nw#zOeEY1U5fpNr}x(0eu}qiOQ`g|eAT6W3`cj|p-NS& z7!|~mAg4Pul@XPLE{+6GaI8r|-cfpei(*mXNFj?&>*E=v%l5v_M~Kno#D`EXF@)x2 z3cFxBA2mHPjWU&ratkO5wveLt4aEr^{`xeaaOg5FLD|H{17;W562ofnYgE}8(hqJs zr$1)JJh+C*kxAkZc7n_zupt_s6;F#>4_pVHC9_Z2k0-6_ z);K@kpIr21@YLU}4`{L}E68xJ8MK!8Ugv{%7PddiJ7mVrR_^4+4u3zoxmzw2>Tc0y zjNi`NomGz-KN$FaAZ4pVnB5T{PWc#Gy67Ts!Ke21DZJ(v4WGArc+<`D(#|$AxR4w( z-kixj9dpsOJjo;BN=ocFcn@ESlYX{Q)p%*=?cQsbC_btbq{Q5qJ^ztud*G|}M_0$m zf_I3+6MI~W_SXIC%Xg3K!-H%^!B)CUx4^-k+H7sgm{Lu;jmFe&9t?P!OC*Nd&D6gk zk*GHGSv?f1&b-jkDwd|3VE*t-?u&kfbV|&RU{&6pykAi+2a`SQ`qhpRA-5SIXu$~! zL}JUu-NWqxMCT!5zjv@Vxw@>LYRB=i_T`CbGS1(;B1aC&WvN~_z#pAhwdp)-Y&`NO z5$1QF0BSjF(1mKmu^hjjm>FpCrSxEtq8tQ1~Vn@{awnR6TqBP&gzJXVBrT$HK$cub(7NlzWm^uW4#H*XrA zbDyksXqygJPJ&M|1#{oeZ|jx`x7??&x4s$_iq{&}N=4ou3E9EH7rb&ms{(r)lY}jc zaq@`=l`pISdYuz>U9sV!!R?x#HD;^RPk!E3mY4ppQc`7szlPYvcNSti5ZV5_TW0Q) zh*wK6mWIjo%Zypq*^RC)`6%XScJ~~dF?;&BiM@#VlIldj`Di2gM5R%p^XOSz4n)K3 z!)DL!ra`cu!4GgXTvx6{0xS}#l>)hum_z*LAYeD|HIbSt8gbAR{EW`kbaS51-t#;t zI_MY$_oi#hX*YRT^~h>l$`#K7V|(ks&VJEqIK_R238^cA_1-o3rj^?Y zm<-)gYuztzFG}c;gs1gkz7?${ytzzJ z9EsN3MPUVxPF~>D8g#W~f5fA8VKBKp@SXgV>;6P#qdv#@BeCS}_;Yb;8sOnP=j^AR zV4p}Y=KQV%7bL4hv@|WbF!`EZ)1O1Rxo%h89Tne(WdSE;()WvMZuR!ywi4Nd&Lcn@9vpMCT?c)Pg zgSRT!FBitDQiYz-6nrpY+Gc0oW!?wU7a_ITI;=* zqf~sXd~(d7n?XfUzp>1-Hlx4QkfqXXE?_z)L~ADP7khW1zG_Hha5>w5`GkrMF$1hF z;w;1Uc^1Bna7KM*()aa2@tv@HYXXsa;EDX|C#I)qd5)GvXZfmoFW@wB3w)dt6EDt! zq7Ba2h^7thfz9FY2|t!I!5I(!u~miu)&Kq1>xI(SZOs`;5jqP!FMzEh+V2e8WiB_3 zMx3dyvY+p{hyp42QwO+fr)l{Hh(#J&+9%HBssrS%LcXh!nDH^F%>r5zDDCY?byl*L5mOi8EmYqHQohU(x81O-spb z6!s)kb+{8NkYJX_&dB)H=!9-+7yt7u_opA_igLPVW1RQf3ukQQgk6{Ms*}l2^N=@Z z24&E{9fJnZ^U-cDIUjRoK^W}8i)2MIOCya=JxW~Y_sK+UaQD1vZ?K`0dX7a&8Ph%@pjkdAFD99{+p zKQOuf0a|+bF4hwd(2dc3kL-TE|Mx21R>uy4gtZ4kKyhdSKp~J-km3&^J(U5&-sYhA z+gce-gy9)qT~*i7VT9r}Q!pCzJe{%+QI+rE+8rs6g!NpN{hXGD+}DT8?l1xbszCaK z>SIVh0d=$WP;oFQOCvvgXa!j29aGcKeck%lSV27mAPv7Lm44e+>9)>^WSjtC9E$V2 zjE`porLmH|eLno@UqEXlfV2(X)&l62@ZGh*SaAmmHG~4OW;8zs-bxw1MDWg3CCY64=bQO(R?5KpIXa?d zKr@|h1L`UTfWOT;lccm1Ur6~LwO=W8-!vx?31gF8NPk!n=YcX%ghC21ZW#bZoNq&; z(UyO6m;lIDETX$Y!@zLr`lp+31k@&mK7alU{GLV%+_j29;DG?CTKbrNv>}HN-5PTdB$wiN&FYnq*vbJ zbXc37c6^kHgU*H`M5fNPajsDC1PV}H2lnh-e;&JDsrA2@x2C4R=4O@b$%=G1UjQ3L z9hm0pP|w7+>?&Z&pqQPVvsj!f6v6T%-zBnIoZ11j_8jP~x@31*pq7DFlY{$Z)J1gw zrJDl68wlpu1wNrgpai{G9*RL`9W1Qu$#Qfc<_4gPnV={V3d*E#!1iShJiE&%I}^eo z-fO#0yFFPp@hu&HA@I}T9h7x+;^nTk+=uyJY%@%c5s4QudDZ9Oc#?vsDu`3*E!3-N z0S=3ujt?Y^!N<(+e;fG(>{tPV%4h)pYC=6X_|_a?L^%Rl3#4Kfs;jF3@M{W=TPUjx zy)e*9U8?$M4DPH?G-iRKhN5ky?%2oY_{cTnY(*_lZ@M$p*^|9@bb+7Tu-PTA4sXXK z{o*UE2g9LN_hphoq1-(gD7pq*mxrrHJXxq0NLi7G*;)wWGeg)(k_C!xyakE7UVOVV zQ@{-vHr;aj3&27LJrIr7Ek`Rz&3g({*BVzVd!$w4;S8PK1sgH+ezEjt)hxZTm3zHs zmT`3{o+}kipB2BaZcMkixs8%V{uM^F;3l=gJfZq~JBmg(ZLyBMtRr$N(iB(9Q zI|K?3t&sk}f=Wd|fS-X1j5`2R(jjjH*ep?^X20IY$2S8E*Am8;7WBAKvO%}nO%#f} z%r~_l8GW;}77o(==cuXed)FfXR0j{!X}V{g3S=t)yaoam^mnO^9sqXQfq9dFb}xjk z(E_*)6WUD#GWx#&_u6{6^c|R|UI5%9rUEJ(03JA=um=VO-ufe?H{J(-3Woa^6qr*4 zG&0DwjK}I3TM<1>J;cMbifuNt**fj84zIR$@j001r#TzR%?p9 zJTPC|{*=PMA+M7!5bp1%(A(f}=sT@XD8cMghbk}t4TH>}*nfLXRgrrb)DenPAE5jU zRC0lea);L=IF%&b);OTJ0c>nfUu470Pbv{GjG* zkf1^eD>DNOS~VP)pvcY-L= zoS=Tl+qwYmFW6pDfK~ITCtEvn(?nQjn!#TF-5rKBODp$0RO#ZDl1hMS=LlYc9*BFP z<*?~j`~v$1rHUNkdK`A*uSRup(3Fz@(QrQ^5=IeYzdlh=3nz7mkYg4A+@pomWde2} zDBJ?yF-tsveRbH@2oe~+8`j)`2?B6`=LdIaB9`DvRdM7mFoJq{J%j*|2y?P*lmN^j z6cqgccPe5M56^x3U;c)bG2)l}5C22s|L>ms?_VENwHtA^K4P1Jnz<;{Z6!6u?>CKK F{RijO>%#y5 literal 0 HcmV?d00001 diff --git a/ur_controller/tests/BUILD b/ur_controller/tests/BUILD new file mode 100644 index 0000000..e3faa51 --- /dev/null +++ b/ur_controller/tests/BUILD @@ -0,0 +1,12 @@ +load("@com_nvidia_isaac_engine//bzl:isaac_engine.bzl", "isaac_cc_test_group") + +isaac_cc_test_group( + srcs = glob(["*.cpp"]), + deps = [ + "//packages/universal_robots/ur_controller:ur_controller_test", + "//packages/composite/gems:serializer", + ], + data = [ + "//apps/assets/kinematic_trees" + ] +) \ No newline at end of file diff --git a/ur_controller/tests/JointSegment.cpp b/ur_controller/tests/JointSegment.cpp new file mode 100644 index 0000000..1b46bc2 --- /dev/null +++ b/ur_controller/tests/JointSegment.cpp @@ -0,0 +1,344 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "packages/universal_robots/ur_controller/JointSegment.hpp" +#include "engine/gems/math/test_utils.hpp" +#include "gtest/gtest.h" + +namespace isaac +{ +namespace ur_controller +{ +double EPS = 1e-9; + +TEST(JointSegment, InvalidJointSegmentConstructionTest) +{ + Timeseries::Entry start_entry, end_entry; + + // Entry stamp mismatch + start_entry.stamp = 2.0; + end_entry.stamp = 1.0; + EXPECT_DEATH(JointSegment(start_entry, end_entry), "start_waypoint stamp shouldn't be larger than end_waypoint " + "stamp"); + + // Empty entry state + start_entry.stamp = 1.0; + end_entry.stamp = 2.0; + EXPECT_DEATH(JointSegment(start_entry, end_entry), "empty state"); + + // Entry state size mismatch + VectorXd start_state(3); + VectorXd end_state(2); + start_state[0] = 1; + start_state[1] = 1; + start_state[2] = 1; + end_state[0] = 1; + end_state[1] = 1; + start_entry.state = start_state; + end_entry.state = end_state; + EXPECT_DEATH(JointSegment(start_entry, end_entry), "start_waypoint and end_waypoint states size mismatch"); +} + +TEST(JointSegment, InterpolationOutsideSegment) +{ + Timeseries::Entry start_entry, end_entry; + + double start_time = 1.0; + double end_time = 2.0; + + VectorXd start_pos(1); + VectorXd end_pos(1); + start_pos << 1.0; + end_pos << 2.0; + + start_entry.stamp = start_time; + end_entry.stamp = end_time; + start_entry.state = start_pos; + end_entry.state = end_pos; + + JointSegment segment(start_entry, end_entry); + double position, velocity, acceleration; + + // Interpolate before start time + EXPECT_DEATH(segment.interpolate(0.5, position, velocity, acceleration), "Time stamp is not within the boundaries."); + + // Interpolate after end_time + EXPECT_DEATH(segment.interpolate(2.5, position, velocity, acceleration), "Time stamp is not within the boundaries."); +} + +TEST(JointSegment, LinearSegmentConstructionTest) +{ + double start_time = 1.0; + double end_time = 2.0; + + // Test linear segment + Timeseries::Entry linear_start_entry, linear_end_entry; + Vector6d linear_coefs, expected_linear_coefs; + + linear_start_entry.stamp = start_time; + linear_end_entry.stamp = end_time; + + VectorXd linear_start_pos(1); + VectorXd linear_end_pos(1); + linear_start_pos << 1.0; + linear_end_pos << 2.0; + linear_start_entry.state = linear_start_pos; + linear_end_entry.state = linear_end_pos; + + // Constructing linear segment of y=coef[0]+coef[1]x + JointSegment linear_segment(linear_start_entry, linear_end_entry); + + // Expected linear segment y = 1 + 1x + // coef[2] = coef[3] = coef[4] = coef[5] = 0 + expected_linear_coefs[0] = 1.0; + expected_linear_coefs[1] = 1.0; + expected_linear_coefs[2] = 0.0; + expected_linear_coefs[3] = 0.0; + expected_linear_coefs[4] = 0.0; + expected_linear_coefs[5] = 0.0; + + // Test that coefficients match + linear_coefs = linear_segment.getCoefficients(); + ISAAC_ASSERT_VEC_NEAR(linear_coefs, expected_linear_coefs, EPS); +} + +TEST(JointSegment, CubicSegmentConstructionTest) +{ + // Test cubic segment + double start_time = 1.0; + double end_time = 2.0; + Timeseries::Entry cubic_start_entry, cubic_end_entry; + Vector6d cubic_coefs, expected_cubic_coefs; + + cubic_start_entry.stamp = start_time; + cubic_end_entry.stamp = end_time; + + VectorXd cubic_start_state(2); + VectorXd cubic_end_state(2); + cubic_start_state << -2.511, 0.1; + cubic_end_state << -3.511, 0.589; + cubic_start_entry.state = cubic_start_state; + cubic_end_entry.state = cubic_end_state; + + // Constructing cubic segment of y=coef[0]+coef[1]x+coef[2]*x^2+coef[3]x^3 + JointSegment cubic_segment(cubic_start_entry, cubic_end_entry); + + // Expected cubic segment y = -2.511 + 0.1x + -3.789x^2 + 2.689x^3 + // coef[4] = coef[5] = 0 + expected_cubic_coefs[0] = -2.511; + expected_cubic_coefs[1] = 0.1; + expected_cubic_coefs[2] = -3.789; + expected_cubic_coefs[3] = 2.689; + expected_cubic_coefs[4] = 0.0; + expected_cubic_coefs[5] = 0.0; + + // Test that coefficients match + cubic_coefs = cubic_segment.getCoefficients(); + ISAAC_ASSERT_VEC_NEAR(cubic_coefs, expected_cubic_coefs, EPS); +} + +TEST(JointSegment, QuinticSegmentConstructionTest) +{ + // Test quintic segment + double start_time = 1.0; + double end_time = 2.0; + Timeseries::Entry quintic_start_entry, quintic_end_entry; + Vector6d quintic_coefs, expected_quintic_coefs; + + quintic_start_entry.stamp = start_time; + quintic_end_entry.stamp = end_time; + + VectorXd quintic_start_state(3); + VectorXd quintic_end_state(3); + quintic_start_state << -2.511, 0.1, 0.1; + quintic_end_state << -3.511, 0.589, 0.857; + quintic_start_entry.state = quintic_start_state; + quintic_end_entry.state = quintic_end_state; + + // Constructing quintic segment of y = coef[0] + coef[1]x + coef[2]*x^2 + coef[3]x^3 + coef[4]x^4 + coef[5]x^5 + JointSegment quintic_segment(quintic_start_entry, quintic_end_entry); + + // expected quintic segment y = -2.511 + 0.1x + 0.05x^2 - 12.6775x^3 + 19.216x^4 - 7.6885x^5 + expected_quintic_coefs[0] = -2.511; + expected_quintic_coefs[1] = 0.1; + expected_quintic_coefs[2] = 0.05; + expected_quintic_coefs[3] = -12.6775; + expected_quintic_coefs[4] = 19.216; + expected_quintic_coefs[5] = -7.6885; + + // Test that coefficients match + quintic_coefs = quintic_segment.getCoefficients(); + ISAAC_ASSERT_VEC_NEAR(quintic_coefs, expected_quintic_coefs, EPS); +} + +TEST(JointSegment, LinearInterpolationTest) +{ + // Linear function y = 1 + x + auto pos = [](double x) { return (1 + x); }; + Timeseries::Entry start_entry, end_entry; + double start_time = 1.0; + double end_time = 2.0; + + start_entry.stamp = start_time; + end_entry.stamp = end_time; + + VectorXd start_state(1); + VectorXd end_state(1); + start_state << 1.0; + end_state << 2.0; + start_entry.state = start_state; + end_entry.state = end_state; + + JointSegment linearSegment(start_entry, end_entry); + + const double duration = end_time - start_time; + const double expected_vel = (end_state[0] - start_state[0]) / duration; + double position, velocity, acceleration; + + // Interpolate at segment start + linearSegment.interpolate(start_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(start_state[0], position); + EXPECT_FLOAT_EQ(expected_vel, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate inside segment + double time = duration * ((double)rand() / (RAND_MAX)); + linearSegment.interpolate(start_time + time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(time), position); + EXPECT_FLOAT_EQ(expected_vel, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate at the end segment + linearSegment.interpolate(end_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(end_state[0], position); + EXPECT_FLOAT_EQ(expected_vel, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); +} + +TEST(JointSegment, CubicInterpolationTest) +{ + // Cubic function y = -2.511 + 0.1x - 3.789x^2 + 2.689x^3 + auto pos = [](double x) { return -2.511 + 0.1 * x - 3.789 * x * x + 2.689 * x * x * x; }; + auto vel = [](double x) { return 0.1 - 2.0 * 3.789 * x + 3.0 * 2.689 * x * x; }; + auto acc = [](double x) { return 2.0 * -3.789 + 6.0 * 2.689 * x; }; + + Timeseries::Entry start_entry, end_entry; + double start_time = 1.0; + double end_time = 2.0; + + start_entry.stamp = start_time; + end_entry.stamp = end_time; + + VectorXd start_state(2); + VectorXd end_state(2); + start_state << -2.511, 0.1; + end_state << -3.511, 0.589; + start_entry.state = start_state; + end_entry.state = end_state; + + JointSegment cubicSegment(start_entry, end_entry); + + double duration = end_time - start_time; + double position, velocity, acceleration; + + // interpolate at segment start + cubicSegment.interpolate(start_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(start_state[0], position); + EXPECT_FLOAT_EQ(vel(0.0), velocity); + EXPECT_FLOAT_EQ(acc(0.0), acceleration); + + // interpolate inside segment + double time = duration * ((double)rand() / (RAND_MAX)); + cubicSegment.interpolate(start_time + time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(time), position); + EXPECT_FLOAT_EQ(vel(time), velocity); + EXPECT_FLOAT_EQ(acc(time), acceleration); + + // interpolate at end segment + cubicSegment.interpolate(end_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(end_state[0], position); + EXPECT_FLOAT_EQ(end_state[1], velocity); + EXPECT_FLOAT_EQ(acc(duration), acceleration); +} + +TEST(JointSegment, QuinticInterpolationTest) +{ + // Quintic function y = -2.511 + 0.1x + 0.05x^2 - 12.6775x^3 + 19.216x^4 - 7.6885x^5 + auto pos = [](double x) { + return -2.511 + 0.1 * x + 0.05 * x * x - 12.6775 * x * x * x + 19.216 * x * x * x * x - 7.6885 * x * x * x * x * x; + }; + auto vel = [](double x) { + return 0.1 + 2.0 * 0.05 * x + 3.0 * -12.6775 * x * x + 4.0 * 19.216 * x * x * x + 5.0 * -7.6885 * x * x * x * x; + }; + auto acc = [](double x) { + return 2.0 * 0.05 + 6.0 * -12.6775 * x + 12.0 * 19.216 * x * x + 20.0 * -7.6885 * x * x * x; + }; + + Timeseries::Entry start_entry, end_entry; + double start_time = 1.0; + double end_time = 2.0; + + start_entry.stamp = start_time; + end_entry.stamp = end_time; + + VectorXd start_state(3); + VectorXd end_state(3); + start_state << -2.511, 0.1, 0.1; + end_state << -3.511, 0.589, 0.857; + start_entry.state = start_state; + end_entry.state = end_state; + + JointSegment quinticSegment(start_entry, end_entry); + + double duration = end_time - start_time; + double position, velocity, acceleration; + + // interpolate at segment start + quinticSegment.interpolate(start_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(start_state[0], position); + EXPECT_FLOAT_EQ(start_state[1], velocity); + EXPECT_FLOAT_EQ(start_state[2], acceleration); + + // interpolate inside segment + double time = duration * ((double)rand() / (RAND_MAX)); + quinticSegment.interpolate(start_time + time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(time), position); + EXPECT_FLOAT_EQ(vel(time), velocity); + EXPECT_FLOAT_EQ(acc(time), acceleration); + + // interpolate at end segment + quinticSegment.interpolate(end_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(end_state[0], position); + EXPECT_FLOAT_EQ(end_state[1], velocity); + EXPECT_FLOAT_EQ(end_state[2], acceleration); +} + +} // namespace ur_controller +} // namespace isaac \ No newline at end of file diff --git a/ur_controller/tests/JointTrajectory.cpp b/ur_controller/tests/JointTrajectory.cpp new file mode 100644 index 0000000..bd0c7a6 --- /dev/null +++ b/ur_controller/tests/JointTrajectory.cpp @@ -0,0 +1,249 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "packages/universal_robots/ur_controller/JointTrajectory.hpp" +#include "gtest/gtest.h" + +namespace isaac +{ +namespace ur_controller +{ +double EPS = 1e-9; + +TEST(JointTrajectory, EmptyTrajectoryTest) +{ + Timeseries trajectory; + JointTrajectory joint_traj; + + EXPECT_DEATH(joint_traj.initTrajectory(trajectory), "The trajectory shouldn't be empty"); +} + +TEST(JointTrajectory, EndTimeTest) +{ + // Test that end time equals last entry in the plan + Timeseries trajectory; + VectorXd state(3); + state << 1, 2, 3; + trajectory.tryPush(1.0, state); + trajectory.tryPush(2.0, state); + trajectory.tryPush(3.0, state); + trajectory.tryPush(4.0, state); + + JointTrajectory joint_traj; + + joint_traj.initTrajectory(trajectory); + EXPECT_EQ(joint_traj.endTime(), 4.0); +} + +TEST(JointTrajectory, LinearInterpolationTest) +{ + // Linear function y = 1 + x + auto pos = [](double x) { return (1 + x); }; + + Timeseries trajectory; + + double start_time = 1.0; + double end_time = 2.0; + + VectorXd start_state(1); + VectorXd end_state(1); + start_state << 1.0; + end_state << 2.0; + + trajectory.tryPush(start_time, start_state); + trajectory.tryPush(end_time, end_state); + + JointTrajectory joint_traj; + + joint_traj.initTrajectory(trajectory); + + double position, velocity, acceleration; + + const double duration = end_time - start_time; + const double vel = (end_state[0] - start_state[0]) / duration; + + // Interpolate before trajectory start + joint_traj.interpolate(start_time - 0.5, position, velocity, acceleration); + EXPECT_FLOAT_EQ(start_state[0], position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate at trajectory start + joint_traj.interpolate(start_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(0.0), position); + EXPECT_FLOAT_EQ(vel, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate inside trajectory + double time = duration * ((double)rand() / (RAND_MAX)); + joint_traj.interpolate(start_time + time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(time), position); + EXPECT_FLOAT_EQ(vel, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate at trajectory end + joint_traj.interpolate(end_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(duration), position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate after trajectory end + joint_traj.interpolate(end_time + 0.5, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(duration), position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); +} + +TEST(JointTrajectory, CubicInterpolationTest) +{ + // Cubic function y = -2.511 + 0.1x - 3.789x^2 + 2.689x^3 for the only segment in the trajectory + auto pos = [](double x) { return -2.511 + 0.1 * x - 3.789 * x * x + 2.689 * x * x * x; }; + auto vel = [](double x) { return 0.1 - 2.0 * 3.789 * x + 3.0 * 2.689 * x * x; }; + auto acc = [](double x) { return 2.0 * -3.789 + 6.0 * 2.689 * x; }; + + Timeseries trajectory; + + double start_time = 1.0; + double end_time = 2.0; + + VectorXd start_state(2); + VectorXd end_state(2); + start_state << -2.511, 0.1; + end_state << -3.511, 0.589; + + trajectory.tryPush(start_time, start_state); + trajectory.tryPush(end_time, end_state); + + JointTrajectory joint_traj; + + joint_traj.initTrajectory(trajectory); + + double position, velocity, acceleration; + const double duration = end_time - start_time; + + // Interpolate before trajectory start + joint_traj.interpolate(start_time - 0.5, position, velocity, acceleration); + EXPECT_FLOAT_EQ(start_state[0], position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate at trajectory start + joint_traj.interpolate(start_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(0.0), position); + EXPECT_FLOAT_EQ(vel(0.0), velocity); + EXPECT_FLOAT_EQ(acc(0.0), acceleration); + + // Interpolate inside trajectory + double time = duration * ((double)rand() / (RAND_MAX)); + joint_traj.interpolate(start_time + time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(time), position); + EXPECT_FLOAT_EQ(vel(time), velocity); + EXPECT_FLOAT_EQ(acc(time), acceleration); + + // Interpolate at trajectory end + joint_traj.interpolate(end_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(duration), position); + EXPECT_FLOAT_EQ(vel(duration), velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate after trajectory end + joint_traj.interpolate(end_time + 0.5, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(duration), position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); +} + +TEST(JointTrajectory, QuinticInterpolationTest) +{ + // Quintic function y = -2.511 + 0.1x + 0.05x^2 - 12.6775x^3 + 19.216x^4 - 7.6885x^5 + auto pos = [](double x) { + return -2.511 + 0.1 * x + 0.05 * x * x - 12.6775 * x * x * x + 19.216 * x * x * x * x - 7.6885 * x * x * x * x * x; + }; + auto vel = [](double x) { + return 0.1 + 2.0 * 0.05 * x + 3.0 * -12.6775 * x * x + 4.0 * 19.216 * x * x * x + 5.0 * -7.6885 * x * x * x * x; + }; + auto acc = [](double x) { + return 2.0 * 0.05 + 6.0 * -12.6775 * x + 12.0 * 19.216 * x * x + 20.0 * -7.6885 * x * x * x; + }; + + Timeseries trajectory; + + double start_time = 1.0; + double end_time = 2.0; + + VectorXd start_state(3); + VectorXd end_state(3); + start_state << -2.511, 0.1, 0.1; + end_state << -3.511, 0.589, 0.857; + + trajectory.tryPush(start_time, start_state); + trajectory.tryPush(end_time, end_state); + + JointTrajectory joint_traj; + + joint_traj.initTrajectory(trajectory); + + double position, velocity, acceleration; + const double duration = end_time - start_time; + + // Interpolate before trajectory start + joint_traj.interpolate(start_time - 0.5, position, velocity, acceleration); + EXPECT_FLOAT_EQ(start_state[0], position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); + + // Interpolate at trajectory start + joint_traj.interpolate(start_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(0.0), position); + EXPECT_FLOAT_EQ(vel(0.0), velocity); + EXPECT_FLOAT_EQ(acc(0.0), acceleration); + + // Interpolate inside trajectory + double time = duration * ((double)rand() / (RAND_MAX)); + joint_traj.interpolate(start_time + time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(time), position); + EXPECT_FLOAT_EQ(vel(time), velocity); + EXPECT_FLOAT_EQ(acc(time), acceleration); + + // Interpolate at trajectory end + joint_traj.interpolate(end_time, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(duration), position); + EXPECT_FLOAT_EQ(vel(duration), velocity); + EXPECT_FLOAT_EQ(acc(duration), acceleration); + + // Interpolate after trajectory end + joint_traj.interpolate(end_time + 0.5, position, velocity, acceleration); + EXPECT_FLOAT_EQ(pos(duration), position); + EXPECT_FLOAT_EQ(0.0, velocity); + EXPECT_FLOAT_EQ(0.0, acceleration); +} + +} // namespace ur_controller +} // namespace isaac diff --git a/ur_controller/tests/Pid.cpp b/ur_controller/tests/Pid.cpp new file mode 100644 index 0000000..425e739 --- /dev/null +++ b/ur_controller/tests/Pid.cpp @@ -0,0 +1,189 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "packages/universal_robots/ur_controller/Pid.hpp" +#include "gtest/gtest.h" + +namespace isaac +{ +namespace ur_controller +{ +TEST(Pid, BadDurationTest) +{ + Pid pid; + pid.initPid(1.0, 0.0, 0.0, 1.0, -1.0); + + // When duration time is zero or less than zero we expect the output to be zero. + EXPECT_EQ(pid.calculate(1.0, 0.0), 0.0); + EXPECT_EQ(pid.calculate(1.0, -1.0), 0.0); + EXPECT_EQ(pid.calculate(1.0, 1.0, -1.0), 0.0); + EXPECT_EQ(pid.calculate(1.0, 1.0, 0.0), 0.0); +} + +TEST(Pid, ResetErrorsTest) +{ + Pid pid; + pid.initPid(1.0, 0.1, 0.1, 1.0, -1.0); + pid.calculate(1, 0.1, 0.1); + + double last_error, i_error; + pid.reset(); + pid.getErrors(last_error, i_error); + + EXPECT_EQ(last_error, 0); + EXPECT_EQ(i_error, 0); +} + +TEST(Pid, InitTest) +{ + Pid pid; + // Empty JSON object + nlohmann::json json = { { "gains", {} } }; + + // Init should return false, when there is no propertional gain + EXPECT_FALSE(pid.init(json)); + + double p_gain = 5.0; + double i_gain = 0.1; + double d_gain = 0.01; + double i_clamp = 1; + + // JSON + json = { { "p", p_gain }, { "i", i_gain }, { "d", d_gain }, { "i_clamp", i_clamp } }; + + // Init should now return true + EXPECT_TRUE(pid.init(json)); + + double p_return, i_return, d_return, i_max_return, i_min_return; + pid.getGains(p_return, i_return, d_return, i_max_return, i_min_return); + + EXPECT_EQ(p_gain, p_return); + EXPECT_EQ(i_gain, i_return); + EXPECT_EQ(d_gain, d_return); + EXPECT_EQ(std::abs(i_clamp), i_max_return); + EXPECT_EQ(-std::abs(i_clamp), i_min_return); +} + +TEST(Pid, PGainTest) +{ + Pid pid; + pid.initPid(1.0, 0.0, 0.0, 0.0, 0.0); + + double cmd = pid.calculate(-0.6, 1); + EXPECT_FLOAT_EQ(cmd, -0.6); + + cmd = pid.calculate(-0.2, 1); + EXPECT_FLOAT_EQ(cmd, -0.2); + + cmd = pid.calculate(0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.2); + + cmd = pid.calculate(0.8, 1); + EXPECT_FLOAT_EQ(cmd, 0.8); + + cmd = pid.calculate(0.0, 1); + EXPECT_FLOAT_EQ(cmd, 0.0); +} + +TEST(Pid, IGainTest) +{ + Pid pid; + pid.initPid(0.0, 1.0, 0.0, 10.0, -10.0); + + double cmd = pid.calculate(-0.6, 1); + EXPECT_FLOAT_EQ(cmd, -0.6); + + cmd = pid.calculate(-0.2, 1); + EXPECT_FLOAT_EQ(cmd, -0.8); + + cmd = pid.calculate(0.0, 1); + EXPECT_FLOAT_EQ(cmd, -0.8); + + pid.reset(); + + cmd = pid.calculate(0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.2); + + cmd = pid.calculate(0.8, 1); + EXPECT_FLOAT_EQ(cmd, 1.0); + + cmd = pid.calculate(0.0, 1); + EXPECT_FLOAT_EQ(cmd, 1.0); +} + +TEST(Pid, DGainTest) +{ + Pid pid; + pid.initPid(0.0, 0.0, 1.0, 0.0, 0.0); + + double cmd = pid.calculate(-0.6, 1); + EXPECT_FLOAT_EQ(cmd, -0.6); + + cmd = pid.calculate(-0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.4); + + cmd = pid.calculate(-0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.0); + + pid.reset(); + + cmd = pid.calculate(0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.2); + + cmd = pid.calculate(0.8, 1); + EXPECT_FLOAT_EQ(cmd, 0.6); + + cmd = pid.calculate(0.0, 1); + EXPECT_FLOAT_EQ(cmd, -0.8); +} + +TEST(Pid, CompleteGainTest) +{ + Pid pid; + pid.initPid(1.0, 1.0, 1.0, 10.0, -10.0); + + double cmd = pid.calculate(0.5, 1); + EXPECT_FLOAT_EQ(cmd, 1.5); + + cmd = pid.calculate(0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.6); + + cmd = pid.calculate(0.0, 1); + EXPECT_FLOAT_EQ(cmd, 0.5); + + cmd = pid.calculate(-0.2, 1); + EXPECT_FLOAT_EQ(cmd, 0.1); + + cmd = pid.calculate(-0.5, 1); + EXPECT_FLOAT_EQ(cmd, -0.8); +} + +} // namespace ur_controller +} // namespace isaac diff --git a/ur_controller/tests/ScaledMultiJointController.cpp b/ur_controller/tests/ScaledMultiJointController.cpp new file mode 100644 index 0000000..47c7cf6 --- /dev/null +++ b/ur_controller/tests/ScaledMultiJointController.cpp @@ -0,0 +1,646 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include + +#include "packages/composite/gems/serializer.hpp" +#include "packages/map/KinematicTree.hpp" +#include "gtest/gtest.h" +// In order to be able to test the private functions of ScaledMultiJointController and access private attributes +#define private public +#include "packages/universal_robots/ur_controller/ScaledMultiJointController.hpp" + +namespace isaac +{ +namespace ur_controller +{ +std::vector joint_names = { "shoulder_pan_joint", "shoulder_lift_joint", "elbow_joint", + "wrist_1_joint", "wrist_2_joint", "wrist_3_joint" }; + +class PublishPlan : public isaac::alice::Codelet +{ +public: + void start() override + { + initQuinticSchema(); + tickPeriodically(); + } + void tick() override + { + if (get_send_trajectory()) + { + set_send_trajectory(false); + if (schema_name_ == "linear") + { + auto proto_builder = tx_trajectory().initProto(); + Timeseries, double> plan; + Vector state; + state << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; + plan.tryPush(1.0, state); + plan.tryPush(2.0, state); + plan.tryPush(3.0, state); + plan.tryPush(4.0, state); + serializer_.serialize(plan, composite::Quantity::Scalar("time", composite::Measure::kTime), proto_builder, + tx_trajectory().buffers()); + tx_trajectory().publish(); + } + else if (schema_name_ == "cubic") + { + set_send_trajectory(false); + auto proto_builder = tx_trajectory().initProto(); + Timeseries, double> plan; + Vector state; + state << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; + plan.tryPush(1.0, state); + plan.tryPush(2.0, state); + plan.tryPush(3.0, state); + plan.tryPush(4.0, state); + serializer_.serialize(plan, composite::Quantity::Scalar("time", composite::Measure::kTime), proto_builder, + tx_trajectory().buffers()); + tx_trajectory().publish(); + } + else if (schema_name_ == "quintic") + { + set_send_trajectory(false); + auto proto_builder = tx_trajectory().initProto(); + Timeseries, double> plan; + Vector state; + state << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; + plan.tryPush(1.0, state); + plan.tryPush(2.0, state); + plan.tryPush(3.0, state); + plan.tryPush(4.0, state); + serializer_.serialize(plan, composite::Quantity::Scalar("time", composite::Measure::kTime), proto_builder, + tx_trajectory().buffers()); + tx_trajectory().publish(); + } + else if (schema_name_ == "invalid") + { + set_send_trajectory(false); + auto proto_builder = tx_trajectory().initProto(); + Timeseries, double> plan; + Vector state; + state << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0; + plan.tryPush(1.0, state); + plan.tryPush(2.0, state); + plan.tryPush(3.0, state); + plan.tryPush(4.0, state); + serializer_.serialize(plan, composite::Quantity::Scalar("time", composite::Measure::kTime), proto_builder, + tx_trajectory().buffers()); + tx_trajectory().publish(); + } + } + } + void initLinearSchema() + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar("time", composite::Measure::kTime)); + for (unsigned int i = 0; i < joint_names.size(); ++i) + { + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kPosition)); + } + + schema_ = composite::Schema(std::move(quantities)); + serializer_.setSchema(schema_); + schema_name_ = "linear"; + } + void initCubcicSchema() + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar("time", composite::Measure::kTime)); + for (unsigned int i = 0; i < joint_names.size(); ++i) + { + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kSpeed)); + } + + schema_ = composite::Schema(std::move(quantities)); + serializer_.setSchema(schema_); + schema_name_ = "cubic"; + } + void initQuinticSchema() + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar("time", composite::Measure::kTime)); + for (unsigned int i = 0; i < joint_names.size(); ++i) + { + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kSpeed)); + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kAcceleration)); + } + schema_ = composite::Schema(std::move(quantities)); + serializer_.setSchema(schema_); + schema_name_ = "quintic"; + } + void initInvalidSchema() + { + std::vector quantities; + quantities.push_back(composite::Quantity::Scalar("time", composite::Measure::kTime)); + for (unsigned int i = 0; i < joint_names.size() - 1; ++i) + { + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kSpeed)); + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kAcceleration)); + } + schema_ = composite::Schema(std::move(quantities)); + serializer_.setSchema(schema_); + schema_name_ = "invalid"; + } + ISAAC_PROTO_TX(CompositeProto, trajectory); + + // Used to trigger when to send new trajecotry + ISAAC_PARAM(bool, send_trajectory, false); + + composite::Schema schema_; + composite::Serializer serializer_; + std::string schema_name_ = ""; +}; + +class PublishRobotState : public isaac::alice::Codelet +{ + void start() override + { + initStateSchema(); + tickPeriodically(); + } + void tick() override + { + auto proto_builder = tx_robot_state().initProto(); + composite::WriteSchema(state_schema_, proto_builder); + + Tensor1d state_data(13); + for (unsigned int i = 0; i < 12; ++i) + { + state_data(i) = 1; + } + state_data(12) = get_speed_fraction(); + + ToProto(std::move(state_data), proto_builder.initValues(), tx_robot_state().buffers()); + tx_robot_state().publish(); + } + void initStateSchema() + { + std::vector quantities; + for (unsigned int i = 0; i < joint_names.size(); i++) + { + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names[i], composite::Measure::kSpeed)); + } + quantities.push_back(composite::Quantity::Scalar("speed_fraction", composite::Measure::kNone)); + state_schema_ = composite::Schema(std::move(quantities)); + } + + ISAAC_PROTO_TX(CompositeProto, robot_state); + // Speed fraction + ISAAC_PARAM(double, speed_fraction, 1.0); + + composite::Schema state_schema_; +}; + +class ReceiveJointCommand : public isaac::alice::Codelet +{ + void start() override + { + initCommandParser(get_control_mode()); + tickPeriodically(); + } + void tick() override + { + if (rx_joint_command().available()) + { + if (control_mode_ != get_control_mode()) + { + initCommandParser(get_control_mode()); + } + // Make sure we can parse command received from controller based upon control mode + VectorXd command(6); + EXPECT_TRUE(command_parser_.parse(rx_joint_command().getProto(), rx_joint_command().buffers(), command)); + } + } + void initCommandParser(const ArmControlMode mode) + { + control_mode_ = mode; + switch (mode) + { + case kJointPosition: + command_parser_.requestSchema(composite::Schema(joint_names, composite::Measure::kPosition)); + break; + case kJointSpeed: + command_parser_.requestSchema(composite::Schema(joint_names, composite::Measure::kSpeed)); + break; + default: + command_parser_.requestSchema({}); + return; + } + } + + ISAAC_PROTO_RX(CompositeProto, joint_command); + // Control mode + ISAAC_PARAM(ArmControlMode, control_mode, kJointPosition); + + ArmControlMode control_mode_; + composite::Parser command_parser_; +}; + +TEST(ScaledMultiJointController, InvalidKinematicTreeComponentTest) +{ + alice::Application first_app; + + // Setup nodes + auto node = first_app.createMessageNode("test"); + auto controller = node->addComponent(); + + // Setup configuration + controller->async_set_tick_period("100Hz"); + + first_app.enableStopOnTimeout(0.2); + first_app.runBlocking(); + + std::string status_msg = controller->getStatusMessage(); + std::string expected_msg = "KinematicTree node is not specified."; + EXPECT_EQ(controller->getStatus(), alice::Status::FAILURE); + EXPECT_STREQ(status_msg.c_str(), expected_msg.c_str()); + + alice::Application second_app; + // Setup nodes + node = second_app.createMessageNode("test"); + controller = node->addComponent(); + + // Setup configuration + controller->async_set_kinematic_tree("apps/assets/kinematic_trees/ur10.kinematic.json"); + controller->async_set_tick_period("100Hz"); + + second_app.enableStopOnTimeout(0.2); + second_app.runBlocking(); + + status_msg = controller->getStatusMessage(); + expected_msg = "Node apps/assets/kinematic_trees/ur10.kinematic.json does not contain KinematicTree component."; + EXPECT_EQ(controller->getStatus(), alice::Status::FAILURE); + EXPECT_STREQ(status_msg.c_str(), expected_msg.c_str()); +} + +TEST(ScaledMultiJointController, ToleranceTest) +{ + alice::Application app; + // Setup nodes + auto controller_node = app.createMessageNode("controller"); + auto controller = controller_node->addComponent(); + + auto kinematic_tree_node = app.createMessageNode("kinematic"); + auto kinematic_tree = kinematic_tree_node->addComponent("kinematic_tree"); + + // Setup configuration + kinematic_tree_node->start_order = -100; + kinematic_tree->async_set_kinematic_file("apps/assets/kinematic_trees/ur10.kinematic.json"); + + controller->async_set_tick_period("100Hz"); + controller->async_set_kinematic_tree("kinematic"); + + app.runAsync(); + Sleep(500000000); // give time to start application + + // No tolerance configured, it should always return true + EXPECT_TRUE(controller->insideTolerance(0.2)); + EXPECT_TRUE(controller->insideTolerance(10)); + + controller->async_set_tolerance(0.1); + Sleep(500000000); // Give time to set the tolerance + + // Inside tolerance + EXPECT_TRUE(controller->insideTolerance(0.05)); + // At tolerance + EXPECT_TRUE(controller->insideTolerance(0.1)); + // Outside tolerance + EXPECT_FALSE(controller->insideTolerance(0.2)); + + app.stopBlocking(); +} + +TEST(ScaledMultiJointController, InitTrajectoryTest) +{ + alice::Application app; + + // Setup nodes + auto controller_node = app.createMessageNode("controller"); + auto controller = controller_node->addComponent(); + + auto kinematic_tree_node = app.createMessageNode("kinematic"); + auto kinematic_tree = kinematic_tree_node->addComponent("kinematic_tree"); + + // Setup configuration + kinematic_tree_node->start_order = -100; + kinematic_tree->async_set_kinematic_file("apps/assets/kinematic_trees/ur10.kinematic.json"); + + controller->async_set_tick_period("100Hz"); + controller->async_set_kinematic_tree("kinematic"); + + app.runAsync(); + Sleep(500000000); // give time to start application + + std::vector > trajectory(joint_names.size()); + + VectorXd start_state(1); + VectorXd mid_state(1); + VectorXd end_state(1); + start_state << 1.0; + mid_state << 1.5; + end_state << 2.0; + + for (unsigned int i = 0; i < joint_names.size(); ++i) + { + trajectory[i].tryPush(1.0, start_state); + trajectory[i].tryPush(2.0, mid_state); + trajectory[i].tryPush(3.0, end_state); + } + + controller->initTrajectory(trajectory); + // We expect an active goal and 0 successful joints after init trajectory + unsigned int count = std::accumulate(controller->successful_joints_.begin(), controller->successful_joints_.end(), + static_cast(0)); + EXPECT_TRUE(controller->active_goal_ == true); + EXPECT_TRUE(count == 0); + // Make sure endtime matches end time trajectory for each joint + for (unsigned int i = 0; i < joint_names.size(); ++i) + { + EXPECT_TRUE(controller->cur_traj_[i].endTime() == 3.0); + } + // We expect active_pid_ to be false, because we havn't configured any gains + EXPECT_TRUE(controller->active_pid_ == false); + + nlohmann::json gains = { + { "shoulder_pan_joint", { { "p", 5 }, { "i", 0.05 }, { "d", 0.1 }, { "i_clamp", 1 }, { "velocity_ff", 0.5 } } }, + { "shoulder_lift_joint", { { "p", 5 }, { "i", 0.05 }, { "d", 0.1 }, { "i_clamp", 1 }, { "velocity_ff", 0.5 } } }, + { "elbow_joint", { { "p", 5 }, { "i", 0.05 }, { "d", 0.1 }, { "i_clamp", 1 }, { "velocity_ff", 0.5 } } }, + { "wrist_1_joint", { { "p", 5 }, { "i", 0.05 }, { "d", 0.1 }, { "i_clamp", 1 }, { "velocity_ff", 0.5 } } }, + { "wrist_2_joint", { { "p", 5 }, { "i", 0.05 }, { "d", 0.1 }, { "i_clamp", 1 }, { "velocity_ff", 0.5 } } }, + { "wrist_3_joint", { { "p", 5 }, { "i", 0.05 }, { "d", 0.1 }, { "i_clamp", 1 }, { "velocity_ff", 0.5 } } } + }; + ; + + controller->async_set_gains(gains); + Sleep(500000000); // give time to set configuration + controller->initTrajectory(trajectory); + + // We now expect active_pid_ to be true + EXPECT_TRUE(controller->active_pid_ == true); + + // Test that ff_term is set correctly + for (unsigned int i = 0; i < joint_names.size(); ++i) + { + LOG_INFO("ff_term %f", controller->ff_term_[i]); + EXPECT_TRUE(controller->ff_term_[i] == 0.5); + } + + app.stopBlocking(); +} + +TEST(ScaledMultiJointController, ControlPeriodTest) +{ + alice::Application app; + + // Setup nodes + auto controller_node = app.createMessageNode("controller"); + auto controller = controller_node->addComponent(); + + auto kinematic_tree_node = app.createMessageNode("kinematic"); + auto kinematic_tree = kinematic_tree_node->addComponent("kinematic_tree"); + + auto planner_node = app.createMessageNode("planner"); + auto planner = planner_node->addComponent(); + + auto robot_state_node = app.createMessageNode("robotState"); + auto robot_state = robot_state_node->addComponent(); + + // Setup configuration + kinematic_tree_node->start_order = -100; + kinematic_tree->async_set_kinematic_file("apps/assets/kinematic_trees/ur10.kinematic.json"); + + controller->async_set_tick_period("100Hz"); + controller->async_set_kinematic_tree("kinematic"); + + planner->async_set_tick_period("10Hz"); + planner->async_set_send_trajectory(true); + + robot_state->async_set_tick_period("100Hz"); + + // Setup communication + Connect(planner->tx_trajectory(), controller->rx_plan()); + Connect(robot_state->tx_robot_state(), controller->rx_current_arm_state()); + + app.runAsync(); + Sleep(500000000); // give time to start application + + double expected_period = 0.01; + double uptime, period; + double abs = 0.001; + + uptime = controller->controller_uptime_; + period = controller->period_; + + EXPECT_NEAR(expected_period, period, abs); + // When the speed isn't scaled we expect controller_uptime and tick_time to be equal + EXPECT_NEAR(uptime, controller->tick_time_, abs); + + robot_state->async_set_speed_fraction(0.5); + + Sleep(500000000); + expected_period = 0.01 * 0.5; + period = controller->period_; + uptime = controller->controller_uptime_; + + EXPECT_NEAR(expected_period, period, abs); + EXPECT_LT(uptime, controller->tick_time_); + + robot_state->async_set_speed_fraction(0.7); + + Sleep(500000000); + expected_period = 0.01 * 0.7; + period = controller->period_; + uptime = controller->controller_uptime_; + + EXPECT_NEAR(expected_period, period, abs); + EXPECT_LT(uptime, controller->tick_time_); + + app.stopBlocking(); +} + +TEST(ScaledMultiJointController, PlanParserTest) +{ + alice::Application app; + + // Setup nodes + auto controller_node = app.createMessageNode("controller"); + auto controller = controller_node->addComponent(); + + auto kinematic_tree_node = app.createMessageNode("kinematic"); + auto kinematic_tree = kinematic_tree_node->addComponent("kinematic_tree"); + + auto planner_node = app.createMessageNode("planner"); + auto planner = planner_node->addComponent(); + + // Setup configuration + kinematic_tree_node->start_order = -100; + kinematic_tree->async_set_kinematic_file("apps/assets/kinematic_trees/ur10.kinematic.json"); + + controller->async_set_tick_period("100Hz"); + controller->async_set_kinematic_tree("kinematic"); + + planner->async_set_tick_period("10Hz"); + + // Setup communication + Connect(planner->tx_trajectory(), controller->rx_plan()); + + app.runAsync(); + Sleep(500000000); // give time to start application + + // Make sure that we can parse messages based upon interpolation scheme. + controller->async_set_interpolation_scheme(InterpolationScheme::linear_interpolation); + planner->initLinearSchema(); + planner->async_set_send_trajectory(true); + + Sleep(500000000); // Wait for message to be received + EXPECT_TRUE(controller->succesful_plan_parse_); + + controller->async_set_interpolation_scheme(InterpolationScheme::cubic_interpolation); + planner->initCubcicSchema(); + planner->async_set_send_trajectory(true); + + Sleep(500000000); // Wait for message to be received + EXPECT_TRUE(controller->succesful_plan_parse_); + + controller->async_set_interpolation_scheme(InterpolationScheme::quintic_interpolation); + planner->initQuinticSchema(); + planner->async_set_send_trajectory(true); + + Sleep(500000000); // Wait for message to be received + EXPECT_TRUE(controller->succesful_plan_parse_); + + planner->initInvalidSchema(); + planner->async_set_send_trajectory(true); + + Sleep(500000000); // Wait for message to be received + EXPECT_FALSE(controller->succesful_plan_parse_); + + app.stopBlocking(); +} + +TEST(ScaledMultiJointController, jointCommandTest) +{ + // First app publishes joint positions as commands + alice::Application first_app; + + // Setup nodes + auto controller_node = first_app.createMessageNode("controller"); + auto controller = controller_node->addComponent(); + + auto kinematic_tree_node = first_app.createMessageNode("kinematic"); + auto kinematic_tree = kinematic_tree_node->addComponent("kinematic_tree"); + + auto planner_node = first_app.createMessageNode("planner"); + auto planner = planner_node->addComponent(); + + auto joint_command_node = first_app.createMessageNode("joint_command"); + auto joint_command = joint_command_node->addComponent(); + + auto robot_state_node = first_app.createMessageNode("robotState"); + auto robot_state = robot_state_node->addComponent(); + + // Setup configuration + kinematic_tree_node->start_order = -100; + kinematic_tree->async_set_kinematic_file("apps/assets/kinematic_trees/ur10.kinematic.json"); + + controller->async_set_tick_period("100Hz"); + controller->async_set_kinematic_tree("kinematic"); + + planner->async_set_tick_period("10Hz"); + planner->async_set_send_trajectory(true); + + joint_command->async_set_tick_period("10Hz"); + + robot_state->async_set_tick_period("100Hz"); + + // Setup communication + Connect(planner->tx_trajectory(), controller->rx_plan()); + Connect(robot_state->tx_robot_state(), controller->rx_current_arm_state()); + Connect(controller->tx_joint_command(), joint_command->rx_joint_command()); + + first_app.enableStopOnTimeout(0.2); + first_app.runBlocking(); + + // Second app publishes joint speeds as commands + alice::Application second_app; + + // Setup nodes + controller_node = second_app.createMessageNode("controller"); + controller = controller_node->addComponent(); + + kinematic_tree_node = second_app.createMessageNode("kinematic"); + kinematic_tree = kinematic_tree_node->addComponent("kinematic_tree"); + + planner_node = second_app.createMessageNode("planner"); + planner = planner_node->addComponent(); + + joint_command_node = second_app.createMessageNode("joint_command"); + joint_command = joint_command_node->addComponent(); + + robot_state_node = second_app.createMessageNode("robotState"); + robot_state = robot_state_node->addComponent(); + + // Setup configuration + kinematic_tree_node->start_order = -100; + kinematic_tree->async_set_kinematic_file("apps/assets/kinematic_trees/ur10.kinematic.json"); + + controller->async_set_tick_period("100Hz"); + controller->async_set_kinematic_tree("kinematic"); + controller->async_set_control_mode(ArmControlMode::kJointSpeed); + + planner->async_set_tick_period("10Hz"); + planner->async_set_send_trajectory(true); + + joint_command->async_set_tick_period("10Hz"); + joint_command->async_set_control_mode(ArmControlMode::kJointSpeed); + + robot_state->async_set_tick_period("100Hz"); + + // Setup communication + Connect(planner->tx_trajectory(), controller->rx_plan()); + Connect(robot_state->tx_robot_state(), controller->rx_current_arm_state()); + Connect(controller->tx_joint_command(), joint_command->rx_joint_command()); + + second_app.enableStopOnTimeout(0.2); + second_app.runBlocking(); +} + +} // namespace ur_controller +} // namespace isaac + +ISAAC_ALICE_REGISTER_CODELET(isaac::ur_controller::PublishPlan); +ISAAC_ALICE_REGISTER_CODELET(isaac::ur_controller::PublishRobotState); +ISAAC_ALICE_REGISTER_CODELET(isaac::ur_controller::ReceiveJointCommand); \ No newline at end of file diff --git a/ur_msg/BUILD b/ur_msg/BUILD new file mode 100644 index 0000000..ee1f354 --- /dev/null +++ b/ur_msg/BUILD @@ -0,0 +1,40 @@ +load("@com_nvidia_isaac_engine//engine/build:cc_capnp_library.bzl", "cc_capnp_library") +load("@com_nvidia_isaac_engine//bzl:isaac_engine.bzl", "isaac_cc_library") +load("//bzl:pybind.bzl", "pybind_library") + +cc_capnp_library( + name = "speed_slider_proto", + protos = [ + "speed_slider.capnp" + ], +) + +cc_capnp_library( + name = "dashboard_command_proto", + protos = [ + "dashboard_command.capnp" + ], +) + +isaac_cc_library( + name = "dashboard_command", + srcs = [ + "dashboardCommand.cpp" + ], + hdrs = [ + "dashboardCommand.hpp" + ], + visibility = ["//visibility:public"], + deps = [ + ":dashboard_command_proto", + "@com_nvidia_isaac_engine//engine/core", + ], +) + +py_library( + name = "ur_msg_python", + srcs = [ + "ur_msg_python.py" + ], + visibility = ["//visibility:public"] +) \ No newline at end of file diff --git a/ur_msg/README.md b/ur_msg/README.md new file mode 100644 index 0000000..3189081 --- /dev/null +++ b/ur_msg/README.md @@ -0,0 +1,628 @@ +# UR message + +This folder contains messages developed specific to the **Universal_Robots_Isaac_Driver**. +The folder contains: + +- **dashboard_command** Consist of two messages. One used to send dashboard commands +to the codelet **DashboardClientIsaac**. And one to receive the status of the command. + +- **dashboardCommand** Helper functions to translate the dashboard commands from +an enum in capnp format to a C++ enum. + +- **speed_slider** Consist of a message to set the actual value of the speedslider. + +- **ur_msg_python** The file contains Python functionality to use ur_msg inside +Python application, see documentation for [ur_msg in python](#UR-message-in-Python) +and [DashboardClientIsaac in Python](#DashboardClientIsaac-usage-in-python). + +## Messages + +The different messages are described here: + +### DashboardCommandProto + +For documentation on the dashboard server see [e-series](https://www.universal-robots.com/articles/ur/dashboard-server-e-series-port-29999/) +and [cb3](https://www.universal-robots.com/articles/ur/dashboard-server-cb-series-port-29999/) + +```capnp +# A message to represent all dashboard commands available +# For documentation about the dashboard server see +# - https://www.universal-robots.com/articles/ur/dashboard-server-e-series-port-29999/ +# - https://www.universal-robots.com/articles/ur/dashboard-server-cb-series-port-29999/ +struct DashboardCommandProto +{ + # Enum holding all dashboard commands available. + enum DashboardCommand + { + load @0; # Load program + play @1; # Play program + stop @2; # Stop program + pause @3; # Pause program + quit @4; # Disconnect client + shutdown @5; # Shut down robot + running @6; # Programm running? + robotmode @7; # Current robot mode + getLoadedProgram @8; # Returns loaded program + popup @9; # Show popup + closePopup @10; # Close popup + addToLog @11; # Add message to log + isProgramSaved @12; # Is current program saved? + programState @13; # Returns current program state + polyscopeVersion @14; # Polyscope version number + setOperationalMode @15; # Set operational mode + getOperationalMode @16; # Returns curretn operationalmode + clearOperationalMode @17; # Dashboard server no longer controls operational mode + powerOn @18; # Power on robot + powerOff @19; # Power down robot + brakeRelease @20; # Brake release + safetystatus @21; # Current safety status + unlockProtectiveStop @22; # Unlocks protective stop + closeSafetyPopup @23; # Close safety popup + loadInstallation @24; # Load installation + restartSafety @25; # Restart safety + isInRemoteControl @26; # Returns remote control status + getSerialNumber @27; # Returns serial number + getRobotModel @28; # Returns robot model + safetymode @29; # Current safetymode + setUserRole @30; # Setting user role + getUserRole @31; # Get current user role + } + + # The request/command to send to the dashboardserver. + dashboardRequest @0: DashboardCommand; + + # Possible argument to the dashboard command can be empty. + argument @1: Text = ""; +} + +``` + +### DashboardCommandStatusProto + +```capnp +# A message to represent the status of a dashboard command. +struct DashboardCommandStatusProto { + + # The anwser from the dashboard server. + anwser @0: Text; + + # Returns whether the command was a succes or not. + succes @1: Bool; +} +``` + +### SpeedSliderProto + +```capnp +# Message to set the actual value of the speedslider. Values should be between +# 0 and 1. Only set this smaller than 1 if you are using the scaledMultiJointController +# or you know what you're doing. Using this with another controller might lead to +unexpected behaviors. +struct SpeedSliderProto { + # The speed slider value + speedSliderValue @0 : Float32; +} +``` + +## UR message usage + +The following documentation shows how to use ur messages in your applications. + +### UR message in C++ + +To use UR messages in C++ applications, we need to use the ur message inside +codelets. UR messages can be used in the same way as regular Isaac messages. +See Isaac documentation on [sending messages](https://docs.nvidia.com/isaac/isaac/doc/tutorials/ping.html#sending-messages) +and [receiving messages](https://docs.nvidia.com/isaac/isaac/doc/tutorials/ping.html#receiving-messages) + +### UR message in Python + +Since support for Python is in an experimental state in Isaac, support for the ur_msg +in Python is also in an experimental state. Therefore things might change in the +future. Isaac supports interacting with a running application in Python, +which the below examples uses. + +To use UR messages in a Python application two functions has been created, which +can be found in *ur_msg_python.py*. The function *create_ur_msg* are used to +create a message which can be published to a specific channel in a Python application. +The function *get_ur_msg* can be used to create a wrapper for a recieved ur_message +in a Python application. + +See the following example on how to send and receive UR messages in a Python application. +The examples uses the [drivers subgraph](../ur_robot_driver/apps/ur_eseries_robot.subgraph.json) +from ur_robot_driver. + +Start by creating a folder inside `isaac/sdk/packages` to store the codelet. All +the following files, should be created inside this folder. + +```bash +$ mkdir ~/isaac/sdk/packages/ur_msg_example +``` + +Next we need to create a file to store our Python application. Create a file called +`ur_msg_example.py` and copy the content below into it. + +```Python +import time +from packages.universal_robots.ur_msg.ur_msg_python import create_ur_msg, get_ur_msg + +from packages.pyalice import Application + +app = Application(name="Sample ur message") + +app.load("packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json", prefix="ur") + +# Remember to set the robots IP address +ur_driver = app.nodes["ur.universal_robots"]["UniversalRobots"] +ur_driver.config.robot_ip = "192.168.56.1" + +app.start() + +# Make sure the driver is running +time.sleep(5) + +# Publish ur message (SpeedSliderProto) +speed_fraction = 0.5 +speed_fraction_msg = create_ur_msg("SpeedSliderProto") +speed_fraction_msg.proto.speedSliderValue = speed_fraction +app.publish("ur.subgraph", "interface", "set_speed_slider", speed_fraction_msg) + +# Publish ur message (DashboardCommandProto) +dashboard_msg = create_ur_msg("DashboardCommandProto") +dashboard_msg.proto.dashboardRequest = "popup" +dashboard_msg.proto.argument = "This is a popup message" +app.publish("ur.subgraph", "interface", "dashboard_command", dashboard_msg) + +# Sleep before receiving anwser +time.sleep(1) + +# Receive ur message (DashboardCommandStatusProto) +dashboard_anwser = app.receive("ur.subgraph", "interface", "dashboard_anwser") +if dashboard_anwser is not None: + ur_msg = get_ur_msg(dashboard_anwser) + print(ur_msg.anwser) + print(ur_msg.success) + +app.stop() +``` + +**NOTE** Remember to update the robot_ip to the IP address on which the Isaac driver +can reach the robot. + +Lastly we need to create the build file. Create a file called `BUILD` and copy the +content below into it. + +```bazel +load("//bzl:py.bzl", "isaac_py_app") + +isaac_py_app( + name = "ur_msg_example", + srcs = ["ur_msg_example.py"], + data = [ + "//apps/assets/kinematic_trees", + "//packages/universal_robots/ur_robot_driver/apps:ur_eseries_robot_subgraph", + "//packages/universal_robots/ur_robot_driver/apps:ur_cb3_robot_subgraph", + "//packages/universal_robots/ur_msg:ur_msg_python" + ], + modules = [ + "planner", + "universal_robots", + ], + deps = [ + "//packages/pyalice", + ], +) +``` + +Now you can run the application inside the `~/isaac/sdk/` folder by typing: + +```bash +$ bazel run packages/ur_msg_example:ur_msg_example +``` + +This should open a popup message on the teach pendant, and you should also see the +speed slider is set to 50%. + +## DashboardClientIsaac usage + +To use the dashboard command messages created in this folder a codelet named DashboardClientIsaac +has been created to serve as an interface between the dashboard server on the robot +and an Isaac aplication. This is created in order to use the robot in an Isaac application +without interacting with the teach pendant. Documentation on DashboardClientIsaac +codelet can be found [here](../ur_robot_driver/doc/component_api.md#DashboardClientIsaac). + +This serves as a documentation on how to use the DashboardclientIsaac in an +application. It comes with some examples on how to use the DashboardClientIsaac +in C++ applications and in Python applications. + +See the [message documentation](#DashboardCommandProto), for documentation on all +the dashboard commands available. + +### DashboardClientIsaac usage in C++ + +Since the DashboardClientIsaac is a C++ codetlet it can be used as any other codelet +in your application. See Isaac documentation on [developing codelets](https://docs.nvidia.com/isaac/isaac/doc/tutorials/ping.html#) +and on [understanding codelets](https://docs.nvidia.com/isaac/isaac/doc/engine/components.html). + +Communicating with the DashboardClientIsaac codelet inside C++ codelets. can be +done in the same way as communications between other C++ codelets. See Isaac documentation +on [sending messages](https://docs.nvidia.com/isaac/isaac/doc/tutorials/ping.html#sending-messages) +and [receiving messages](https://docs.nvidia.com/isaac/isaac/doc/tutorials/ping.html#receiving-messages). + +The below example shows how to create a small codelet that can communicate with +the DashboardClientIsaac codelet. It will send a dashboard command and then afterwards +receive the anwser from the command and then the codelet will report success. This +example makes use of the [drivers subgraph](../ur_robot_driver/apps/ur_eseries_robot.subgraph.json) +from ur_robot_driver. + +Start by creating a folder inside `isaac/sdk/packages` to store the codelet. All +the following files, should be created inside this folder. + +```bash +$ mkdir ~/isaac/sdk/packages/dashboard_example +``` + +Next we want to create the header file for the codelet. Create a file called `DashboardExample.hpp` +and copy the content below into it. + +```c++ +#pragma once +#include "engine/alice/alice_codelet.hpp" +#include "packages/universal_robots/ur_msg/dashboard_command.capnp.h" +#include "packages/universal_robots/ur_msg/dashboardCommand.hpp" + +namespace isaac +{ +namespace dashboard_example +{ + +class DashboardExample : public isaac::alice::Codelet { +public: + void start() override; + void tick() override; + + // Publish the dashboard command + ISAAC_PROTO_TX(DashboardCommandProto, dashboard_command); + + // Channel to receive the anwser from the dashbordserver + ISAAC_PROTO_RX(DashboardCommandStatusProto, dashboard_anwser); + + bool command_published_; + std::optional message_time_; +}; +} +} +ISAAC_ALICE_REGISTER_CODELET(isaac::dashboard_example::DashboardExample); +``` + +Next we want to create the cpp file for the codelet. Create a file called `DashboardExample.cpp` +and copy the content below into it. + +```c++ +#include "DashboardExample.hpp" + +namespace isaac +{ +namespace dashboard_example +{ +void DashboardExample::start() +{ + command_published_ = false; + tickPeriodically(); +} + +void DashboardExample::tick() +{ + if (!command_published_ && getTickTime() > 5.0) + { + // Make sure that we dont collect and old message as the anwser + if (rx_dashboard_anwser().available()) + { + message_time_ = rx_dashboard_anwser().acqtime(); + } + // Publish popup command + auto proto_sender = tx_dashboard_command().initProto(); + proto_sender.setDashboardRequest(dashboard_command::ToProto(dashboard_command::DashboardCommand::popup)); + proto_sender.setArgument("This message is added from an Isaac application"); + + tx_dashboard_command().publish(); + command_published_ = true; + } + + // Receive anwser from dashboard server + if (command_published_ && rx_dashboard_anwser().available()) + { + if (!message_time_ || rx_dashboard_anwser().acqtime() > *message_time_) + { + auto proto = rx_dashboard_anwser().getProto(); + LOG_INFO("Received anwser: %s", proto.getAnwser().cStr()); + LOG_INFO("The command was a succes? %i", proto.getSuccess()); + reportSuccess(); + } + } +} + +} +} +``` + +Next we need to create our application JSON file. Create a file called `dashboard_example.app.json` +and copy the content below into it. + +```JSON +{ + "name": "dashboard_example", + "modules": [ + "//packages/dashboard_example:dashboard_example_components" + ], + "graph": { + "nodes": [ + { + "name": "ur_driver", + "subgraph": "packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json" + }, + { + "name": "dashboard_example", + "components": [ + { + "name": "MessageLedger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "DashboardExample", + "type": "isaac::dashboard_example::DashboardExample" + } + ] + } + ], + "edges": [ + { + "source": "ur_driver.subgraph/interface/dashboard_anwser", + "target": "dashboard_example/DashboardExample/dashboard_anwser" + }, + { + "source": "dashboard_example/DashboardExample/dashboard_command", + "target": "ur_driver.subgraph/interface/dashboard_command" + } + ] + }, + "config": { + "dashboard_example": { + "DashboardExample": { + "tick_period": "10Hz" + } + }, + "ur_driver.universal_robots": { + "UniversalRobots": { + "robot_ip": "192.168.56.1" + } + } + } +} +``` + +**NOTE** Remember to update the robot_ip to the IP address on which the Isaac driver +can reach the robot + +Lastly we need to create the build file. Create a file called `BUILD` and copy the +content below into it. + +```bazel +load("//bzl:module.bzl", "isaac_app", "isaac_cc_module") + +isaac_cc_module( + name = "dashboard_example_components", + srcs = [ + "DashboardExample.cpp" + ], + hdrs = [ + "DashboardExample.hpp" + ], + deps = [ + "//packages/universal_robots/ur_msg:dashboard_command", + "//packages/universal_robots/ur_msg:dashboard_command_proto", + ] +) + +isaac_app( + name = "dashboard_example", + data = [ + "//packages/universal_robots/ur_robot_driver/apps:ur_eseries_robot_subgraph" + ], + modules = [ + "//packages/dashboard_example:dashboard_example_components", + ] +) +``` + +Now you can run the application inside the `~/isaac/sdk/` folder by typing: + +```bash +$ bazel run packages/dashboard_example:dashboard_example +``` + +You should now see a popup message on the teach pendant with the message `This message +is added from an Isaac application`. + +This is just a quick example on how to use the DashboardClientIsaac, but serves +as inspiration on how to use DashboardClientIsaac to interact with the robot +without interacting with the teach pendant. + +### DashboardClientIsaac usage in python + +Since support for Python is in an experimental state in Isaac, support for the dashboardClientIsaac +in Python is also in an experimental state. Therefore things might change in the +future. Isaac supports interacting with a running application in Python, +which the below examples uses. + +To use the DashboardClientIsaac Python and to be able to send and receive dashboard +commands, some additional functionality has been created, which can be found in *ur_msg_python.py*. +The function *do_dashboard_command* can be used to execute a dashboard command and +returns the anwser from the command, or None if no anwser was received. + +See the following examples on how to communicate with the dashboard server in a running +application in Python. The examples uses the [drivers subgraph](../ur_robot_driver/apps/ur_eseries_robot.subgraph.json) +from ur_robot_driver. + +If you haven't created the dashboard_example folder, go ahead and create it. + +```bash +$ mkdir ~/isaac/sdk/packages/dashboard_example +``` + +Next we need to create a file to store our Python application. Create a file called +`py_dashboard_example.py` and copy the content below into it. + +```Python +import time +from packages.pyalice import Application +from packages.universal_robots.ur_msg.ur_msg_python import do_dashboard_command + +app = Application(name="Sample dashboard client") + +app.load("packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json", prefix="ur") + +# Remember to set the robots IP address +ur_driver = app.nodes["ur.universal_robots"]["UniversalRobots"] +ur_driver.config.robot_ip = "192.168.56.1" + +app.start() + +# Make sure the driver is running +time.sleep(5) + +anwser = do_dashboard_command(app, "popup", arguments="This message is added from an Isaac application") +if anwser is not None: + print(anwser.anwser) + print(anwser.success) + +# We can also power on the robot +anwser = do_dashboard_command(app, "powerOn") +if anwser is not None: + print(anwser.anwser) + print(anwser.success) + +app.stop() +``` + +**NOTE** Remember to update the robot_ip to the IP address on which the Isaac driver +can reach the robot. + +If you haven't already created the build file. Go ahead and create a file called +`BUILD` and copy the content below into it else just copy the content below into +the already created build file. + +```bazel +load("//bzl:py.bzl", "isaac_py_app") + +isaac_py_app( + name = "py_dashboard_example", + srcs = ["py_dashboard_example.py"], + data = [ + "//apps/assets/kinematic_trees", + "//packages/universal_robots/ur_robot_driver/apps:ur_eseries_robot_subgraph", + "//packages/universal_robots/ur_robot_driver/apps:ur_cb3_robot_subgraph", + "//packages/universal_robots/ur_msg:ur_msg_python" + ], + modules = [ + "planner", + "universal_robots", + ], + deps = [ + "//packages/pyalice", + ], +) +``` + +Now you can run the application inside the `~/isaac/sdk/` folder by typing: + +```bash +$ bazel run packages/dashboard_example:py_dashboard_example +``` + +You should now see a popup message on the teach pendant with the message `This message +is added from an Isaac application`. + +The below example can be used to power on a robot and playing the currently loaded +program right after starting your application. You can copy the content below into +`py_dashboard_example.py` to use this example. + +```Python +import time +from packages.pyalice import Application +from packages.universal_robots.ur_msg.ur_msg_python import do_dashboard_command + +app = Application(name="Sample dashboard client") + +app.load("packages/universal_robots/ur_robot_driver/apps/ur_eseries_robot.subgraph.json", prefix="ur") + +# Remember to set the robots IP address +ur_driver = app.nodes["ur.universal_robots"]["UniversalRobots"] +ur_driver.config.robot_ip = "192.168.56.1" + +app.start() + +# Make sure the driver is running +time.sleep(5) + +# The following can be used make sure the robot is powered on. +anwser = do_dashboard_command(app, "powerOn") +if anwser is not None: + print(anwser.anwser) + print(anwser.success) + +robot_mode = do_dashboard_command(app, "robotmode") +timeout = 10.0 +wait_time = 0.0 +while wait_time < timeout: + robot_mode = do_dashboard_command(app, "robotmode") + if robot_mode is not None: + if robot_mode.anwser == "Robotmode: IDLE" or robot_mode.anwser == "Robotmode: RUNNING": + break + + time.sleep(0.1) + wait_time += 0.1 + +# Now we can brakerelease the robot +anwser = do_dashboard_command(app, "brakeRelease") +if anwser is not None: + print(anwser.anwser) + print(anwser.success) + +robot_mode = do_dashboard_command(app, "robotmode") +timeout = 10.0 +wait_time = 0.0 +while wait_time < timeout: + robot_mode = do_dashboard_command(app, "robotmode") + if robot_mode is not None and robot_mode.anwser == "Robotmode: RUNNING": + break + + time.sleep(0.1) + wait_time += 0.1 + +time.sleep(1) + +# Now we can play the currently loaded robot program +anwser = do_dashboard_command(app, "play") +if anwser is not None: + print(anwser.anwser) + print(anwser.success) + +app.stop() +``` + +**NOTE** Remember to update the robot_ip to the IP address on which the Isaac driver +can reach the robot. + +Now you can run the application inside the `~/isaac/sdk/` folder by typing: + +```bash +$ bazel run packages/dashboard_example:py_dashboard_example +``` + +After running the above example the robot should be powered on and the currently +loaded program should start playing. + +This is just a quick example on how to use the DashboardClientIsaac, but serves +as inspiration on how to use DashboardClientIsaac to interact with the robot +without interacting with the teach pendant. diff --git a/ur_msg/dashboardCommand.cpp b/ur_msg/dashboardCommand.cpp new file mode 100644 index 0000000..e5d009b --- /dev/null +++ b/ur_msg/dashboardCommand.cpp @@ -0,0 +1,185 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "dashboardCommand.hpp" +#include "engine/core/assert.hpp" + +namespace isaac +{ +namespace dashboard_command +{ +DashboardCommand FromProto(const ::DashboardCommandProto::DashboardCommand command) +{ + switch (command) + { + case ::DashboardCommandProto::DashboardCommand::LOAD: + return DashboardCommand::load; + case ::DashboardCommandProto::DashboardCommand::PLAY: + return DashboardCommand::play; + case ::DashboardCommandProto::DashboardCommand::STOP: + return DashboardCommand::stop; + case ::DashboardCommandProto::DashboardCommand::PAUSE: + return DashboardCommand::pause; + case ::DashboardCommandProto::DashboardCommand::QUIT: + return DashboardCommand::quit; + case ::DashboardCommandProto::DashboardCommand::SHUTDOWN: + return DashboardCommand::shutdown; + case ::DashboardCommandProto::DashboardCommand::RUNNING: + return DashboardCommand::running; + case ::DashboardCommandProto::DashboardCommand::ROBOTMODE: + return DashboardCommand::robotmode; + case ::DashboardCommandProto::DashboardCommand::GET_LOADED_PROGRAM: + return DashboardCommand::getLoadedProgram; + case ::DashboardCommandProto::DashboardCommand::POPUP: + return DashboardCommand::popup; + case ::DashboardCommandProto::DashboardCommand::CLOSE_POPUP: + return DashboardCommand::closePopup; + case ::DashboardCommandProto::DashboardCommand::ADD_TO_LOG: + return DashboardCommand::addToLog; + case ::DashboardCommandProto::DashboardCommand::IS_PROGRAM_SAVED: + return DashboardCommand::isProgramSaved; + case ::DashboardCommandProto::DashboardCommand::PROGRAM_STATE: + return DashboardCommand::programState; + case ::DashboardCommandProto::DashboardCommand::POLYSCOPE_VERSION: + return DashboardCommand::polyscopeVersion; + case ::DashboardCommandProto::DashboardCommand::SET_OPERATIONAL_MODE: + return DashboardCommand::setOperationalMode; + case ::DashboardCommandProto::DashboardCommand::GET_OPERATIONAL_MODE: + return DashboardCommand::getOperationalMode; + case ::DashboardCommandProto::DashboardCommand::CLEAR_OPERATIONAL_MODE: + return DashboardCommand::clearOperationalMode; + case ::DashboardCommandProto::DashboardCommand::POWER_ON: + return DashboardCommand::powerOn; + case ::DashboardCommandProto::DashboardCommand::POWER_OFF: + return DashboardCommand::powerOff; + case ::DashboardCommandProto::DashboardCommand::BRAKE_RELEASE: + return DashboardCommand::brakeRelease; + case ::DashboardCommandProto::DashboardCommand::SAFETYSTATUS: + return DashboardCommand::safetystatus; + case ::DashboardCommandProto::DashboardCommand::UNLOCK_PROTECTIVE_STOP: + return DashboardCommand::unlockProtectiveStop; + case ::DashboardCommandProto::DashboardCommand::CLOSE_SAFETY_POPUP: + return DashboardCommand::closeSafetyPopup; + case ::DashboardCommandProto::DashboardCommand::LOAD_INSTALLATION: + return DashboardCommand::loadInstallation; + case ::DashboardCommandProto::DashboardCommand::RESTART_SAFETY: + return DashboardCommand::restartSafety; + case ::DashboardCommandProto::DashboardCommand::IS_IN_REMOTE_CONTROL: + return DashboardCommand::isInRemoteControl; + case ::DashboardCommandProto::DashboardCommand::GET_SERIAL_NUMBER: + return DashboardCommand::getSerialNumber; + case ::DashboardCommandProto::DashboardCommand::GET_ROBOT_MODEL: + return DashboardCommand::getRobotModel; + case ::DashboardCommandProto::DashboardCommand::SAFETYMODE: + return DashboardCommand::safetymode; + case ::DashboardCommandProto::DashboardCommand::SET_USER_ROLE: + return DashboardCommand::setUserRole; + case ::DashboardCommandProto::DashboardCommand::GET_USER_ROLE: + return DashboardCommand::getUserRole; + default: + PANIC("Unknown command %x", command); + } +} + +::DashboardCommandProto::DashboardCommand ToProto(const DashboardCommand command) +{ + switch (command) + { + case DashboardCommand::load: + return ::DashboardCommandProto::DashboardCommand::LOAD; + case DashboardCommand::stop: + return ::DashboardCommandProto::DashboardCommand::STOP; + case DashboardCommand::play: + return ::DashboardCommandProto::DashboardCommand::PLAY; + case DashboardCommand::pause: + return ::DashboardCommandProto::DashboardCommand::PAUSE; + case DashboardCommand::quit: + return ::DashboardCommandProto::DashboardCommand::QUIT; + case DashboardCommand::shutdown: + return ::DashboardCommandProto::DashboardCommand::SHUTDOWN; + case DashboardCommand::running: + return ::DashboardCommandProto::DashboardCommand::RUNNING; + case DashboardCommand::robotmode: + return ::DashboardCommandProto::DashboardCommand::ROBOTMODE; + case DashboardCommand::getLoadedProgram: + return ::DashboardCommandProto::DashboardCommand::GET_LOADED_PROGRAM; + case DashboardCommand::popup: + return ::DashboardCommandProto::DashboardCommand::POPUP; + case DashboardCommand::closePopup: + return ::DashboardCommandProto::DashboardCommand::CLOSE_POPUP; + case DashboardCommand::addToLog: + return ::DashboardCommandProto::DashboardCommand::ADD_TO_LOG; + case DashboardCommand::isProgramSaved: + return ::DashboardCommandProto::DashboardCommand::IS_PROGRAM_SAVED; + case DashboardCommand::programState: + return ::DashboardCommandProto::DashboardCommand::PROGRAM_STATE; + case DashboardCommand::polyscopeVersion: + return ::DashboardCommandProto::DashboardCommand::POLYSCOPE_VERSION; + case DashboardCommand::setOperationalMode: + return ::DashboardCommandProto::DashboardCommand::SET_OPERATIONAL_MODE; + case DashboardCommand::getOperationalMode: + return ::DashboardCommandProto::DashboardCommand::GET_OPERATIONAL_MODE; + case DashboardCommand::clearOperationalMode: + return ::DashboardCommandProto::DashboardCommand::CLEAR_OPERATIONAL_MODE; + case DashboardCommand::powerOn: + return ::DashboardCommandProto::DashboardCommand::POWER_ON; + case DashboardCommand::powerOff: + return ::DashboardCommandProto::DashboardCommand::POWER_OFF; + case DashboardCommand::brakeRelease: + return ::DashboardCommandProto::DashboardCommand::BRAKE_RELEASE; + case DashboardCommand::safetystatus: + return ::DashboardCommandProto::DashboardCommand::SAFETYSTATUS; + case DashboardCommand::unlockProtectiveStop: + return ::DashboardCommandProto::DashboardCommand::UNLOCK_PROTECTIVE_STOP; + case DashboardCommand::closeSafetyPopup: + return ::DashboardCommandProto::DashboardCommand::CLOSE_SAFETY_POPUP; + case DashboardCommand::loadInstallation: + return ::DashboardCommandProto::DashboardCommand::LOAD_INSTALLATION; + case DashboardCommand::restartSafety: + return ::DashboardCommandProto::DashboardCommand::RESTART_SAFETY; + case DashboardCommand::isInRemoteControl: + return ::DashboardCommandProto::DashboardCommand::IS_IN_REMOTE_CONTROL; + case DashboardCommand::getSerialNumber: + return ::DashboardCommandProto::DashboardCommand::GET_SERIAL_NUMBER; + case DashboardCommand::getRobotModel: + return ::DashboardCommandProto::DashboardCommand::GET_ROBOT_MODEL; + case DashboardCommand::safetymode: + return ::DashboardCommandProto::DashboardCommand::SAFETYMODE; + case DashboardCommand::setUserRole: + return ::DashboardCommandProto::DashboardCommand::SET_USER_ROLE; + case DashboardCommand::getUserRole: + return ::DashboardCommandProto::DashboardCommand::GET_USER_ROLE; + default: + PANIC("Unknown command %x", command); + } +} + +} // namespace dashboard_command +} // namespace isaac \ No newline at end of file diff --git a/ur_msg/dashboardCommand.hpp b/ur_msg/dashboardCommand.hpp new file mode 100644 index 0000000..8a89dca --- /dev/null +++ b/ur_msg/dashboardCommand.hpp @@ -0,0 +1,98 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include + +#include "packages/universal_robots/ur_msg/dashboard_command.capnp.h" + +namespace isaac +{ +namespace dashboard_command +{ +/*! + * \brief Enum holding all dashboard commands available. + * For documentation about the dashboardserver see + * - https://www.universal-robots.com/articles/ur/dashboard-server-e-series-port-29999/ + * - https://www.universal-robots.com/articles/ur/dashboard-server-cb-series-port-29999/ + */ +enum class DashboardCommand +{ + load, // Load program + play, // Play program + stop, // Stop program + pause, // Pause program + quit, // Disconnect client + shutdown, // Shut down robot + running, // Programm running? + robotmode, // Current robot mode + getLoadedProgram, // Returns loaded program + popup, // Show popup + closePopup, // Close popup + addToLog, // Add message to log + isProgramSaved, // Is current program saved? + programState, // Returns current program state + polyscopeVersion, // Polyscope version number + setOperationalMode, // Set operational mode + getOperationalMode, // Returns curretn operationalmode + clearOperationalMode, // Dashboard server no longer controls operational mode + powerOn, // Power on robot + powerOff, // Power down robot + brakeRelease, // Brake release + safetystatus, // Current safetystatus + unlockProtectiveStop, // Unlocks protective stop + closeSafetyPopup, // Close safety popup + loadInstallation, // Load installation + restartSafety, // Restart safety + isInRemoteControl, // Returns remote control status + getSerialNumber, // Returns serial number + getRobotModel, // Returns robot model + safetymode, // Current safetymode + setUserRole, // Set User role + getUserRole, // Get current user role +}; + +/*! + * \brief Parses command in proto message to a dashboardCommand. + * + * \param command Proto command. + */ +DashboardCommand FromProto(const ::DashboardCommandProto::DashboardCommand command); + +/*! + * \brief Creates type of command for Proto message + * + * \param command DashboardCommand. + */ +::DashboardCommandProto::DashboardCommand ToProto(const DashboardCommand command); + +} // namespace dashboard_command +} // namespace isaac \ No newline at end of file diff --git a/ur_msg/dashboard_command.capnp b/ur_msg/dashboard_command.capnp new file mode 100644 index 0000000..3475a39 --- /dev/null +++ b/ur_msg/dashboard_command.capnp @@ -0,0 +1,91 @@ +# -- BEGIN LICENSE BLOCK ---------------------------------------------- +# Copyright 2021 Universal Robots A/S +# +# 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. + +# All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +# Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +# OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +# NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +# MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +# CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +# OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +# USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +# Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +# appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +# published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +# in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +# please contact legal@universal-robots.com. +# -- END LICENSE BLOCK ------------------------------------------------ + +@0xfe6f9cc1919289ad; + +# A message to represent all dashboard commands available +# For documentation about the dashboard server see +# - https://www.universal-robots.com/articles/ur/dashboard-server-e-series-port-29999/ +# - https://www.universal-robots.com/articles/ur/dashboard-server-cb-series-port-29999/ +struct DashboardCommandProto +{ + # Enum holding all dashboard commands available. + enum DashboardCommand + { + load @0; # Load program + play @1; # Play program + stop @2; # Stop program + pause @3; # Pause program + quit @4; # Disconnect client + shutdown @5; # Shut down robot + running @6; # Programm running? + robotmode @7; # Current robot mode + getLoadedProgram @8; # Returns loaded program + popup @9; # Show popup + closePopup @10; # Close popup + addToLog @11; # Add message to log + isProgramSaved @12; # Is current program saved? + programState @13; # Returns current program state + polyscopeVersion @14; # Polyscope version number + setOperationalMode @15; # Set operational mode + getOperationalMode @16; # Returns curretn operationalmode + clearOperationalMode @17; # Dashboard server no longer controls operational mode + powerOn @18; # Power on robot + powerOff @19; # Power down robot + brakeRelease @20; # Brake release + safetystatus @21; # Current safety status + unlockProtectiveStop @22; # Unlocks protective stop + closeSafetyPopup @23; # Close safety popup + loadInstallation @24; # Load installation + restartSafety @25; # Restart safety + isInRemoteControl @26; # Returns remote control status + getSerialNumber @27; # Returns serial number + getRobotModel @28; # Returns robot model + safetymode @29; # Current safetymode + setUserRole @30; # Setting user role + getUserRole @31; # Get current user role + } + + # The request/command to send to the dashboardserver. + dashboardRequest @0: DashboardCommand; + + # Possible argument to the dashboard command can be empty. + argument @1: Text = ""; +} + +# A message to represent the status of a dashboard command. +struct DashboardCommandStatusProto +{ + # The anwser from the dashboard server. + anwser @0: Text; + + # Returns whether the command was a succes or not. + success @1: Bool; +} \ No newline at end of file diff --git a/ur_msg/speed_slider.capnp b/ur_msg/speed_slider.capnp new file mode 100644 index 0000000..8dbf8db --- /dev/null +++ b/ur_msg/speed_slider.capnp @@ -0,0 +1,39 @@ +# -- BEGIN LICENSE BLOCK ---------------------------------------------- +# Copyright 2021 Universal Robots A/S +# +# 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. + +# All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +# Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +# OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +# NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +# MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +# CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +# OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +# USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +# Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +# appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +# published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +# in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +# please contact legal@universal-robots.com. +# -- END LICENSE BLOCK ------------------------------------------------ + +@0x94c62233ca62cd8b; + +# Message to set the actual value of the speedslider. Values should be between +# 0 and 1. Only set this smaller than 1 if you are using the scaledMultiJointController +# or you know what you're doing. Using this with another controller might lead to unexpected behaviors. +struct SpeedSliderProto { + # The speed slider value + speedSliderValue @0 : Float32; +} \ No newline at end of file diff --git a/ur_msg/ur_msg_python.py b/ur_msg/ur_msg_python.py new file mode 100644 index 0000000..8a5c45a --- /dev/null +++ b/ur_msg/ur_msg_python.py @@ -0,0 +1,74 @@ +import glob +import capnp +import time +from packages.pyalice import Message + +def create_ur_msg_dictornary(): + """Load all the capnp'n'proto schemata in the ur_msg folder. The function will glob through all the + files with "*.capnp" extension name.""" + ur_msg_capnp_dict = {} + ur_msg_ur_capnp_files = glob.glob("packages/universal_robots/ur_msg/*.capnp") + for ur_msg_capnp_file in ur_msg_ur_capnp_files: + module = capnp.load(ur_msg_capnp_file) + for name, obj in module.__dict__.items(): + if obj.__class__.__name__ == "_StructModule": + ur_msg_capnp_dict[name] = obj + + return ur_msg_capnp_dict + +def ur_capnp_schema_type_id_dict(): + """Creates a dictionary which maps Capn'proto type ids to class schemata.""" + ur_msg_capnp_files = glob.glob("packages/universal_robots/ur_msg/*.capnp") + + result = {} + for ur_msg_capnp_f in ur_msg_capnp_files: + module = capnp.load(ur_msg_capnp_f) + for name, obj in module.__dict__.items(): + if obj.__class__.__name__ == "_StructModule": + assert name not in result + result[obj.schema.node.id] = obj + + return result + +UR_MSG_CAPNP_DICT = create_ur_msg_dictornary() +UR_MSG_CAPNP_TYPE_ID_DICT = ur_capnp_schema_type_id_dict() + +def create_ur_msg(msg_type): + """Creates a proto message for populating and publishing from specified proto name.""" + msg = Message.MessageBuilder() + msg.proto = UR_MSG_CAPNP_DICT[msg_type].new_message() + return msg + +def get_ur_msg(msg): + """Creates a wrapper for received message.""" + data = msg._message.get_capn_proto_bytes() + if data: + msg._proto = UR_MSG_CAPNP_TYPE_ID_DICT[msg.type_id].from_bytes(data) + return msg._proto + +def do_dashboard_command(app, command, arguments="", node="ur.subgraph", component="interface", timeout=5): + """Execute a dashboard command and waits for the result. + Returns None if no result could be received within timeout.""" + + dashboard_msg = create_ur_msg("DashboardCommandProto") + dashboard_msg.proto.dashboardRequest = command + dashboard_msg.proto.argument = arguments + cur_time = app.clock.time * 1000000000 # Turn into nano seconds + app.publish(node, component, "dashboard_command", dashboard_msg) + + # wait for a new message + wait_time = 0.0 + msg = None + while wait_time < timeout: + msg = app.receive(node, component, "dashboard_anwser") + if msg is not None and cur_time < msg.pubtime: + break + time.sleep(0.1) + wait_time += 0.1 + + if msg is None: + app.logger.warning("Failed to receive anwser from DashboardClientIsaac") + return None + + dc_response = get_ur_msg(msg) + return dc_response \ No newline at end of file diff --git a/ur_robot_driver/CHANGELOG.rst b/ur_robot_driver/CHANGELOG.rst deleted file mode 100644 index bb2ab23..0000000 --- a/ur_robot_driver/CHANGELOG.rst +++ /dev/null @@ -1,22 +0,0 @@ -0.0.3 (2019-08-09) ------------------- -* Added a service to end ROS control from ROS side -* Publish IO state on ROS topics -* Added write channel through RTDE with speed slider and IO services -* Added subscriber to send arbitrary URScript commands to the robot - -0.0.2 (2019-07-03) ------------------- -* Fixed dependencies and installation -* Updated README -* Fixed passing parameters through launch files -* Added support for correctly switching controllers during runtime and using the standard - joint_trajectory_controller -* Updated externalcontrol URCap to version 1.0.2 - + Fixed Script timeout when running the URCap inside of a looping tree - + Fixed a couple of typos -* Increased minimal required UR software version to 3.7/5.1 - -0.0.1 (2019-06-28) ------------------- -Initial release diff --git a/ur_robot_driver/CMakeLists.txt b/ur_robot_driver/CMakeLists.txt deleted file mode 100644 index 7ccd3cb..0000000 --- a/ur_robot_driver/CMakeLists.txt +++ /dev/null @@ -1,66 +0,0 @@ -cmake_minimum_required(VERSION 2.8.12) -project(ur_robot_driver) - -#add_definitions( -DROS_BUILD ) - -if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) - message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.") - set(CMAKE_BUILD_TYPE RelWithDebInfo) -endif() - -find_package(Boost REQUIRED) - -# check c++11 / c++0x -include(CheckCXXCompilerFlag) -check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11) -check_cxx_compiler_flag("-std=c++0x" COMPILER_SUPPORTS_CXX0X) -if(COMPILER_SUPPORTS_CXX11) - add_compile_options(-std=c++11) -elseif(COMPILER_SUPPORTS_CXX0X) - add_compile_options(-std=c++0x) -else() - message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler. Suggested solution: update the pkg build-essential ") -endif() - -add_compile_options(-Wall) -add_compile_options(-Wextra) -add_compile_options(-Wno-unused-parameter) - - -include_directories( - include - ${Boost_INCLUDE_DIRS} -) - -add_library(ur_robot_driver - src/comm/tcp_socket.cpp - src/comm/server.cpp - src/primary/primary_package.cpp - src/primary/robot_message.cpp - src/primary/robot_message/version_message.cpp - src/primary/robot_state/kinematics_info.cpp - src/rtde/control_package_pause.cpp - src/rtde/control_package_setup_inputs.cpp - src/rtde/control_package_setup_outputs.cpp - src/rtde/control_package_start.cpp - src/rtde/data_package.cpp - src/rtde/get_urcontrol_version.cpp - src/rtde/request_protocol_version.cpp - src/rtde/rtde_package.cpp - src/rtde/text_message.cpp - src/rtde/rtde_client.cpp - src/ur/ur_driver.cpp - src/ur/calibration_checker.cpp - src/ur/dashboard_client.cpp - src/ur/tool_communication.cpp - src/rtde/rtde_writer.cpp -) -target_link_libraries(ur_robot_driver) -#add_dependencies(ur_robot_driver ${${PROJECT_NAME}_EXPORTED_TARGETS}) - -#install(TARGETS ur_robot_driver -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -#) - diff --git a/ur_robot_driver/DashboardClientIsaac.cpp b/ur_robot_driver/DashboardClientIsaac.cpp new file mode 100644 index 0000000..59d02df --- /dev/null +++ b/ur_robot_driver/DashboardClientIsaac.cpp @@ -0,0 +1,314 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include + +#include "DashboardClientIsaac.hpp" +#include "UrclLogHandler.hpp" + +namespace isaac +{ +namespace ur_driver +{ +void DashboardClientIsaac::start() +{ + registerUrclLogHandler(); + + const auto robot_ip = try_get_robot_ip(); + if (!robot_ip) + { + reportFailure("No IP address was specified unable to start driver"); + return; + } + + dc_client_.reset(new urcl::DashboardClient(get_robot_ip())); + dc_client_->connect(); + + getVersion(); + + // Setup tick + tickOnMessage(rx_dashboard_command()); +} + +void DashboardClientIsaac::tick() +{ + // Receive and execute dashboard command + auto proto = rx_dashboard_command().getProto(); + dashboard_command::DashboardCommand command = dashboard_command::FromProto(proto.getDashboardRequest()); + Response resp = handleCommand(command, proto.getArgument()); + + // Publish anwser + auto proto_sender = tx_dashboard_anwser().initProto(); + proto_sender.setAnwser(resp.anwser); + proto_sender.setSuccess(resp.success); + tx_dashboard_anwser().publish(); +} + +void DashboardClientIsaac::stop() +{ + dc_client_->disconnect(); + dc_client_.reset(); +} + +DashboardClientIsaac::Response DashboardClientIsaac::handleCommand(const dashboard_command::DashboardCommand& command, + const std::string& argument) +{ + switch (command) + { + case dashboard_command::DashboardCommand::load: + return executeCommand("load " + argument + "\n", "Loading program: (.*)"); + case dashboard_command::DashboardCommand::stop: + return executeCommand("stop\n", "Stopped"); + case dashboard_command::DashboardCommand::play: + return executeCommand("play\n", "Starting program"); + case dashboard_command::DashboardCommand::pause: + return executeCommand("pause\n", "Pausing program"); + case dashboard_command::DashboardCommand::quit: + return executeCommand("quit\n", "Disconnected"); + case dashboard_command::DashboardCommand::shutdown: + return executeCommand("shutdown\n", "Shutting down"); + case dashboard_command::DashboardCommand::running: + return executeCommand("running\n", "Program running: (.*)"); + case dashboard_command::DashboardCommand::robotmode: + return executeCommand("robotmode\n", "Robotmode: (.*)"); + case dashboard_command::DashboardCommand::getLoadedProgram: + return executeCommand("get loaded program\n", "Loaded program: (.*)"); + case dashboard_command::DashboardCommand::popup: + return executeCommand("popup " + argument + "\n", "showing popup"); + case dashboard_command::DashboardCommand::closePopup: + return executeCommand("close popup\n", "closing popup"); + case dashboard_command::DashboardCommand::addToLog: + return executeCommand("addToLog " + argument + "\n", "(Added log message|No log message to add)"); + case dashboard_command::DashboardCommand::isProgramSaved: + return executeCommand("isProgramSaved\n", "(true|false) (.*)"); + case dashboard_command::DashboardCommand::programState: + return executeCommand("programState\n", "(STOPPED|PLAYING|PAUSED) (.*)"); + case dashboard_command::DashboardCommand::polyscopeVersion: + return executeCommand("PolyscopeVersion\n", "URSoftware (.*)"); + case dashboard_command::DashboardCommand::setOperationalMode: + if (major_version_ >= 5) + { + return executeCommand("set operational mode " + argument + "\n", "Operational mode ('manual'|'automatic') is " + "set"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::getOperationalMode: + if (major_version_ == 5 && minor_version_ >= 6) + { + return executeCommand("get operational mode\n", "(MANUAL|AUTOMATIC|NONE)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::clearOperationalMode: + if (major_version_ == 5) + { + return executeCommand("clear operational mode\n", "No longer controlling the operational mode. (.*)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::powerOn: + return executeCommand("power on\n", "Powering on"); + case dashboard_command::DashboardCommand::powerOff: + return executeCommand("power off\n", "Powering off"); + case dashboard_command::DashboardCommand::brakeRelease: + return executeCommand("brake release\n", "Brake releasing"); + case dashboard_command::DashboardCommand::safetystatus: + if (major_version_ == 5 && minor_version_ >= 4) + { + return executeCommand("safetystatus\n", "Safetystatus: (.*)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::unlockProtectiveStop: + return executeCommand("unlock protective stop\n", "Protective stop releasing"); + case dashboard_command::DashboardCommand::closeSafetyPopup: + return executeCommand("close safety popup\n", "closing safety popup"); + case dashboard_command::DashboardCommand::loadInstallation: + return executeCommand("load installation " + argument + "\n", "Loading installation: (.*)"); + case dashboard_command::DashboardCommand::restartSafety: + return executeCommand("restart safety\n", "Restarting safety"); + case dashboard_command::DashboardCommand::isInRemoteControl: + if (major_version_ == 5 && minor_version_ >= 6) + { + return executeCommand("is in remote control\n", "(true|false)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::getSerialNumber: + if ((major_version_ == 5 && minor_version_ >= 6) || (major_version_ == 3 && minor_version_ >= 12)) + { + return executeCommand("get serial number\n", "\\d+"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::getRobotModel: + if ((major_version_ == 5 && minor_version_ >= 6) || (major_version_ == 3 && minor_version_ >= 12)) + { + return executeCommand("get robot model\n", "(UR3|UR5|UR10|UR16)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::safetymode: + return executeCommand("safetymode\n", "Safetymode: (.*)"); + case dashboard_command::DashboardCommand::setUserRole: + if (major_version_ == 3) + { + return executeCommand("setUserRole " + argument + "\n", "Setting user role: (.*)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + case dashboard_command::DashboardCommand::getUserRole: + if (major_version_ == 3) + { + return executeCommand("getUserRole\n", "(PROGRAMMER|OPERATOR|NONE|LOCKED|RESTRICTED)"); + } + else + { + Response resp; + resp.anwser = "Command not supported for current software version: major " + std::to_string(major_version_) + + " minor " + std::to_string(minor_version_); + resp.success = false; + return resp; + } + default: + PANIC("Unknown command %x", command); + } +} + +DashboardClientIsaac::Response DashboardClientIsaac::executeCommand(const std::string& command, + const std::string& expected) +{ + Response resp; + if (dc_client_->getState() == urcl::comm::SocketState::Connected) + { + resp.anwser = dc_client_->sendAndReceive(command); + resp.success = std::regex_match(resp.anwser, std::regex(expected)); + } + else + { + LOG_INFO("reconnecting"); + if (dc_client_->connect()) + { + resp.anwser = dc_client_->sendAndReceive(command); + resp.success = std::regex_match(resp.anwser, std::regex(expected)); + } + else + { + resp.anwser = "failed to connect to dashboard server, unable to send command"; + resp.success = false; + } + } + return resp; +} + +void DashboardClientIsaac::getVersion() +{ + std::smatch match; + std::string anwser = dc_client_->sendAndReceive("PolyscopeVersion\n"); + std::regex_search(anwser, match, std::regex("\\d+\\.\\d+\\.\\d+\\.\\d+")); + if (match.empty()) + { + reportFailure("Unable to get polyscope version"); + } + + const std::regex base_regex("\\d+"); + std::smatch base_match; + if (std::regex_search(anwser, base_match, base_regex)) + { + major_version_ = std::atoi(base_match[0].str().c_str()); + anwser = base_match.suffix(); + } + else + { + reportFailure("Unable to get major version"); + } + + if (std::regex_search(anwser, base_match, base_regex)) + { + minor_version_ = std::atoi(base_match[0].str().c_str()); + anwser = base_match.suffix(); + } + else + { + reportFailure("Unable to get minor version"); + } +} + +} // namespace ur_driver +} // namespace isaac \ No newline at end of file diff --git a/ur_robot_driver/DashboardClientIsaac.hpp b/ur_robot_driver/DashboardClientIsaac.hpp new file mode 100644 index 0000000..a21fb36 --- /dev/null +++ b/ur_robot_driver/DashboardClientIsaac.hpp @@ -0,0 +1,130 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include "engine/alice/alice_codelet.hpp" +#include "ur_client_library/ur/dashboard_client.h" +#include "packages/universal_robots/ur_msg/dashboardCommand.hpp" +#include "packages/universal_robots/ur_msg/dashboard_command.capnp.h" + +namespace isaac +{ +namespace ur_driver +{ +/*! + * \brief The dashboardClientIsaac class is the interface between the dashboardserver and an Isaac application. + * Almost all the dashboard commands can be sent through this codelet to the dashboardserver and this codelet, + * will return the anwser to the application. + */ + +class DashboardClientIsaac : public isaac::alice::Codelet +{ +public: + /*! + * \brief Handles the setup functionality of this class. This includes setting up dashboardclient object. + */ + void start() override; + /*! + * \brief This functions is run when a new message is received. It sends the dashboard command to the dashboard server + * receives the anwser and publishing the anwser to the application. + */ + void tick() override; + + /*! + * \brief Disconnects from the dashboard server + */ + void stop() override; + + /*! + * \brief Receiving the dashboard command, which is forwarded to the dashboard server. + */ + ISAAC_PROTO_RX(DashboardCommandProto, dashboard_command); + + /*! + * \brief Channel to publish the anwser from the dashbordserver and whether the command was a success. + */ + ISAAC_PROTO_TX(DashboardCommandStatusProto, dashboard_anwser); + + /*! + * \brief The ip address of the robot. + */ + ISAAC_PARAM(std::string, robot_ip); + +private: + /*! + * \brief Struct representing the anwser from the dasboardserver. + * + * \param anwser String storing the anwser from the dashboardserver. + * \param success Representing if the command was a success. + */ + struct Response + { + std::string anwser; + bool success; + }; + + /*! + * \brief Handles the dashboard command, by changing the command with the correct string, + * that is then send to the dashboardserver. + * + * \param command Dashboard command + * \param argument argument to the dashboard command. + */ + Response handleCommand(const dashboard_command::DashboardCommand& command, const std::string& argument); + + /*! + * \brief Sends the command to dashboard server and receives the anwser. + * It matches the anwser with the expected anwser, to see if the command was a success. + * + * \param command The string command to send. + * \param expected The expected anwser as a string. + */ + Response executeCommand(const std::string& command, const std::string& expected); + + /*! + * \brief Used to retrieve polyscope version, in order to make sure commands that is not available in current version + * arent't executed. + */ + void getVersion(); + + // Dashboardclient object. + std::unique_ptr dc_client_; + + int major_version_; + int minor_version_; + + bool initialized_; +}; + +} // namespace ur_driver +} // namespace isaac + +ISAAC_ALICE_REGISTER_CODELET(isaac::ur_driver::DashboardClientIsaac) \ No newline at end of file diff --git a/ur_robot_driver/LICENSE b/ur_robot_driver/LICENSE deleted file mode 100644 index c35b007..0000000 --- a/ur_robot_driver/LICENSE +++ /dev/null @@ -1,180 +0,0 @@ -Copyright 2019 FZI Forschungszentrum Informatik - - 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 - - diff --git a/ur_robot_driver/README.md b/ur_robot_driver/README.md index 0529c9e..7d87669 100644 --- a/ur_robot_driver/README.md +++ b/ur_robot_driver/README.md @@ -1,57 +1,169 @@ -# ur_robot_driver +# ur_robot_driver -This package contains the actual driver for UR robots. It is part of the *universal_robots_driver* -repository and requires other packages from that repository. Also, see the [main repository's -README](../README.md) for information on how to install and startup this driver. +This package contains the actual driver for UR robots. It is part of the +**Universal_Robots_Isaac_Driver** repository and requires other packages from that +repository. Also, see the [main repository's README](../README.md) for information +on how to setup and startup +this driver. -## ROS-API -The ROS API is documented in a [standalone document](doc/ROS_INTERFACE.md). It is auto-generated -using [catkin_doc](https://github.com/fzi-forschungszentrum-informatik/catkin_doc). +## Isaac API + +This folder comes with 2 codelets: + +- **UniversalRobots** The UniversalRobots codelet handles the interface between +an Isaac application and the main driver, which can be found in the +[client library](https://github.com/UniversalRobots/Universal_Robots_Client_Library). +It is publishing actual robot and IO state and receiving IO and arm commands. + +- **DashboardClientIsaac** The dashboardClientIsaac class is an interface between +the dashboardserver on the robot and an Isaac application. This codelet is started +through the UniversalRobots codelet. For further details on how to use it [see documentation](../ur_msg/README.md#DashboardClientIsaac-usage). + +The components are further documented in a [standalone document](doc/component_api.md) +together with other components from this repository. + +### Subgraph + +This driver comes with 2 subgraphs, which sets up all the nescarry parts to use the +driver in an application. + +- One subgraph for the [e-series robots](apps/ur_eseries_robot.subgraph.json) + +- One subgraph for the [cb3 robots](apps/ur_cb3_robot.subgraph.json) + +These subgraphs integrates +[UniversalRobots](UniversalRobots.hpp), [DashboardClientIsaac](DashboardClientIsaac.hpp) +[ScaledMultiJointController](../ur_controller/ScaledMultiJointController.hpp), +[MultiJointLqrPlanner](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-planner-multijointplanner) +and [KinematicTree](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-map-kinematictree) +components. The subgraphs provides the following interface edges: + +- **joint_target(input)**: "subgraph/interface/joint_target" + +- **stop_control(input)**: "subgraph/interface/stop_control" + +- **set_speed_slider(input)**: "subgraph/interface/set_speed_slider" + +- **io_command(input)**: "subgraph/interface/io_command" + +- **resend_control_script(input)**: "subgraph/interface/resend_control_script" + +- **dashboard_command(input)**: "subgraph/interface/dashboard_command" + +- **dashboard_anwser(output)**: "subgraph/interface/dashboard_anwser" + +- **io_state(output)**: "subgraph/interface/io_state" + +- **arm_state(output)**: "subgraph/interface/arm_state" + +- **robot_program_running(output)**: "subgraph/interface/robot_program_running" + +- **trajectory_executed_succesfully(output)**: "subgraph/interface/trajectory_executed_succesfully" + +### Kinematic tree + +Isaac SDK uses [kinematic trees](https://docs.nvidia.com/isaac/isaac/doc/manipulation/kinematics.html) +to represent robot arms inside Isaac application. Currently there is only a kinematic +tree representation of a UR10 robot. It can be found in Isaac SDK folder in +`"apps/assets/kinematic_trees/ur_10.kinematic.json"`. + +When using [MultiJointLqrPlanner](https://docs.nvidia.com/isaac/isaac/doc/doc/component_api.html#isaac-planner-multijointplanner) +all calculation are done in the joint space, meaning no kinematics calculation are +applied. Then it's fine to use this file for all UR robot sizes. + +It is recommended to update the kinematic file before applying forward or inverse +kinematics calculation. ## Technical details -The following image shows a very coarse overview of the driver's architecture. + +The following image shows a very coarse overview of the drivers architecture: ![Architecture overview](doc/architecture_coarse.svg "Architecture overview") -Upon connection to the primary interface the robot sends version and calibration information which -is consumed by the *calibration_check*. If the calibration reported by the robot doesn't match the -one configured (See [calibration guide](../ur_calibration/README.md)) an error will be printed to Roslog. - -Real-time data from the robot is read through the RTDE interface. This is done automatically as soon -as a connection to the robot could be established. Thus joint states and IO data will be immediately -available. - -To actually control the robot, a program node from the **External Control** URCap must be running on -the robot interpreting commands sent from an external source. When this program is not running, no -controllers moving the robot around will be available, which is handled by the -[controller_stopper](../controller_stopper/README.md). Please see the [initial setup -guide](../README.md) on how to install and start this on the robot. - -The URScript that will be running on the robot is requested by the **External Control** program node -from the remote ROS PC. The robot *ur_control.launch* file has a parameter called `urscript_file` to -select a different program than the default one that will be sent as a response to a program -request. - -**Custom script snippets** can be sent to the robot on a topic basis. By default, they will -interrupt other programs (such as the one controlling the robot). For a certain subset of functions, -it is however possible to send them as secondary programs. See [UR -documentation](https://www.universal-robots.com/how-tos-and-faqs/how-to/ur-how-tos/secondary-program-17257/) -on details. -
-**Note to e-Series users:** -The robot won't accept script code from a remote source unless the robot is put into -*remote_control-mode*. However, if put into *remote_control-mode*, the program containing the -**External Control** program node can't be started from the panel. -For this purpose, please use the **dashboard** services to load, start and stop the main program -running on the robot. See the [ROS-API documentation](doc/ROS_INTERFACE.md) for details on the -dashboard services. - -For using the **tool communication interface** on e-Series robots, a `socat` script is prepared to -forward the robot's tool communication interface to a local device on the ROS PC. See [the tool -communication setup guide](doc/setup_tool_communication.md) for details. - -This driver is using [ROS-Control](https://wiki.ros.org/ros_control) for any control statements. -Therefor, it can be used with all position-based controllers available in ROS-Control. However, we -recommend using the controllers from the `ur_controllers` package. See it's -[documentation](../ur_controllers/README.md) for details. **Note: Speed scaling support will only be -available using the controllers from `ur_controllers`** +The calibration check is not implemented yet. So for now an error will be printed +to the log upon startup. + +Real-time data from the robot is read through the RTDE interface. This is done +automatically as soon as a connection to the robot could be established. Thus joint +states and IO data will be immediately available. + +To actually control the robot, a program node from the **External Control** URCap +must be running on the robot interpreting commands sent from an external source. +When this program is not running, no controller moving the robot around will be +available, which is handled by the [controller_stopper](../controller_stopper/README.md). +Please see the [initial setup guide](../README.md) on how to install and start the +URCap on the robot. + +The URScript that will be running on the robot is requested by the **External Control** +program node from the remote ROS PC. A parameter **control_script_program** can +be used to select a different program than the default one that will be sent as +a response to a program request. + +This driver is using [Manipulation Motion Planning](https://docs.nvidia.com/isaac/isaac/doc/manipulation/motion_planning.html) +for any control statements. Therefor, it can be used with all manipulation controllers +available in Isaac SDK. However, we recommend using the controller from the `ur_controller` +package. See it's [documentation](../ur_controllers/README.md) for details. **Note: +Speed scaling support will only be available using the controller from `ur_controller`** + +## A note about modes + +The term **mode** is used in different meanings inside this driver. + +### Remote control mode + +On the e-series the robot itself can operate in different command modes: It can +be either in **local control mode** where the teach pendant is the single point +of command or in **remote control mode**, where motions from the TP, starting & +loading programs from the TP activating the freedrive mode are blocked. Note that +the **remote control mode** has to be explicitly enabled in the robot's settings +under **Settings** -> **System** -> **Remote Control**. See the robot's manual for +details. + +The **remote control mode** is needed for many aspects of this driver such as + +- headless mode (see below) + +- many dashboard functionalities such as: + + - Powering on the robot and doing brake release + + - Loading and starting programs + +### Headless mode + +Inside this driver, there's the **headless** mode, which can be either enabled or +not. When the headless mode is activated, required script +code for external control will be sent to the robot directly when the driver starts. +As soon as other script code is sent to the robot, the script will be overwritten +by this action and has to be restarted by sending a signal to [resend_robot_program](./doc/component_api.md) +channel. If this is necessary, you will see the output `Connection to robot dropped, +waiting for new connection.` from the driver. Note that pressing "play" on the TP +won't start the external control again, but whatever program is currently loaded +on the controller. This mode doesn't require the "External Control" URCap being +installed on the robot as the program is sent to the robot directly. However, we +recommend to use the non-headless mode. The **headless** mode might be removed +in future releases. + +**Note for the e-Series:** In order to leverage the **headless** mode on the e-Series +the robot must be in **remote_control_mode** as explained above. + +## Log handler + +The C++ client library comes with its own logging interface. To adjust that logging +interface to make use of Isaac logging a LogHandler has been created. +The `UrclLogHandler` handles messages logged in the C++ client library with Isaac +logging. This loghandler is automatically configured in `UniversalRobots` and `DashboardClientIsaac`. + +If you are to use the client library in another node in Isaac, below example can +be used to register the loghandler and set the loglevel: + +```c++ +#include "UrclLogHandler.hpp" + +int main(int argc, char* argv[]) +{ + // Initialize UrclLogHandler + urcl::setLogLevel(urcl::LogLevel::DEBUG); + isaac::ur_driver::registerUrclLogHandler(); +} +``` diff --git a/UniversalRobots.cpp b/ur_robot_driver/UniversalRobots.cpp similarity index 53% rename from UniversalRobots.cpp rename to ur_robot_driver/UniversalRobots.cpp index 65ff376..adc04a0 100644 --- a/UniversalRobots.cpp +++ b/ur_robot_driver/UniversalRobots.cpp @@ -28,16 +28,19 @@ // please contact legal@universal-robots.com. // -- END LICENSE BLOCK ------------------------------------------------ -#include "ur_robot_driver/rtde/get_urcontrol_version.h" -#include "ur_robot_driver/rtde/data_package.h" +#include "ur_client_library/rtde/get_urcontrol_version.h" +#include "ur_client_library/rtde/data_package.h" #include "UniversalRobots.hpp" - -#include "engine/gems/kinematic_tree/kinematic_tree.hpp" +#include "packages/universal_robots/controller_stopper/ControllerStopper.hpp" #include "packages/map/KinematicTree.hpp" +#include "engine/alice/backend/backend.hpp" +#include "engine/alice/backend/node_backend.hpp" +#include "UrclLogHandler.hpp" +#include "DashboardClientIsaac.hpp" namespace isaac { -namespace universal_robots +namespace ur_driver { namespace { @@ -46,10 +49,21 @@ constexpr int kNumJoints = 6; // number of joints void UniversalRobots::handle_program_state(bool program_running) { + if (program_running && robot_program_running_ == false) + { + trajectory_reset_necessary_ = true; + } + robot_program_running_ = program_running; + publish_program_state_ = true; } void UniversalRobots::start() { + // Initialize UrclLogHandler and set loglevel + registerUrclLogHandler(); + urcl::setLogLevel(urcl::LogLevel::INFO); + logger::SetSeverity(logger::Severity::INFO); + // Try to get the map::KinematicTree component const auto maybe_kinematic_tree_node = try_get_kinematic_tree(); if (!maybe_kinematic_tree_node) @@ -72,35 +86,86 @@ void UniversalRobots::start() return; } + // Try to get the controller node + const auto controller_node_name = try_get_controller(); + if (!controller_node_name) + { + reportFailure("Controller node is not specified."); + return; + } + initControllerStopper(*controller_node_name); + + const auto robot_ip = try_get_robot_ip(); + if (!robot_ip) + { + reportFailure("No IP address was specified unable to start driver"); + return; + } + LOG_INFO("Connecting to robot at %s", get_robot_ip().c_str()); + // Configure and start dashboard client + dashboard_client_started_ = false; + const auto dashboard_node = try_get_dashboard_client(); + if (dashboard_node) + { + LOG_INFO("Initializing dashboard client"); + const auto dashboard_component = node()->app()->getNodeComponentOrNull(*dashboard_node); + if (dashboard_component) + { + dashboard_client_ = node()->app()->findNodeByName(*dashboard_node); + dashboard_component->async_set_robot_ip(get_robot_ip()); + node()->app()->backend()->node_backend()->startNode(dashboard_client_); + dashboard_client_started_ = true; + } + else + { + LOG_WARNING("Node doesn't contain dashboard client component. Unable to start it, you wont be able to send " + "commands to the dashboard server through the application"); + } + } + // Set up driver - static const bool HEADLESS_MODE = true; + static const bool HEADLESS_MODE = get_headless_mode(); static const std::string CALIB_CHECKSUM = ""; - ur_driver = new ur_driver::UrDriver(get_robot_ip(), get_control_script_program(), get_rtde_output_recipe(), - get_rtde_input_recipe(), - std::bind(&UniversalRobots::handle_program_state, this, std::placeholders::_1), - HEADLESS_MODE, NULL, CALIB_CHECKSUM, 50001, 50002, 200, 0.03, - // true //non blocking mode - false // blocking mode - ); + LOG_INFO("Initializing ur driver"); + try + { + ur_driver_.reset(new urcl::UrDriver( + get_robot_ip(), get_control_script_program(), get_rtde_output_recipe(), get_rtde_input_recipe(), + std::bind(&UniversalRobots::handle_program_state, this, std::placeholders::_1), HEADLESS_MODE, NULL, + CALIB_CHECKSUM, 50001, 50002, get_servoj_gain(), get_servoj_lookahead_time(), false)); + } + catch (urcl::UrException& e) + { + reportFailure("failed to create ur driver object error: [%s]", e.what()); + return; + } // Init internal state initStateSchema(); initIOSchema(); + initTrajectorySchema(); initIOCommandParser(); control_mode_ = kInvalid; pausing_ramp_up_increment_ = 0.01; pausing_state_ = PausingState::RUNNING; + trajectory_reset_necessary_ = false; + publish_program_state_ = false; + robot_program_running_ = false; + runtime_state_ = static_cast(urcl::rtde_interface::RUNTIME_STATE::STOPPED); // Connect to RTDE - ur_driver->startRTDECommunication(); + ur_driver_->startRTDECommunication(); LOG_INFO("Waiting to receive the first RTDE data"); while (!updateRobotState()) ; // TODO add count limit LOG_INFO("First RTDE data received"); - RTDEMainLoopTrd = std::thread(&UniversalRobots::RTDEMainLoop, this); + rtde_main_loop_trd_ = std::thread(&UniversalRobots::RTDEMainLoop, this); + + // Set number of allowed timeout reads on the robot. + ur_driver_->setKeepaliveCount(3); // Setup tick tickPeriodically(); @@ -108,18 +173,32 @@ void UniversalRobots::start() void UniversalRobots::tick() { - if (rx_arm_command().available()) + uint32_t runtime_state; { - const int64_t time = rx_arm_command().acqtime(); - bool isFirstMessage = !last_command_time_; - bool unseenMessage = time > *last_command_time_; - if (isFirstMessage || unseenMessage) + std::lock_guard guard(runtime_mutex_); + runtime_state = runtime_state_; + } + if ((runtime_state == static_cast(urcl::rtde_interface::RUNTIME_STATE::PLAYING) || + runtime_state == static_cast(urcl::rtde_interface::RUNTIME_STATE::PAUSING)) && + robot_program_running_) + { + if (controller_node_->getStage() != alice::LifecycleStage::kStarted) { - last_command_time_ = time; - parseCommand(get_control_mode()); + // Keep the connection alive if the controller is not running + ur_driver_->writeKeepalive(); + } + else if (rx_arm_command().available()) + { + const int64_t time = rx_arm_command().acqtime(); + bool isFirstMessage = !last_command_time_; + bool unseenMessage = time > *last_command_time_; + if (isFirstMessage || unseenMessage) + { + last_command_time_ = time; + parseCommand(get_control_mode()); + } } } - if (rx_io_command().available()) { const int64_t time = rx_io_command().acqtime(); @@ -131,15 +210,56 @@ void UniversalRobots::tick() parseIOCommand(); } } - + if (rx_stop_control().available()) + { + const int64_t time = rx_stop_control().acqtime(); + bool isFirstMessage = !last_stop_control_time_; + bool unseenMessage = time > *last_stop_control_time_; + if (isFirstMessage || unseenMessage) + { + last_stop_control_time_ = time; + stopControl(); + } + } + if (rx_set_speed_slider().available()) + { + const int64_t time = rx_set_speed_slider().acqtime(); + bool isFirstMessage = !last_speed_slider_time_; + bool unseenMessage = time > *last_speed_slider_time_; + if (isFirstMessage || unseenMessage) + { + last_speed_slider_time_ = time; + setSpeedSlider(); + } + } + if (rx_resend_control_script().available()) + { + const int64_t time = rx_resend_control_script().acqtime(); + bool isFirstMessage = !last_resend_control_script_time_; + bool unseenMessage = time > *last_resend_control_script_time_; + if (isFirstMessage || unseenMessage) + { + last_resend_control_script_time_ = time; + resendControlScript(); + } + } publishState(); + if (publish_program_state_) + { + publishProgramState(); + } } void UniversalRobots::stop() { - ur_driver->stopControl(); - rtde_thread_running = false; - delete ur_driver; + if (dashboard_client_started_) + { + node()->app()->backend()->node_backend()->stopNode(dashboard_client_); + } + ur_driver_->stopControl(); + rtde_thread_running_ = false; + rtde_main_loop_trd_.join(); + ur_driver_.reset(); } bool UniversalRobots::validateKinematicTree(const kinematic_tree::KinematicTree& model) @@ -164,6 +284,21 @@ bool UniversalRobots::validateKinematicTree(const kinematic_tree::KinematicTree& return true; } +void UniversalRobots::initControllerStopper(const std::string controller_node_name) +{ + // Setup controller stopper node + alice::Node* controller_stopper_node = node()->app()->createMessageNode("controller_stopper_node"); + auto controller_stopper = controller_stopper_node->addComponent(); + controller_stopper->async_set_controller(controller_node_name); + + Connect(tx_robot_program_running(), controller_stopper->rx_robot_program_running()); + + node()->app()->backend()->node_backend()->startNode(controller_stopper_node); + + // Get the controller node, used to check if the node is running. + controller_node_ = node()->app()->getNodeByName(controller_node_name); +} + void UniversalRobots::initCommandParser(const ArmControlMode mode) { switch (mode) @@ -187,9 +322,9 @@ void UniversalRobots::initIOCommandParser() io_names, composite::Measure::kNone)); // Set to rotation so it's controllable by joint controller } -ur_driver::vector6d_t toVector6D(const VectorXd q_in) +urcl::vector6d_t toVector6D(const VectorXd q_in) { - ur_driver::vector6d_t q; + urcl::vector6d_t q; for (unsigned int i = 0; i < kNumJoints; ++i) q[i] = q_in(i); @@ -218,18 +353,12 @@ void UniversalRobots::parseCommand(const ArmControlMode mode) if (parse_success) { - ur_driver::vector6d_t q_command = toVector6D(command); - - // Show targets from command - for (unsigned int i = 0; i < q_command.size(); ++i) - { - show(joint_names_[i], q_command[i]); - } + urcl::vector6d_t q_command = toVector6D(command); if (mode == kJointPosition) - ur_driver->writeJointCommand(q_command, ur_driver::comm::ControlMode::MODE_SERVOJ); + ur_driver_->writeJointCommand(q_command, urcl::comm::ControlMode::MODE_SERVOJ); else if (mode == kJointSpeed) - ur_driver->writeJointCommand(q_command, ur_driver::comm::ControlMode::MODE_SPEEDJ); + ur_driver_->writeJointCommand(q_command, urcl::comm::ControlMode::MODE_SPEEDJ); } else { @@ -245,7 +374,7 @@ void UniversalRobots::parseIOCommand() if (parse_success) { - ur_driver::rtde_interface::RTDEWriter& rtdeWriter = ur_driver->getRTDEWriter(); + urcl::rtde_interface::RTDEWriter& rtdeWriter = ur_driver_->getRTDEWriter(); rtdeWriter.sendToolDigitalOutput(0, io_command(0) != 0.0 ? true : false); rtdeWriter.sendToolDigitalOutput(1, io_command(1) != 0.0 ? true : false); } @@ -258,10 +387,13 @@ void UniversalRobots::parseIOCommand() void UniversalRobots::initStateSchema() { std::vector quantities; + std::vector target_quantities; + // Add joint positions for (int i = 0; i < kNumJoints; i++) { quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); + target_quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); } // Add joint velocities @@ -277,6 +409,7 @@ void UniversalRobots::initStateSchema() // fraction state_schema_ = composite::Schema(std::move(quantities)); + target_state_schema_ = composite::Schema(std::move(target_quantities)); } void UniversalRobots::initIOSchema() @@ -302,15 +435,30 @@ void UniversalRobots::initIOSchema() io_schema_ = composite::Schema(std::move(quantities)); } +void UniversalRobots::initTrajectorySchema() +{ + std::vector quantities; + + quantities.push_back(composite::Quantity::Scalar("time", composite::Measure::kTime)); + for (unsigned int i = 0; i < kNumJoints; ++i) + { + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kPosition)); + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kSpeed)); + quantities.push_back(composite::Quantity::Scalar(joint_names_[i], composite::Measure::kAcceleration)); + } + composite::Schema schema = composite::Schema(std::move(quantities)); + trajectory_serializer_.setSchema(schema); +} + // The speed scaling is normally just the target speed fraction set by the user in // the UI multiplied with the speed scale used by the robot to comply with limits. // But in some cases (depending on robot state) the logic is a little more convoluted -bool UniversalRobots::updateSpeedScale(ur_driver::rtde_interface::DataPackage* data_pkg) +bool UniversalRobots::updateSpeedScale(urcl::rtde_interface::DataPackage* data_pkg) { bool rtde_read_succeed(false); double target_speed_fraction(0.0); double speed_scaling(0.0); - uint32_t runtime_state(0); + uint32_t runtime_state = 0; rtde_read_succeed = data_pkg->getData("target_speed_fraction", target_speed_fraction); rtde_read_succeed = data_pkg->getData("speed_scaling", speed_scaling); @@ -319,12 +467,12 @@ bool UniversalRobots::updateSpeedScale(ur_driver::rtde_interface::DataPackage* d if (rtde_read_succeed) { // pausing state follows runtime state when pausing - if (runtime_state == static_cast(ur_driver::rtde_interface::RUNTIME_STATE::PAUSED)) + if (runtime_state == static_cast(urcl::rtde_interface::RUNTIME_STATE::PAUSED)) { pausing_state_ = PausingState::PAUSED; } // When the robot resumed program execution and pausing state was PAUSED, we enter RAMPUP - else if (runtime_state == static_cast(ur_driver::rtde_interface::RUNTIME_STATE::PLAYING) && + else if (runtime_state == static_cast(urcl::rtde_interface::RUNTIME_STATE::PLAYING) && pausing_state_ == PausingState::PAUSED) { speed_scaling_combined_ = 0.0; @@ -341,7 +489,7 @@ bool UniversalRobots::updateSpeedScale(ur_driver::rtde_interface::DataPackage* d pausing_state_ = PausingState::RUNNING; } } - else if (runtime_state == static_cast(ur_driver::rtde_interface::RUNTIME_STATE::RESUMING)) + else if (runtime_state == static_cast(urcl::rtde_interface::RUNTIME_STATE::RESUMING)) { // We have to keep speed scaling during RESUMING to prevent controllers from continuing to interpolate speed_scaling_combined_ = 0.0; @@ -352,6 +500,10 @@ bool UniversalRobots::updateSpeedScale(ur_driver::rtde_interface::DataPackage* d speed_scaling_combined_ = speed_scaling * target_speed_fraction; } } + { + std::lock_guard guard(runtime_mutex_); + runtime_state_ = runtime_state; + } return rtde_read_succeed; } @@ -359,36 +511,40 @@ bool UniversalRobots::updateSpeedScale(ur_driver::rtde_interface::DataPackage* d bool UniversalRobots::updateRobotState() { bool rtde_read_succeed(false); - std::unique_ptr data_pkg; + std::unique_ptr data_pkg; - if (data_pkg = ur_driver->getDataPackage()) + if (ur_driver_) { - RobotState newState; - rtde_read_succeed = data_pkg->getData("timestamp", newState.timestamp); - rtde_read_succeed = data_pkg->getData("target_q", newState.q) && rtde_read_succeed; - rtde_read_succeed = data_pkg->getData("target_qd", newState.qd) && rtde_read_succeed; - rtde_read_succeed = - data_pkg->getData("actual_digital_input_bits", newState.actual_dig_in_bits) && rtde_read_succeed; - rtde_read_succeed = - data_pkg->getData("actual_digital_output_bits", newState.actual_dig_out_bits) && rtde_read_succeed; + if (data_pkg = ur_driver_->getDataPackage()) + { + RobotState newState; + rtde_read_succeed = data_pkg->getData("timestamp", newState.timestamp); + rtde_read_succeed = data_pkg->getData("actual_q", newState.q) && rtde_read_succeed; + rtde_read_succeed = data_pkg->getData("actual_qd", newState.qd) && rtde_read_succeed; + rtde_read_succeed = + data_pkg->getData("actual_digital_input_bits", newState.actual_dig_in_bits) && rtde_read_succeed; + rtde_read_succeed = + data_pkg->getData("actual_digital_output_bits", newState.actual_dig_out_bits) && rtde_read_succeed; - rtde_read_succeed = updateSpeedScale(data_pkg.get()) && rtde_read_succeed; + rtde_read_succeed = updateSpeedScale(data_pkg.get()) && rtde_read_succeed; - newState.speed_fraction = speed_scaling_combined_; + newState.speed_fraction = speed_scaling_combined_; - if (rtde_read_succeed) - { - std::lock_guard guard(robotStateMutex); - latestRobotState = newState; + if (rtde_read_succeed) + { + std::lock_guard guard(robot_state_mutex_); + latest_robot_state_ = newState; + } } } + return rtde_read_succeed; } void UniversalRobots::RTDEMainLoop() { - rtde_thread_running = true; - while (rtde_thread_running) + rtde_thread_running_ = true; + while (rtde_thread_running_) { updateRobotState(); } @@ -423,6 +579,12 @@ void UniversalRobots::publishRobotState(RobotState robotStateSnapshot) state_data(offset + 0) = robotStateSnapshot.timestamp; state_data(offset + 1) = robotStateSnapshot.speed_fraction; + // Show current joint position + for (unsigned int i = 0; i < kNumJoints; ++i) + { + show(joint_names_[i], state_data[i]); + } + const auto misc_names = get_misc_names(); show(misc_names[0], robotStateSnapshot.timestamp); show(misc_names[1], robotStateSnapshot.speed_fraction); @@ -433,14 +595,14 @@ void UniversalRobots::publishRobotState(RobotState robotStateSnapshot) void UniversalRobots::publishIOState(RobotState robotStateSnapshot) { - // Publish io to Isaac + // Publish IO to Isaac auto proto_builder = tx_io_state().initProto(); composite::WriteSchema(io_schema_, proto_builder); const auto io_out_names = get_tool_digital_out_names(); const auto io_in_names = get_tool_digital_in_names(); - // allocate tensor1d to store io data + // Allocate tensor1d to store io data Tensor1d io_data(io_out_names.size() + io_in_names.size()); io_data(0) = ((robotStateSnapshot.actual_dig_out_bits & 0x10000) != 0) ? 1.0 : 0.0; @@ -466,13 +628,92 @@ void UniversalRobots::publishState() { RobotState robotStateSnapshot; { - std::lock_guard guard(robotStateMutex); - robotStateSnapshot = latestRobotState; + std::lock_guard guard(robot_state_mutex_); + robotStateSnapshot = latest_robot_state_; } + if (trajectory_reset_necessary_) + { + publishJointTrajectory(robotStateSnapshot); + } publishRobotState(robotStateSnapshot); publishIOState(robotStateSnapshot); } -} // namespace universal_robots +void UniversalRobots::publishJointTrajectory(RobotState robotStateSnapshot) +{ + auto proto_builder = tx_trajectory().initProto(); + Timeseries, double> trajectory; + + // Create a trajectory that keeps the robot in the current position + for (unsigned int i = 0; i < 10; ++i) + { + Vector state; + state[0] = getTickTime() + i * 0.1; + int offset = 1; + for (unsigned int j = 0; j < kNumJoints; ++j) + { + state[offset] = robotStateSnapshot.q[j]; // position + state[offset + 1] = 0.0; // velocity + state[offset + 2] = 0.0; // acceleration + offset += 3; + } + trajectory.tryPush(state[0], state); + } + trajectory_serializer_.serialize(trajectory, composite::Quantity::Scalar("time", composite::Measure::kTime), + proto_builder, tx_trajectory().buffers()); + tx_trajectory().publish(); + trajectory_reset_necessary_ = false; +} + +void UniversalRobots::publishProgramState() +{ + auto proto = tx_robot_program_running().initProto(); + proto.setFlag(robot_program_running_); + tx_robot_program_running().publish(); + publish_program_state_ = false; +} + +void UniversalRobots::stopControl() +{ + auto proto = rx_stop_control().getProto(); + if (proto.getFlag()) + { + if (robot_program_running_) + { + ur_driver_->stopControl(); + robot_program_running_ = false; + LOG_INFO("Stopped control of robot through Isaac"); + } + else + { + LOG_INFO("No control active nothing to do"); + } + } +} + +void UniversalRobots::setSpeedSlider() +{ + auto proto = rx_set_speed_slider().getProto(); + double speed_fraction = proto.getSpeedSliderValue(); + if (speed_fraction <= 1 && speed_fraction >= 0) + { + ur_driver_->getRTDEWriter().sendSpeedSlider(speed_fraction); + } + else + { + LOG_WARNING("speed slider value should be between 0 and 1"); + } +} + +void UniversalRobots::resendControlScript() +{ + auto proto = rx_resend_control_script().getProto(); + if (proto.getFlag() && get_headless_mode()) + { + ur_driver_->sendRobotProgram(); + } +} + +} // namespace ur_driver } // namespace isaac diff --git a/ur_robot_driver/UniversalRobots.hpp b/ur_robot_driver/UniversalRobots.hpp new file mode 100644 index 0000000..a0bab7b --- /dev/null +++ b/ur_robot_driver/UniversalRobots.hpp @@ -0,0 +1,398 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2020 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2020”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once +#include +#include +#include +#include + +#include "ur_client_library/ur/ur_driver.h" +#include "engine/alice/alice_codelet.hpp" +#include "packages/math/gems/kinematic_tree/kinematic_tree.hpp" +#include "packages/composite/gems/serializer.hpp" +#include "packages/composite/gems/parser.hpp" +#include "messages/composite.capnp.h" +#include "messages/basic.capnp.h" +#include "packages/universal_robots/ur_msg/speed_slider.capnp.h" + +namespace isaac +{ +namespace ur_driver +{ +/*! + * \brief Available control modes for arm. + */ +enum ArmControlMode +{ + kJointPosition, // Control joints position + kJointSpeed, // Control joints speed + kInvalid = -1 // Invalid control mode, returned from an invalid string in JSON +}; + +/*! + * \brief Mapping between each ArmControlMode type and an identifying string. + */ +NLOHMANN_JSON_SERIALIZE_ENUM(ArmControlMode, { { kInvalid, nullptr }, + { kJointPosition, "joint position" }, + { kJointSpeed, "joint speed" } }); + +/*! + * \brief Possible states for robot control + */ +enum class PausingState +{ + PAUSED, + RUNNING, + RAMPUP +}; + +/*! + * \brief The UniversalRobots class handles the interface between an Isaac application and + * the main driver. It is publishing actual robot and IO state and receiving IO and arm commands. + */ + +class UniversalRobots : public isaac::alice::Codelet +{ +public: + /*! + * \brief Handles the setup functionality. This includes collecting the kinematic tree and controller node, setting + * up the main driver object and connecting to the robot. + */ + void start() override; + + /*! + * \brief This functions is run cyclic with a fixed frequency. It checks whether a new message is available, + * in any of the incomming channels. In the end the robot and IO state is published. + */ + void tick() override; + + /*! + * \brief Used to stop the running thread and stop the drivers control of the robot. + */ + void stop() override; + + /*! + * \brief Receives command for arm, parsed based on control mode + */ + ISAAC_PROTO_RX(CompositeProto, arm_command); + + /*! + * \brief Receives IO command, to set any of the robot's IOs. + */ + ISAAC_PROTO_RX(CompositeProto, io_command); + + /*! + * \brief Receives a signal to stop control of robot through Isaac. The boolean flag needs to be true, + * to stop control of the robot through Isaac. This will make the "External Control" program node on the UR-Program + * return. + */ + ISAAC_PROTO_RX(BooleanProto, stop_control); + + /*! + * \brief Receives a signal to send the URScript program to the robot for execution, when the robot is in headless + * mode. The boolean flag needs to be true, to send the script. Use this after the program has been interrupted, e.g. + * by a protective- or EM-stop. + */ + ISAAC_PROTO_RX(BooleanProto, resend_control_script); + + /*! + * \brief Set the speed slider fraction used by the robot's execution. Values should be between 0 and 1. + * Only set this smaller than 1 if you are using the ur_controller or you know what you're + * doing. Using this with other controllers might lead to unexpected behaviors. + */ + ISAAC_PROTO_RX(SpeedSliderProto, set_speed_slider); + + /*! + * \brief Current state of the arm, includes joint angles, joint speeds and current speed fraction. + */ + ISAAC_PROTO_TX(CompositeProto, arm_state); + + /*! + * \brief Current IO state, includes digital inputs and outputs. + */ + ISAAC_PROTO_TX(CompositeProto, io_state); + + /*! + * \brief Whenever the runtime state of the "External Control" program node in the UR-program changes + * a message gets published. So this is equivalent to the information whether the robot + * accepts commands from Isaac side. + */ + ISAAC_PROTO_TX(BooleanProto, robot_program_running); + + /*! + * \brief Publish a trajectory to the controller to make sure the robots stays in the same position. The trajectory is + * published everytime "External Control" program node starts running. This used to make sure that the newest + * trajectory, is based upon the robots current position when Isaac starts controlling the robot. + */ + ISAAC_PROTO_TX(CompositeProto, trajectory); + + /*! + * \brief Name of the node containing the map:KinematicTree component. This is used to obtain the names + * of the joints for parsing/creating composite message. + */ + ISAAC_PARAM(std::string, kinematic_tree); + + /*! + * \brief Name of the node containing the controller component. + * This node is started and stopped based upon the drivers control status of the robot. + */ + ISAAC_PARAM(std::string, controller); + + /*! + * \brief Name of the node containing the dashboard component This is used to start the node and set the ip address. + * Nothing will happen if this parameter is kept empty. + */ + ISAAC_PARAM(std::string, dashboard_client); + + /*! + * \brief Set control mode for arm. + */ + ISAAC_PARAM(ArmControlMode, control_mode, kJointPosition); + + /*! + * \brief Name of speed_fraction and timestamp used for creating composite message. + */ + ISAAC_PARAM(std::vector, misc_names, std::vector({ "timestamp", "speed_fraction" })); + + /*! + * \brief Entity name for digital tool output. + */ + ISAAC_PARAM(std::vector, tool_digital_out_names, + std::vector({ "tool_digital_out_0", "tool_digital_out_1" })); + + /*! + * \brief Entity name for digital tool input. + */ + ISAAC_PARAM(std::vector, tool_digital_in_names, + std::vector({ "tool_digital_in_0", "tool_digital_in_1" })); + + /*! + * \brief Driver settings + * + * \param robot_ip Ip address of the robot. + * \param control_script_program URScript file that is sent to the robot. + * \param rtde_input_recipe Filename where the input recipe is stored in. + * \param rtde_output_recipe Filename where the output recipe is stored in. + * \param headless_mode Parameter to control if the driver should be started in headless mode. + * \param servoj_gain Specify gain for servoing to position in joint space. A higher gain can sharpen the trajectory. + * \param servoj_lookahead_time Specify lookahead time for servoing to position in joint space. A longer lookahead + * time can smooth the trajectory. + */ + ISAAC_PARAM(std::string, robot_ip); + ISAAC_PARAM(std::string, control_script_program, + "packages/universal_robots/ur_robot_driver/resources/ros_control.urscript"); + ISAAC_PARAM(std::string, rtde_input_recipe, + "packages/universal_robots/ur_robot_driver/resources/rtde_input_recipe.txt"); + ISAAC_PARAM(std::string, rtde_output_recipe, + "packages/universal_robots/ur_robot_driver/resources/rtde_output_recipe.txt"); + ISAAC_PARAM(bool, headless_mode, false); + ISAAC_PARAM(double, servoj_gain, 2000); + ISAAC_PARAM(double, servoj_lookahead_time, 0.03) + +private: + std::unique_ptr ur_driver_; + + /*! + * \brief Callback to handle a change in the current state of the URScript running on the robot. + * This function is called when the robot connects to the driver or when it disconnects from driver. + * + * \param program_running True when robot connects false when robot disconnects. + */ + void handle_program_state(bool program_running); + + /*! + * \brief Running thread which reads robot state data over RTDE connection. + */ + std::thread rtde_main_loop_trd_; + bool rtde_thread_running_; + void RTDEMainLoop(); + + /*! + * \brief Struct representing the robot state. + * + * \param timestamp Time elapsed since the controller was started. + * \param q Actual joint positions. + * \param qd Actual joint speeds. + * \param actual_dig_in_bits Current state of the digital inputs. + * \param actual_dig_out_bits Current state of the digital outputs. + * \param speed_fraction Current speed fraction. + */ + struct RobotState + { + double timestamp; + urcl::vector6d_t q, qd; + uint64_t actual_dig_in_bits, actual_dig_out_bits; + double speed_fraction; + }; + + /*! + * \brief Reads robot state over RTDE connection. + * + * \returns true on succes. + */ + std::mutex robot_state_mutex_; + bool updateRobotState(); + RobotState latest_robot_state_; + + /*! + * \brief Update the speed scaling depending on the robot state. + * + * \param data_pkg received RTDE Data package. + * + * \returns true on succes. + */ + PausingState pausing_state_; + double pausing_ramp_up_increment_; + double speed_scaling_combined_; + bool updateSpeedScale(urcl::rtde_interface::DataPackage* data_pkg); + + /*! + * \brief Validates the kinematic tree object is consistent with the hardware model + * + * \param model The kinematicTree model. + * + * \returns true on succes. + */ + bool validateKinematicTree(const kinematic_tree::KinematicTree& model); + + /*! + * \brief Initialize controller_stopper node, used to stop and start the Isaac controller. + * When the status goes to false, the controller is stopped. If status returns to true the stopped controller is + * restarted. + */ + void initControllerStopper(const std::string controller_node_name); + + /*! + * \brief Request a schema for parsing IO command and arm command based on control mode. + * + * \param mode Arm control mode. + */ + void initCommandParser(const ArmControlMode mode); + void initIOCommandParser(); + + /*! + * \brief Parse commands from Composite message + * + * \param mode Arm control mode. + */ + void parseCommand(const ArmControlMode mode); + void parseIOCommand(); + + /*! + * \brief Generate the composite schema for publishing messages. + */ + void initStateSchema(); + void initIOSchema(); + void initTrajectorySchema(); + + /*! + * \brief Publish current arm state and current IO state + * + * \param state Current robot state. + */ + void publishRobotState(RobotState state); + void publishIOState(RobotState state); + void publishState(); + + /*! + * \brief Publish a trajectory to the Isaac controller to make sure the robots stays in the same position. + * The trajectory is published everytime "External Control" program node starts running. + * + * \param state Current robot state. + */ + void publishJointTrajectory(RobotState state); + + /*! + * \brief Publishing program state. + */ + void publishProgramState(); + + /*! + * \brief Stop robot control. + */ + void stopControl(); + + /*! + * \brief Set the speed slider. + */ + void setSpeedSlider(); + + /*! + * \brief Resend the control script. + */ + void resendControlScript(); + + // Cache control mode. + ArmControlMode control_mode_; + + // Cache list of joint names + std::vector joint_names_; + + // Acquire time for most recently received message + std::optional last_command_time_; + std::optional last_io_command_time_; + std::optional last_stop_control_time_; + std::optional last_speed_slider_time_; + std::optional last_resend_control_script_time_; + + // Parsers for command message + composite::Parser command_parser_; + composite::Parser io_command_parser_; + + // Cache schema for state message + composite::Schema state_schema_; + composite::Schema io_schema_; + composite::Schema target_state_schema_; + + // Cache serialize for creating joint trajectory + composite::Serializer trajectory_serializer_; + + // Robots runtime state and bool to reflect if control script is running on the robot. + uint32_t runtime_state_; + std::mutex runtime_mutex_; + bool robot_program_running_; + + // Bool to reflect when to publish program state and trajectory reset. + bool publish_program_state_; + bool trajectory_reset_necessary_; + + // Node containing the controller + alice::Node* controller_node_; + + // Node containing the dashboard client used for starting and stopping the client along with the driver + alice::Node* dashboard_client_; + bool dashboard_client_started_; +}; + +} // namespace ur_driver +} // namespace isaac + +ISAAC_ALICE_REGISTER_CODELET(isaac::ur_driver::UniversalRobots); diff --git a/ur_robot_driver/UrclLogHandler.cpp b/ur_robot_driver/UrclLogHandler.cpp new file mode 100644 index 0000000..0398c02 --- /dev/null +++ b/ur_robot_driver/UrclLogHandler.cpp @@ -0,0 +1,88 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#include "UrclLogHandler.hpp" +#include "engine/core/logger.hpp" + +namespace isaac +{ +namespace ur_driver +{ + +bool g_initialized_ = false; +std::unique_ptr g_log_handler(new UrclLogHandler); + +UrclLogHandler::UrclLogHandler() = default; + +void UrclLogHandler::log(const char* file, int line, urcl::LogLevel loglevel, const char* message) +{ + switch (loglevel) + { + case urcl::LogLevel::INFO: + logger::LoggingFunction(file, line, logger::Severity::INFO, message); + break; + case urcl::LogLevel::DEBUG: + logger::LoggingFunction(file, line, logger::Severity::DEBUG, message); + break; + case urcl::LogLevel::WARN: + logger::LoggingFunction(file, line, logger::Severity::WARNING, message); + break; + case urcl::LogLevel::ERROR: + logger::LoggingFunction(file, line, logger::Severity::ERROR, message); + break; + case urcl::LogLevel::FATAL: + logger::LoggingFunction(file, line, logger::Severity::ERROR, message); + break; + default: + break; + } +} + +void registerUrclLogHandler() +{ + if (g_initialized_ == false) + { + urcl::setLogLevel(urcl::LogLevel::DEBUG); + urcl::registerLogHandler(std::move(g_log_handler)); + g_initialized_ = true; + } +} + +void unregisterUrclLogHandler() +{ + if (g_initialized_ == true) + { + urcl::unregisterLogHandler(); + g_initialized_ = false; + } +} + +} // namespace ur_driver +} // namespace isaac \ No newline at end of file diff --git a/ur_robot_driver/UrclLogHandler.hpp b/ur_robot_driver/UrclLogHandler.hpp new file mode 100644 index 0000000..cbb91c4 --- /dev/null +++ b/ur_robot_driver/UrclLogHandler.hpp @@ -0,0 +1,75 @@ +// -- BEGIN LICENSE BLOCK ---------------------------------------------- +// Copyright 2021 Universal Robots A/S +// +// 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. + +// All source code contained in and/or linked to in this message (the “Source Code”) is subject to the copyright of +// Universal Robots A/S and/or its licensors. THE SOURCE CODE IS PROVIDED “AS IS” WITHOUT WARRANTY OF ANY KIND, EXPRESS +// OR IMPLIED, INCLUDING – BUT NOT LIMITED TO – WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR +// NONINFRINGEMENT. USE OF THE SOURCE CODE IS AT YOUR OWN RISK AND UNIVERSAL ROBOTS A/S AND ITS LICENSORS SHALL, TO THE +// MAXIMUM EXTENT PERMITTED BY LAW, NOT BE LIABLE FOR ANY ERRORS OR MALICIOUS CODE IN THE SOURCE CODE, ANY THIRD-PARTY +// CLAIMS, OR ANY OTHER CLAIMS AND DAMAGES, INCLUDING INDIRECT, INCIDENTAL, SPECIAL, CONSEQUENTIAL OR PUNITIVE DAMAGES, +// OR ANY LOSS OF PROFITS, EXPECTED SAVINGS, OR REVENUES, WHETHER INCURRED DIRECTLY OR INDIRECTLY, OR ANY LOSS OF DATA, +// USE, GOODWILL, OR OTHER INTANGIBLE LOSSES, RESULTING FROM YOUR USE OF THE SOURCE CODE. You may make copies of the +// Source Code for use in connection with a Universal Robots or UR+ product, provided that you include (i) an +// appropriate copyright notice (“© [the year in which you received the Source Code or the Source Code was first +// published, e.g. “2021”] Universal Robots A/S and/or its licensors”) along with the capitalized section of this notice +// in all copies of the Source Code. By using the Source Code, you agree to the above terms. For more information, +// please contact legal@universal-robots.com. +// -- END LICENSE BLOCK ------------------------------------------------ + +#pragma once + +#include "ur_client_library/log.h" + +namespace isaac +{ +namespace ur_driver +{ +/*! + * \brief Loghandler for handling messages logged with the C++ client library. This loghandler will log the messages + * from the client library with Isaac logging. + * Use registerLogHandler to register this class, shouldn't be instansiated directly. + */ +class UrclLogHandler : public urcl::LogHandler +{ +public: + /*! + * \brief Default constructor + */ + UrclLogHandler(); + + /*! + * \brief Function to log a message + * + * \param file The log message comes from this file + * \param line The log message comes from this line + * \param loglevel Indicates the severity of the log message + * \param log Log message + */ + void log(const char* file, int line, urcl::LogLevel loglevel, const char* message) override; +}; + +/*! + * \brief Register the UrclLoghHandler, this will start logging messages from the client library with Isaac logging. + * This function has to be called inside your node, to enable the log handler. + */ +void registerUrclLogHandler(); + +/*! + * \brief Unregister the UrclLoghHandler, stop logging messages from the client library with Isaac logging. + */ +void unregisterUrclLogHandler(); + +} // namespace ur_driver +} // namespace isaac diff --git a/ur_robot_driver/apps/BUILD b/ur_robot_driver/apps/BUILD new file mode 100644 index 0000000..a783b12 --- /dev/null +++ b/ur_robot_driver/apps/BUILD @@ -0,0 +1,33 @@ +load("//bzl:module.bzl", "isaac_subgraph") + +isaac_subgraph( + name = "ur_eseries_robot_subgraph", + modules = [ + "//packages/universal_robots:universal_robots", + "map", + "planner", + "lqr", + "//packages/universal_robots/ur_controller:ur_controller", + ], + data = [ + "//apps/assets/kinematic_trees", + ], + subgraph = "ur_eseries_robot.subgraph.json", + visibility = ["//visibility:public"], +) + +isaac_subgraph( + name = "ur_cb3_robot_subgraph", + modules = [ + "//packages/universal_robots:universal_robots", + "map", + "planner", + "lqr", + "//packages/universal_robots/ur_controller:ur_controller", + ], + data = [ + "//apps/assets/kinematic_trees", + ], + subgraph = "ur_cb3_robot.subgraph.json", + visibility = ["//visibility:public"], +) \ No newline at end of file diff --git a/ur_robot_driver/apps/ur_cb3_robot.subgraph.json b/ur_robot_driver/apps/ur_cb3_robot.subgraph.json new file mode 100644 index 0000000..7f40e98 --- /dev/null +++ b/ur_robot_driver/apps/ur_cb3_robot.subgraph.json @@ -0,0 +1,243 @@ +{ + "modules": [ + "map", + "planner", + "lqr", + "//packages/universal_robots/ur_controller:ur_controller", + "//packages/universal_robots:universal_robots" + ], + "graph": { + "nodes": [ + { + "name": "subgraph", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "interface", + "type": "isaac::alice::Subgraph" + } + ] + }, + { + "name": "universal_robots", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "UniversalRobots", + "type": "isaac::ur_driver::UniversalRobots" + } + ] + }, + { + "name": "dashboard_client_isaac", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "DashboardClientIsaac", + "type": "isaac::ur_driver::DashboardClientIsaac" + } + ], + "disable_automatic_start": true + }, + { + "start_order": -100, + "name": "kinematic_tree", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "KinematicTree", + "type": "isaac::map::KinematicTree" + } + ] + }, + { + "name": "local_plan", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "MultiJointLqrPlanner", + "type": "isaac::lqr::MultiJointLqrPlanner" + }, + { + "name": "MultiJointPlanner", + "type": "isaac::planner::MultiJointPlanner" + } + ] + }, + { + "name": "controller", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "ScaledMultiJointController", + "type": "isaac::ur_controller::ScaledMultiJointController" + } + ] + } + ], + "edges": [ + { + "source": "universal_robots/UniversalRobots/arm_state", + "target": "local_plan/MultiJointPlanner/starting_state" + }, + { + "source": "local_plan/MultiJointPlanner/plan", + "target": "controller/ScaledMultiJointController/plan" + }, + { + "source": "controller/ScaledMultiJointController/joint_command", + "target": "universal_robots/UniversalRobots/arm_command" + }, + { + "source": "universal_robots/UniversalRobots/arm_state", + "target": "controller/ScaledMultiJointController/current_arm_state" + }, + { + "source": "universal_robots/UniversalRobots/trajectory", + "target": "controller/ScaledMultiJointController/plan" + }, + { + "source": "subgraph/interface/joint_target", + "target": "local_plan/MultiJointPlanner/target_state" + }, + { + "source": "controller/ScaledMultiJointController/trajectory_executed_succesfully", + "target": "subgraph/interface/trajectory_executed_succesfully" + }, + { + "source": "subgraph/interface/dashboard_command", + "target": "dashboard_client_isaac/DashboardClientIsaac/dashboard_command" + }, + { + "source": "dashboard_client_isaac/DashboardClientIsaac/dashboard_anwser", + "target": "subgraph/interface/dashboard_anwser" + }, + { + "source": "subgraph/interface/stop_control", + "target": "universal_robots/UniversalRobots/stop_control" + }, + { + "source": "subgraph/interface/set_speed_slider", + "target": "universal_robots/UniversalRobots/set_speed_slider" + }, + { + "source": "subgraph/interface/io_command", + "target": "universal_robots/UniversalRobots/io_command" + }, + { + "source": "subgraph/interface/resend_control_script", + "target": "universal_robots/UniversalRobots/resend_control_script" + }, + { + "source": "universal_robots/UniversalRobots/io_state", + "target": "subgraph/interface/io_state" + }, + { + "source": "universal_robots/UniversalRobots/arm_state", + "target": "subgraph/interface/arm_state" + }, + { + "source": "universal_robots/UniversalRobots/robot_program_running", + "target": "subgraph/interface/robot_program_running" + } + ] + }, + "config": { + "kinematic_tree": { + "KinematicTree": { + "kinematic_file": "apps/assets/kinematic_trees/ur10.kinematic.json" + } + }, + "universal_robots": { + "UniversalRobots": { + "tick_period": "125Hz", + "kinematic_tree": "$(fullname kinematic_tree)", + "controller": "$(fullname controller)", + "dashboard_client": "$(fullname dashboard_client_isaac)" + } + }, + "local_plan":{ + "MultiJointLqrPlanner": { + "speed_max": [1,1,1,1,1,1], + "speed_min": [-1,-1,-1,-1,-1,-1], + "acceleration_max": [1,1,1,1,1,1], + "acceleration_min": [-1,-1,-1,-1,-1,-1] + }, + "MultiJointPlanner": { + "tick_period": "10Hz", + "kinematic_tree_node_name": "$(fullname kinematic_tree)", + "multi_joint_planner_node_name": "$(fullname local_plan)" + } + }, + "controller": { + "ScaledMultiJointController": { + "goal_time": 0.6, + "tolerance": 0.1, + "tick_period": "125Hz", + "kinematic_tree": "$(fullname kinematic_tree)", + "gains": { + "shoulder_pan_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "shoulder_lift_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "elbow_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "wrist_1_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "wrist_2_joint": { + "p": 5, + "i": 0.05, + "d": 0.01, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "wrist_3_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + } + } + } + } + } +} diff --git a/ur_robot_driver/apps/ur_eseries_robot.subgraph.json b/ur_robot_driver/apps/ur_eseries_robot.subgraph.json new file mode 100644 index 0000000..a196c1f --- /dev/null +++ b/ur_robot_driver/apps/ur_eseries_robot.subgraph.json @@ -0,0 +1,243 @@ +{ + "modules": [ + "map", + "planner", + "lqr", + "//packages/universal_robots/ur_controller:ur_controller", + "//packages/universal_robots:universal_robots" + ], + "graph": { + "nodes": [ + { + "name": "subgraph", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "interface", + "type": "isaac::alice::Subgraph" + } + ] + }, + { + "name": "universal_robots", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "UniversalRobots", + "type": "isaac::ur_driver::UniversalRobots" + } + ] + }, + { + "name": "dashboard_client_isaac", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "DashboardClientIsaac", + "type": "isaac::ur_driver::DashboardClientIsaac" + } + ], + "disable_automatic_start": true + }, + { + "start_order": -100, + "name": "kinematic_tree", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "KinematicTree", + "type": "isaac::map::KinematicTree" + } + ] + }, + { + "name": "local_plan", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "MultiJointLqrPlanner", + "type": "isaac::lqr::MultiJointLqrPlanner" + }, + { + "name": "MultiJointPlanner", + "type": "isaac::planner::MultiJointPlanner" + } + ] + }, + { + "name": "controller", + "components": [ + { + "name": "ledger", + "type": "isaac::alice::MessageLedger" + }, + { + "name": "ScaledMultiJointController", + "type": "isaac::ur_controller::ScaledMultiJointController" + } + ] + } + ], + "edges": [ + { + "source": "universal_robots/UniversalRobots/arm_state", + "target": "local_plan/MultiJointPlanner/starting_state" + }, + { + "source": "local_plan/MultiJointPlanner/plan", + "target": "controller/ScaledMultiJointController/plan" + }, + { + "source": "controller/ScaledMultiJointController/joint_command", + "target": "universal_robots/UniversalRobots/arm_command" + }, + { + "source": "universal_robots/UniversalRobots/arm_state", + "target": "controller/ScaledMultiJointController/current_arm_state" + }, + { + "source": "universal_robots/UniversalRobots/trajectory", + "target": "controller/ScaledMultiJointController/plan" + }, + { + "source": "subgraph/interface/joint_target", + "target": "local_plan/MultiJointPlanner/target_state" + }, + { + "source": "controller/ScaledMultiJointController/trajectory_executed_succesfully", + "target": "subgraph/interface/trajectory_executed_succesfully" + }, + { + "source": "subgraph/interface/dashboard_command", + "target": "dashboard_client_isaac/DashboardClientIsaac/dashboard_command" + }, + { + "source": "dashboard_client_isaac/DashboardClientIsaac/dashboard_anwser", + "target": "subgraph/interface/dashboard_anwser" + }, + { + "source": "subgraph/interface/resend_control_script", + "target": "universal_robots/UniversalRobots/resend_control_script" + }, + { + "source": "subgraph/interface/stop_control", + "target": "universal_robots/UniversalRobots/stop_control" + }, + { + "source": "subgraph/interface/set_speed_slider", + "target": "universal_robots/UniversalRobots/set_speed_slider" + }, + { + "source": "subgraph/interface/io_command", + "target": "universal_robots/UniversalRobots/io_command" + }, + { + "source": "universal_robots/UniversalRobots/io_state", + "target": "subgraph/interface/io_state" + }, + { + "source": "universal_robots/UniversalRobots/arm_state", + "target": "subgraph/interface/arm_state" + }, + { + "source": "universal_robots/UniversalRobots/robot_program_running", + "target": "subgraph/interface/robot_program_running" + } + ] + }, + "config": { + "kinematic_tree": { + "KinematicTree": { + "kinematic_file": "apps/assets/kinematic_trees/ur10.kinematic.json" + } + }, + "universal_robots": { + "UniversalRobots": { + "tick_period": "500Hz", + "kinematic_tree": "$(fullname kinematic_tree)", + "controller": "$(fullname controller)", + "dashboard_client": "$(fullname dashboard_client_isaac)" + } + }, + "local_plan":{ + "MultiJointLqrPlanner": { + "speed_max": [1,1,1,1,1,1], + "speed_min": [-1,-1,-1,-1,-1,-1], + "acceleration_max": [1,1,1,1,1,1], + "acceleration_min": [-1,-1,-1,-1,-1,-1] + }, + "MultiJointPlanner": { + "tick_period": "10Hz", + "kinematic_tree_node_name": "$(fullname kinematic_tree)", + "multi_joint_planner_node_name": "$(fullname local_plan)" + } + }, + "controller": { + "ScaledMultiJointController": { + "goal_time": 0.6, + "tolerance": 0.1, + "tick_period": "500Hz", + "kinematic_tree": "$(fullname kinematic_tree)", + "gains": { + "shoulder_pan_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "shoulder_lift_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "elbow_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "wrist_1_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "wrist_2_joint": { + "p": 5, + "i": 0.05, + "d": 0.01, + "i_clamp": 1, + "velocity_ff" : 1 + }, + "wrist_3_joint": { + "p": 5, + "i": 0.05, + "d": 0.1, + "i_clamp": 1, + "velocity_ff" : 1 + } + } + } + } + } +} diff --git a/ur_robot_driver/config/ur10_controllers.yaml b/ur_robot_driver/config/ur10_controllers.yaml deleted file mode 100644 index d90b0ca..0000000 --- a/ur_robot_driver/config/ur10_controllers.yaml +++ /dev/null @@ -1,141 +0,0 @@ -# Settings for ros_control control loop -hardware_control_loop: - loop_hz: &loop_hz 125 - -# Settings for ros_control hardware interface -hardware_interface: - joints: &robot_joints - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - -# Publish all joint states ---------------------------------- -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: *loop_hz - -# Publish wrench ---------------------------------- -force_torque_sensor_controller: - type: force_torque_sensor_controller/ForceTorqueSensorController - publish_rate: *loop_hz - -# Publish speed_scaling factor -speed_scaling_state_controller: - type: ur_controllers/SpeedScalingStateController - publish_rate: *loop_hz - -# Joint Trajectory Controller - position based ------------------------------- -# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller -scaled_pos_traj_controller: - type: position_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -pos_traj_controller: - type: position_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -scaled_vel_traj_controller: - type: velocity_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -vel_traj_controller: - type: velocity_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -# Pass an array of joint velocities directly to the joints -joint_group_vel_controller: - type: velocity_controllers/JointGroupVelocityController - joints: *robot_joints diff --git a/ur_robot_driver/config/ur10e_controllers.yaml b/ur_robot_driver/config/ur10e_controllers.yaml deleted file mode 100644 index b2c4632..0000000 --- a/ur_robot_driver/config/ur10e_controllers.yaml +++ /dev/null @@ -1,141 +0,0 @@ -# Settings for ros_control control loop -hardware_control_loop: - loop_hz: &loop_hz 500 - -# Settings for ros_control hardware interface -hardware_interface: - joints: &robot_joints - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - -# Publish all joint states ---------------------------------- -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: *loop_hz - -# Publish wrench ---------------------------------- -force_torque_sensor_controller: - type: force_torque_sensor_controller/ForceTorqueSensorController - publish_rate: *loop_hz - -# Publish speed_scaling factor -speed_scaling_state_controller: - type: ur_controllers/SpeedScalingStateController - publish_rate: *loop_hz - -# Joint Trajectory Controller - position based ------------------------------- -# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller -scaled_pos_traj_controller: - type: position_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -pos_traj_controller: - type: position_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -scaled_vel_traj_controller: - type: velocity_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -vel_traj_controller: - type: velocity_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -# Pass an array of joint velocities directly to the joints -joint_group_vel_controller: - type: velocity_controllers/JointGroupVelocityController - joints: *robot_joints diff --git a/ur_robot_driver/config/ur3_controllers.yaml b/ur_robot_driver/config/ur3_controllers.yaml deleted file mode 100644 index e6994ba..0000000 --- a/ur_robot_driver/config/ur3_controllers.yaml +++ /dev/null @@ -1,142 +0,0 @@ -# Settings for ros_control control loop -hardware_control_loop: - loop_hz: &loop_hz 125 - -# Settings for ros_control hardware interface -hardware_interface: - joints: &robot_joints - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - -# Publish all joint states ---------------------------------- -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: *loop_hz - -# Publish wrench ---------------------------------- -force_torque_sensor_controller: - type: force_torque_sensor_controller/ForceTorqueSensorController - publish_rate: *loop_hz - -# Publish speed_scaling factor -speed_scaling_state_controller: - type: ur_controllers/SpeedScalingStateController - publish_rate: *loop_hz - -# Joint Trajectory Controller - position based ------------------------------- -# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller -scaled_pos_traj_controller: - type: position_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -pos_traj_controller: - type: position_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - - -scaled_vel_traj_controller: - type: velocity_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -vel_traj_controller: - type: velocity_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -# Pass an array of joint velocities directly to the joints -joint_group_vel_controller: - type: velocity_controllers/JointGroupVelocityController - joints: *robot_joints diff --git a/ur_robot_driver/config/ur3e_controllers.yaml b/ur_robot_driver/config/ur3e_controllers.yaml deleted file mode 100644 index b2c4632..0000000 --- a/ur_robot_driver/config/ur3e_controllers.yaml +++ /dev/null @@ -1,141 +0,0 @@ -# Settings for ros_control control loop -hardware_control_loop: - loop_hz: &loop_hz 500 - -# Settings for ros_control hardware interface -hardware_interface: - joints: &robot_joints - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - -# Publish all joint states ---------------------------------- -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: *loop_hz - -# Publish wrench ---------------------------------- -force_torque_sensor_controller: - type: force_torque_sensor_controller/ForceTorqueSensorController - publish_rate: *loop_hz - -# Publish speed_scaling factor -speed_scaling_state_controller: - type: ur_controllers/SpeedScalingStateController - publish_rate: *loop_hz - -# Joint Trajectory Controller - position based ------------------------------- -# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller -scaled_pos_traj_controller: - type: position_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -pos_traj_controller: - type: position_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -scaled_vel_traj_controller: - type: velocity_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -vel_traj_controller: - type: velocity_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -# Pass an array of joint velocities directly to the joints -joint_group_vel_controller: - type: velocity_controllers/JointGroupVelocityController - joints: *robot_joints diff --git a/ur_robot_driver/config/ur5_controllers.yaml b/ur_robot_driver/config/ur5_controllers.yaml deleted file mode 100644 index d90b0ca..0000000 --- a/ur_robot_driver/config/ur5_controllers.yaml +++ /dev/null @@ -1,141 +0,0 @@ -# Settings for ros_control control loop -hardware_control_loop: - loop_hz: &loop_hz 125 - -# Settings for ros_control hardware interface -hardware_interface: - joints: &robot_joints - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - -# Publish all joint states ---------------------------------- -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: *loop_hz - -# Publish wrench ---------------------------------- -force_torque_sensor_controller: - type: force_torque_sensor_controller/ForceTorqueSensorController - publish_rate: *loop_hz - -# Publish speed_scaling factor -speed_scaling_state_controller: - type: ur_controllers/SpeedScalingStateController - publish_rate: *loop_hz - -# Joint Trajectory Controller - position based ------------------------------- -# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller -scaled_pos_traj_controller: - type: position_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -pos_traj_controller: - type: position_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -scaled_vel_traj_controller: - type: velocity_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -vel_traj_controller: - type: velocity_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -# Pass an array of joint velocities directly to the joints -joint_group_vel_controller: - type: velocity_controllers/JointGroupVelocityController - joints: *robot_joints diff --git a/ur_robot_driver/config/ur5e_controllers.yaml b/ur_robot_driver/config/ur5e_controllers.yaml deleted file mode 100644 index b2c4632..0000000 --- a/ur_robot_driver/config/ur5e_controllers.yaml +++ /dev/null @@ -1,141 +0,0 @@ -# Settings for ros_control control loop -hardware_control_loop: - loop_hz: &loop_hz 500 - -# Settings for ros_control hardware interface -hardware_interface: - joints: &robot_joints - - shoulder_pan_joint - - shoulder_lift_joint - - elbow_joint - - wrist_1_joint - - wrist_2_joint - - wrist_3_joint - -# Publish all joint states ---------------------------------- -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: *loop_hz - -# Publish wrench ---------------------------------- -force_torque_sensor_controller: - type: force_torque_sensor_controller/ForceTorqueSensorController - publish_rate: *loop_hz - -# Publish speed_scaling factor -speed_scaling_state_controller: - type: ur_controllers/SpeedScalingStateController - publish_rate: *loop_hz - -# Joint Trajectory Controller - position based ------------------------------- -# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller -scaled_pos_traj_controller: - type: position_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -pos_traj_controller: - type: position_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} - elbow_joint: {trajectory: 0.2, goal: 0.1} - wrist_1_joint: {trajectory: 0.2, goal: 0.1} - wrist_2_joint: {trajectory: 0.2, goal: 0.1} - wrist_3_joint: {trajectory: 0.2, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - -scaled_vel_traj_controller: - type: velocity_controllers/ScaledJointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -vel_traj_controller: - type: velocity_controllers/JointTrajectoryController - joints: *robot_joints - constraints: - goal_time: 0.6 - stopped_velocity_tolerance: 0.05 - shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} - shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} - elbow_joint: {trajectory: 0.1, goal: 0.1} - wrist_1_joint: {trajectory: 0.1, goal: 0.1} - wrist_2_joint: {trajectory: 0.1, goal: 0.1} - wrist_3_joint: {trajectory: 0.1, goal: 0.1} - stop_trajectory_duration: 0.5 - state_publish_rate: *loop_hz - action_monitor_rate: 10 - gains: - #!!These values have not been optimized!! - shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} - - # Use a feedforward term to reduce the size of PID gains - velocity_ff: - shoulder_pan_joint: 1.0 - shoulder_lift_joint: 1.0 - elbow_joint: 1.0 - wrist_1_joint: 1.0 - wrist_2_joint: 1.0 - wrist_3_joint: 1.0 - - # state_publish_rate: 50 # Defaults to 50 - # action_monitor_rate: 20 # Defaults to 20 - #stop_trajectory_duration: 0 # Defaults to 0.0 - -# Pass an array of joint velocities directly to the joints -joint_group_vel_controller: - type: velocity_controllers/JointGroupVelocityController - joints: *robot_joints diff --git a/ur_robot_driver/doc/ROS_INTERFACE.md b/ur_robot_driver/doc/ROS_INTERFACE.md deleted file mode 100644 index c33fa4f..0000000 --- a/ur_robot_driver/doc/ROS_INTERFACE.md +++ /dev/null @@ -1,1023 +0,0 @@ -# ur_robot_driver - -The new driver for Universal Robots UR3, UR5 and UR10 robots with CB3 controllers and the e-series. - -## Launchfiles -### ur3e_bringup.launch - -Standalone launchfile to startup a ur3e. This requires a robot reachable via a network connection. - -#### Arguments - * "**controller_config_file**" (default: "$(find ur_robot_driver)/config/ur3e_controllers.yaml") - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_common.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (default: "$(find ur_e_description)/config/ur3e_default.yaml") - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (default: "$(find ur_e_description)/launch/ur3e_upload.launch") - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - - * "**tool_baud_rate**" (default: "115200") - - Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_device_name**" (default: "/tmp/ttyUR") - - Local device name used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_parity**" (default: "0") - - Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_rx_idle_chars**" (default: "1.5") - - Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_stop_bits**" (default: "1") - - Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_tcp_port**" (default: "54321") - - Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true. - - * "**tool_tx_idle_chars**" (default: "3.5") - - Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_voltage**" (default: "0") - - Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true. - - * "**use_tool_communication**" (default: "false") - - On e-Series robots tool communication can be enabled with this argument - -### ur10_bringup.launch - -Standalone launchfile to startup a ur10 robot. This requires a robot reachable via a network connection. - -#### Arguments - * "**controller_config_file**" (default: "$(find ur_robot_driver)/config/ur10_controllers.yaml") - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_common.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (default: "$(find ur_description)/config/ur10_default.yaml") - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (default: "$(find ur_description)/launch/ur10_upload.launch") - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - -### ur_control.launch - -Robot bringup launchfile without the robot description. Include this, if you want to include robot control into a larger launchfile structure. - -#### Arguments - * "**controller_config_file**" (Required) - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - If set to true, will start the driver inside gdb - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (Required) - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Pass the same config file that is passed to the robot_description. - - * "**launch_prefix**" (Required) - - Please add description. See file "launch/ur_control.launch". - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**rtde_input_recipe_file**" (default: "$(find ur_robot_driver)/resources/rtde_input_recipe.txt") - - Recipe file used for the RTDE-inputs. Only change this if you know what you're doing. - - * "**rtde_output_recipe_file**" (default: "$(find ur_robot_driver)/resources/rtde_output_recipe.txt") - - Recipe file used for the RTDE-outputs. Only change this if you know what you're doing. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - - * "**tool_baud_rate**" (default: "115200") - - Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_device_name**" (default: "/tmp/ttyUR") - - Local device name used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_parity**" (default: "0") - - Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_rx_idle_chars**" (default: "1.5") - - Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_stop_bits**" (default: "1") - - Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_tcp_port**" (default: "54321") - - Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true. - - * "**tool_tx_idle_chars**" (default: "3.5") - - Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_voltage**" (default: "0") - - Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true. - - * "**urscript_file**" (default: "$(find ur_robot_driver)/resources/ros_control.urscript") - - Path to URScript that will be sent to the robot and that forms the main control program. - - * "**use_tool_communication**" (Required) - - On e-Series robots tool communication can be enabled with this argument - -### ur_common.launch - -Launchfile that starts a robot description with robot_state publisher and the driver for a given robot. It is recommended to use the individual launch files instead such as `ur10_bringup.launch`. Additionally, this launchfile can be used as a template to include this driver into a larger launch file structure. - -#### Arguments - * "**controller_config_file**" (Required) - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_control.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (Required) - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (Required) - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - - * "**tool_baud_rate**" (default: "115200") - - Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_device_name**" (default: "/tmp/ttyUR") - - Local device name used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_parity**" (default: "0") - - Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_rx_idle_chars**" (default: "1.5") - - Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_stop_bits**" (default: "1") - - Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_tcp_port**" (default: "54321") - - Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true. - - * "**tool_tx_idle_chars**" (default: "3.5") - - Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_voltage**" (default: "0") - - Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true. - - * "**use_tool_communication**" (Required) - - On e-Series robots tool communication can be enabled with this argument - -### ur5_bringup.launch - -Standalone launchfile to startup a ur5 robot. This requires a robot reachable via a network connection. - -#### Arguments - * "**controller_config_file**" (default: "$(find ur_robot_driver)/config/ur5_controllers.yaml") - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_common.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (default: "$(find ur_description)/config/ur5_default.yaml") - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (default: "$(find ur_description)/launch/ur5_upload.launch") - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - -### ur5e_bringup.launch - -Standalone launchfile to startup a ur5e robot. This requires a robot reachable via a network connection. - -#### Arguments - * "**controller_config_file**" (default: "$(find ur_robot_driver)/config/ur5e_controllers.yaml") - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_common.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (default: "$(find ur_e_description)/config/ur5e_default.yaml") - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (default: "$(find ur_e_description)/launch/ur5e_upload.launch") - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - - * "**tool_baud_rate**" (default: "115200") - - Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_device_name**" (default: "/tmp/ttyUR") - - Local device name used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_parity**" (default: "0") - - Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_rx_idle_chars**" (default: "1.5") - - Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_stop_bits**" (default: "1") - - Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_tcp_port**" (default: "54321") - - Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true. - - * "**tool_tx_idle_chars**" (default: "3.5") - - Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_voltage**" (default: "0") - - Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true. - - * "**use_tool_communication**" (default: "false") - - On e-Series robots tool communication can be enabled with this argument - -### ur3_bringup.launch - -Standalone launchfile to startup a ur5 robot. This requires a robot reachable via a network connection. - -#### Arguments - * "**controller_config_file**" (default: "$(find ur_robot_driver)/config/ur3_controllers.yaml") - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_common.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (default: "$(find ur_description)/config/ur3_default.yaml") - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (default: "$(find ur_description)/launch/ur3_upload.launch") - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - -### ur10e_bringup.launch - -Standalone launchfile to startup a ur10e robot. This requires a robot reachable via a network connection. - -#### Arguments - * "**controller_config_file**" (default: "$(find ur_robot_driver)/config/ur10e_controllers.yaml") - - Config file used for defining the ROS-Control controllers. - - * "**controllers**" (default: "joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller") - - Controllers that are activated by default. - - * "**debug**" (default: "false") - - Debug flag that will get passed on to ur_common.launch - - * "**headless_mode**" (default: "false") - - Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot. - - * "**kinematics_config**" (default: "$(find ur_e_description)/config/ur10e_default.yaml") - - Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. - - * "**limited**" (default: "false") - - Use the description in limited mode (Every axis rotates from -PI to PI) - - * "**reverse_port**" (default: "50001") - - Port that will be opened by the driver to allow direct communication between the driver and the robot controller. - - * "**robot_description_file**" (default: "$(find ur_e_description)/launch/ur10e_upload.launch") - - Robot description launch file. - - * "**robot_ip**" (Required) - - IP address by which the robot can be reached. - - * "**script_sender_port**" (default: "50002") - - The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately. - - * "**stopped_controllers**" (default: "pos_traj_controller") - - Controllers that are initally loaded, but not started. - - * "**tf_prefix**" (default: "") - - tf_prefix used for the robot. - - * "**tool_baud_rate**" (default: "115200") - - Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_device_name**" (default: "/tmp/ttyUR") - - Local device name used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_parity**" (default: "0") - - Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_rx_idle_chars**" (default: "1.5") - - Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_stop_bits**" (default: "1") - - Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_tcp_port**" (default: "54321") - - Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true. - - * "**tool_tx_idle_chars**" (default: "3.5") - - Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true. - - * "**tool_voltage**" (default: "0") - - Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true. - - * "**use_tool_communication**" (default: "false") - - On e-Series robots tool communication can be enabled with this argument - -## Nodes -### ur_robot_driver_node - -This is the actual driver node containing the ROS-Control stack. Interfaces documented here refer to the robot's hardware interface. Controller-specific API elements might be present for the individual controllers outside of this package. - -#### Advertised Services - * "**dashboard/add_to_log**" (ur_dashboard_msgs/AddToLog) - - Service to add a message to the robot's log - - * "**dashboard/brake_release**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to release the brakes. If the robot is currently powered off, it will get powered on on the fly. - - * "**dashboard/clear_operational_mode**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - If this service is called the operational mode can again be changed from PolyScope, and the user password is enabled. - - * "**dashboard/close_popup**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Close a (non-safety) popup on the teach pendant. - - * "**dashboard/close_safety_popup**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Close a safety popup on the teach pendant. - - * "**dashboard/connect**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to reconnect to the dashboard server - - * "**dashboard/get_loaded_program**" (ur_dashboard_msgs/GetLoadedProgram) - - Load a robot installation from a file - - * "**dashboard/get_robot_mode**" (ur_dashboard_msgs/GetRobotMode) - - Service to query the current robot mode - - * "**dashboard/get_safety_mode**" (ur_dashboard_msgs/GetSafetyMode) - - Service to query the current safety mode - - * "**dashboard/load_installation**" (ur_dashboard_msgs/Load) - - Load a robot installation from a file - - * "**dashboard/load_program**" (ur_dashboard_msgs/Load) - - Load a robot program from a file - - * "**dashboard/pause**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Pause a running program. - - * "**dashboard/play**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Start execution of a previously loaded program - - * "**dashboard/popup**" (ur_dashboard_msgs/Popup) - - Service to show a popup on the UR Teach pendant. - - * "**dashboard/power_off**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Power off the robot motors - - * "**dashboard/power_on**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Power on the robot motors. To fully start the robot, call 'brake_release' afterwards. - - * "**dashboard/program_running**" (ur_dashboard_msgs/IsProgramRunning) - - Query whether there is currently a program running - - * "**dashboard/program_saved**" (ur_dashboard_msgs/IsProgramSaved) - - Query whether the current program is saved - - * "**dashboard/program_state**" (ur_dashboard_msgs/GetProgramState) - - Service to query the current program state - - * "**dashboard/quit**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Disconnect from the dashboard service. - - * "**dashboard/raw_request**" (ur_dashboard_msgs/RawRequest) - - General purpose service to send arbitrary messages to the dashboard server - - * "**dashboard/restart_safety**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Used when robot gets a safety fault or violation to restart the safety. After safety has been rebooted the robot will be in Power Off. NOTE: You should always ensure it is okay to restart the system. It is highly recommended to check the error log before using this command (either via PolyScope or e.g. ssh connection). - - * "**dashboard/shutdown**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Shutdown the robot controller - - * "**dashboard/stop**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Stop program execution on the robot - - * "**dashboard/unlock_protective_stop**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Dismiss a protective stop to continue robot movements. NOTE: It is the responsibility of the user to ensure the cause of the protective stop is resolved before calling this service. - - * "**hand_back_control**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Calling this service will make the "External Control" program node on the UR-Program return. - - * "**resend_robot_program**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - When in headless mode, this sends the URScript program to the robot for execution. Use this after the program has been interrupted, e.g. by a protective- or EM-stop. - - * "**set_io**" (ur_msgs/SetIO) - - Service to set any of the robot's IOs - - * "**set_speed_slider**" (ur_msgs/SetSpeedSliderFraction) - - Set the speed slider fraction used by the robot's execution. Values should be between 0 and 1. Only set this smaller than 1 if you are using the scaled controllers (as by default) or you know what you're doing. Using this with other controllers might lead to unexpected behaviors. - - * "**zero_ftsensor**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Calling this service will zero the robot's ftsensor. Note: On e-Series robots this will only work when the robot is in remote-control mode. - -#### Parameters - * "**dashboard/receive_timeout**" (Required) - - Timeout after which a call to the dashboard server will be considered failure if no answer has been received. - - * "**hardware_interface/joints**" (Required) - - Names of the joints. Usually, this is given in the controller config file. - - * "**headless_mode**" (Required) - - Start robot in headless mode. This does not require the 'External Control' URCap to be running on the robot, but this will send the URScript to the robot directly. On e-Series robots this requires the robot to run in 'remote-control' mode. - - * "**input_recipe_file**" (Required) - - Path to the file containing the recipe used for requesting RTDE inputs. - - * "**kinematics/hash**" (Required) - - Hash of the calibration reported by the robot. This is used for validating the robot description is using the correct calibration. If the robot's calibration doesn't match this hash, an error will be printed. You can use the robot as usual, however Cartesian poses of the endeffector might be inaccurate. See the "ur_calibration" package on help how to generate your own hash matching your actual robot. - - * "**non_blocking_read**" (default: "false") - - Enables non_blocking_read mode. Should only be used with combined_robot_hw. Disables error generated when read returns without any data, sets the read timeout to zero, and synchronises read/write operations. Enabling this when not used with combined_robot_hw can suppress important errors and affect real-time performance. - - * "**output_recipe_file**" (Required) - - Path to the file containing the recipe used for requesting RTDE outputs. - - * "**reverse_port**" (Required) - - Port that will be opened to communicate between the driver and the robot controller. - - * "**robot_ip**" (Required) - - The robot's IP address. - - * "**script_file**" (Required) - - Path to the urscript code that will be sent to the robot. - - * "**script_sender_port**" (Required) - - The driver will offer an interface to receive the program's URScript on this port. - - * "**tf_prefix**" (default: "") - - Please add description. See hardware_interface.cpp line number: 74 - - - - robot_hw_nh.param("tf_prefix", tf_prefix_, ""); - - * "**tool_baud_rate**" (Required) - - Baud rate used for tool communication. Will be set as soon as the UR-Program on the robot is started. See UR documentation for valid baud rates. Note: This parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE. Then, this parameter is required. - - * "**tool_parity**" (Required) - - Parity used for tool communication. Will be set as soon as the UR-Program on the robot is started. Can be 0 (None), 1 (odd) and 2 (even). Note: This parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE. Then, this parameter is required. - - * "**tool_rx_idle_chars**" (Required) - - Number of idle chars for the RX unit used for tool communication. Will be set as soon as the UR-Program on the robot is started. Valid values: min=1.0, max=40.0 Note: This parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE. Then, this parameter is required. - - * "**tool_stop_bits**" (Required) - - Number of stop bits used for tool communication. Will be set as soon as the UR-Program on the robot is started. Can be 1 or 2. Note: This parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE. Then, this parameter is required. - - * "**tool_tx_idle_chars**" (Required) - - Number of idle chars for the TX unit used for tool communication. Will be set as soon as the UR-Program on the robot is started. Valid values: min=0.0, max=40.0 Note: This parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE. Then, this parameter is required. - - * "**tool_voltage**" (Required) - - Tool voltage that will be set as soon as the UR-Program on the robot is started. Note: This parameter is only evaluated, when the parameter "use_tool_communication" is set to TRUE. Then, this parameter is required. - - * "**use_tool_communication**" (Required) - - Should the tool's RS485 interface be forwarded to the ROS machine? This is only available on e-Series models. Setting this parameter to TRUE requires multiple other parameters to be set,as well. - - * "**servoj_gain**" (default: "2000") - - Specify gain for servoing to position in joint space. A higher gain can sharpen the trajectory. - - * "**servoj_gain**" (default: "0.03") - - Specify lookahead time for servoing to position in joint space. A longer lookahead time can smooth the trajectory. - -#### Published topics - * "**robot_program_running**" ([std_msgs/Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html)) - - Whenever the runtime state of the "External Control" program node in the UR-program changes, a message gets published here. So this is equivalent to the information whether the robot accepts commands from ROS side. - -#### Subscribed topics - * "**script_command**" ([std_msgs/String](http://docs.ros.org/api/std_msgs/html/msg/String.html)) - - Send arbitrary script commands to this topic. Note: On e-Series the robot has to be in remote-control mode. Sending scripts to this will stop program execution unless wrapped in a secondary program: sec myProgram(): set_digital_out(0, True) end - -### dashboard_client - - - -#### Advertised Services - * "**add_to_log**" (ur_dashboard_msgs/AddToLog) - - Service to add a message to the robot's log - - * "**brake_release**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to release the brakes. If the robot is currently powered off, it will get powered on on the fly. - - * "**clear_operational_mode**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - If this service is called the operational mode can again be changed from PolyScope, and the user password is enabled. - - * "**close_popup**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Close a (non-safety) popup on the teach pendant. - - * "**close_safety_popup**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Close a safety popup on the teach pendant. - - * "**connect**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to reconnect to the dashboard server - - * "**get_loaded_program**" (ur_dashboard_msgs/GetLoadedProgram) - - Load a robot installation from a file - - * "**get_robot_mode**" (ur_dashboard_msgs/GetRobotMode) - - Service to query the current robot mode - - * "**get_safety_mode**" (ur_dashboard_msgs/GetSafetyMode) - - Service to query the current safety mode - - * "**load_installation**" (ur_dashboard_msgs/Load) - - Load a robot installation from a file - - * "**load_program**" (ur_dashboard_msgs/Load) - - Load a robot program from a file - - * "**pause**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Pause a running program. - - * "**play**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Start execution of a previously loaded program - - * "**popup**" (ur_dashboard_msgs/Popup) - - Service to show a popup on the UR Teach pendant. - - * "**power_off**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Power off the robot motors - - * "**power_on**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Power on the robot motors. To fully start the robot, call 'brake_release' afterwards. - - * "**program_running**" (ur_dashboard_msgs/IsProgramRunning) - - Query whether there is currently a program running - - * "**program_saved**" (ur_dashboard_msgs/IsProgramSaved) - - Query whether the current program is saved - - * "**program_state**" (ur_dashboard_msgs/GetProgramState) - - Service to query the current program state - - * "**quit**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Disconnect from the dashboard service. - - * "**raw_request**" (ur_dashboard_msgs/RawRequest) - - General purpose service to send arbitrary messages to the dashboard server - - * "**restart_safety**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Used when robot gets a safety fault or violation to restart the safety. After safety has been rebooted the robot will be in Power Off. NOTE: You should always ensure it is okay to restart the system. It is highly recommended to check the error log before using this command (either via PolyScope or e.g. ssh connection). - - * "**shutdown**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Shutdown the robot controller - - * "**stop**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Stop program execution on the robot - - * "**unlock_protective_stop**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Dismiss a protective stop to continue robot movements. NOTE: It is the responsibility of the user to ensure the cause of the protective stop is resolved before calling this service. - -#### Parameters - * "**receive_timeout**" (Required) - - Timeout after which a call to the dashboard server will be considered failure if no answer has been received. - - * "**robot_ip**" (Required) - - The IP address under which the robot is reachable. - -### robot_state_helper - -This node prints the robot- and safety mode to ROS logging and offers an action to set the robot to a specific mode (e.g. for initial startup or recovery after a protective stop or EM-Stop). It should best be started inside the hardware interface's namespace - -#### Service Clients - * "**dashboard/brake_release**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to release the robot's brakes - - * "**dashboard/play**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to start UR program execution on the robot - - * "**dashboard/power_off**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to power off the robot - - * "**dashboard/power_on**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to power on the robot - - * "**dashboard/restart_safety**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to restart safety - - * "**dashboard/stop**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to stop UR program execution on the robot - - * "**dashboard/unlock_protective_stop**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html)) - - Service to unlock protective stop - -#### Subscribed topics - * "**robot_mode**" (ur_dashboard_msgs/RobotMode) - - Topic on which the robot_mode is published by the driver - - * "**safety_mode**" (ur_dashboard_msgs/SafetyMode) - - Topic on which the safety is published by the driver - -#### Actions - * "**set_mode**" (ur_dashboard_msgs/SetMode) - - Action server to set the robot into a specific mode (e.g. RUNNING). If desired, program - execution can be stopped before switching modes and/or (re-)started after the robot reached - state RUNNING. - - **Note**: If you use this feature make sure that it is safe to continue program execution. The - robot might start moving again, immediately after this action finishes. - - The 'play' field is only evaluated, when the target mode is RUNNING. - -### tool_communication - -This node is used to start the RS485 tunneling interface on the ROS machine. This requires that the RS485 daemon is running on the robot controller and tool communication is enabled on the robot. - -#### Parameters - * "**~device_name**" (Required) - - By default, socat will create a pty in /dev/pts/N with n being an increasing number. Additionally, a symlink at the given location will be created. Use an absolute path here. - - * "**~robot_ip**" (Required) - - IP address of the robot - diff --git a/ur_robot_driver/doc/architecture_coarse.svg b/ur_robot_driver/doc/architecture_coarse.svg index 8e85f27..f6a2514 100644 --- a/ur_robot_driver/doc/architecture_coarse.svg +++ b/ur_robot_driver/doc/architecture_coarse.svg @@ -205,7 +205,7 @@ - ROS-Driver + Isaac-Driver @@ -229,7 +229,7 @@ - Controllers + URController - speed_scaling - tcp_force - joint_states diff --git a/ur_robot_driver/doc/component_api.md b/ur_robot_driver/doc/component_api.md new file mode 100644 index 0000000..b05c4b8 --- /dev/null +++ b/ur_robot_driver/doc/component_api.md @@ -0,0 +1,203 @@ +# Component api + +This section describes all the codelets part of this driver. + +For each component, the incoming and outgoing message channels and the corresponding +message types are listed. Additionally, all parameters with their names and types +and corresponding default values are explained. + +## UniversalRobots + +The `UniversalRobots` codelet handles the interface between an Isaac application +and the main driver. It is publishing actual robot and IO state and receiving IO +and arm commands. + +### Incoming messages + +- **arm_command** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Receives command for arm, parsed based on control mode. + +- **io_command** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Receives IO command, to set any of the robot's IOs. + +- **stop_control** [[BooleanProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#booleanproto)]: +Stop control of the robot through Isaac. The boolean flag needs to be true, to stop +control of the robot through Isaac. This will make the "External Control" program +node on the UR-Program return. + +- **resend_control_script** [[BooleanProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#booleanproto)]: +Receives a signal to send the URScript program to the robot for execution, when +the robot is in headless mode. The boolean flag needs to be true, to send the script. +Use this after the program has been interrupted, e.g. by a protective- or EM-stop. + +- **set_speed_slider** [[SpeedSliderProto](../../ur_msg/README.md#SpeedSliderProto)]: +Set the speed slider fraction used by the robot's execution. Values should be between +0 and 1. Only set this smaller than 1 if you are using the ur_controller or you +know what you're doing. Using this with other controllers might lead to unexpected +behaviors. + +### Outgoing messages + +- **arm_state** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Current state of the arm, includes joint angles, joint speeds and current speed fraction. + +- **io_state** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Current IO, includes digital inputs and outputs. + +- **robot_program_running** [[BooleanProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#booleanproto)]: +Whenever the runtime state of the "External Control" program node in the UR-program +changes a message gets published. So this is equivalent to the information whether +the robot accepts commands from Isaac side. + +- **trajectory** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Publish a trajectory to the controller to make sure the robots stays in the same +position. The trajectory is published everytime "External Control" program node +starts running. This is used to make sure that the newest trajectory, is based upon +the robots current position when Isaac starts controlling the robot. + +### Parameters + +- **kinematic_tree** [std::string] [default=]: Name of the node containing the map:KinematicTree +component. This is used to obtain the names of the joints for parsing/creating +composite message. + +- **controller** [std::string] [default=]: Name of the node containing the controller +component. This node is started and stopped based upon the drivers control status +of the robot. + +- **dashboard_client** [std::string] [default=]: Name of the node containing the +DashboardClientIsaac component This is used to start the node and set the ip address. +Nothing will happen if this parameter is kept empty. + +- **control_mode** [ArmControlMode] [default = kJointPosition]: Set control mode +for arm. Use "joint position" or "joint speed" to specify wheter the control mode +should be joint positions or joint speeds. + +- **misc_names** [std::vector\] [default = std::vector\({ +"timestamp", "speed_fraction" })]: Name of speed_fraction and timestamp used for +creating composite message. + +- **tool_digital_out_names** [std::vector\] [default = std::vector\({ +"tool_digital_out_0", "tool_digital_out_1" })]: Entity name for digital tool output. + +- **tool_digital_in_names** [std::vector\] [default = std::vector\({ +"tool_digital_in_0", "tool_digital_in_1" })]: Entity name for digital tool input. + +#### Driver settings + +These are parameters parsed forward to the UrDriver object, which is created, during +startup of this codelet. + +- **robot_ip** [std::string] [default=]: Ip address of the robot. + +- **control_script_program** [std::string] [default = "packages/universal_robots/ur_robot_driver/resources/ros_control.urscript"]: +URScript file that is sent to the robot. + +- **rtde_input_recipe** [std::string] [default = "packages/universal_robots/ur_robot_driver/resources/rtde_input_recipe.txt"]: +Filename where the input recipe is stored in. + +- **rtde_output_recipe** [std::string] [default = ""packages/universal_robots/ur_robot_driver/resources/rtde_output_recipe.txt"]: +Filename where the output recipe is stored in. + +- **headless_mode** [bool] [default = false]: Parameter to control if the driver +should be started in headless mode. + +- **servoj_gain** [double] [default = 2000]: Specify gain for servoing to position +in joint space. A higher gain can sharpen the trajectory. + +- **servoj_lookahead_time** [double] [default = 0.03]: Specify lookahead time for +servoing to position in joint space. A longer lookahead time can smooth the trajectory. + +## DashboardClientIsaac + +The `dashboardClientIsaac` class is the interface between the dashboardserver and +an Isaac application. Almost all the dashboard commands can be sent through this +codelet to the dashboardserver and this codelet, will return the anwser to the application. + +If you use this codelet together with the UniversalRobots codelet, the node containing +this codelet can be started through the UniversalRobots codelet, this is done so +you only have to set the robots ip once. See this [subgraph](../apps/ur_eseries_robot.subgraph.json) +for inspiration. + +### Incoming messages + +- **dashboard_command** [[DashboardCommandProto](../../ur_msg/README.md#DashboardCommandProto)]: +Receiving the dashboard command, which is forwarded to the dashboard server. + +### Outgoing messages + +- **anwser** [[DashboardCommandStatusProto](../../ur_msg/README.md#DashboardCommandStatusProto)]: +Channel to publish the anwser from the dashbordserver and whether the command was +a succes. + +### Parameters + +- **robot_ip** [std::string] [default=]: The ip address of the robot. + +## ScaledMultiJointController + +The ScaledMultiJointController class receives a trajectory and calculates the actual +joint command to publish each iteration. It slows down trajectory execution according +to the actual speedscaling of the robot. + +### Incoming messages +- **current_arm_state** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Receives current state of the robot arm, this also includes the actual speedscaling. + +- **plan** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Receives a plan that contains a trajectory for each joint. If linear interpolation +is configured the trajectory must contain joint position. If cubic interpolation +is configured the trajectory must contain joint position and joint speeds. If quintic +interpolation is configured the trajectory must contain joint positions, joint speeds +and joint accelerations. + +### Outgoing messages + +- **joint_command** [[CompositeProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#compositeproto)]: +Publishes the actual joint command as joint position or joint speeds based upon control_mode. + +- **trajectory_executed_succesfully** [[BooleanProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#booleanproto)]: +Publishes the status after a trajectory has been executed. The flag will be true +if the joints are within the tolerance after trajectory execution and false otherwise. + +### Parameters + +- **kinematic_tree** [std::string] [default=]: Name of the node containing the map:KinematicTree +component. This is used to obtain the names of the joints for parsing/creating +composite message. + +- **interpolation_scheme** [InterpolationScheme] [default=quintic_interpolation]: +Set the interpolation scheme used to calculate joint commands and parse joint trajectory. + +- **control_mode** [ArmControlMode] [default=kJointPosition]: Set the control mode. +Use "joint position" or "joint speed" to specify wheter the control mode should be +joint positions or joint speeds. + +- **goal_time** [double] [default = 0.0]: Time after the last waypoint in the trajectory +is published and until the joints should be within the tolerance. + +- **tolerance** [double] [default = 0.0]: Tolerance for arrival. The trajectory +is completed when the error for all joints are below this tolerance after the last +waypoint in the trajectory is published. If the tolerance is 0.0, no check will +be made. + +- **gains** [nlohmann::json] [default=(nlohmann::json{{"gains", {}}})]: PID gains +for each joint, when control mode is kJointSpeed. + +## ControllerStopper + +ControllerStopper class is a small helper component that stops and restarts the +controller based on a boolean message. When the message goes to false, the controller +is stopped. If message returns to true the stopped controller is restarted. This +component is automatically started inside the driver. + +### Incoming messages + +- **robot_program_running** [[BooleanProto](https://docs.nvidia.com/isaac/isaac/doc/doc/message_api.html#booleanproto)]: +Receives the robots running state. + +### Parameters + +- **controller** [std::string] [default=]: Name of the node containing the controller +node that is sending targets to the driver. This node is started and stopped based +upon the drivers control status of the robot. diff --git a/ur_robot_driver/doc/features.md b/ur_robot_driver/doc/features.md deleted file mode 100644 index 62628e5..0000000 --- a/ur_robot_driver/doc/features.md +++ /dev/null @@ -1,34 +0,0 @@ -# Feature comparison and roadmap - -| Feature | ur_modern_driver | this_driver | -| --- | --- | --- | -| position-based control | yes | yes | -| scaled position-based control | - | yes | -| velocity-based control | yes | planned | -| reporting of tcp wrench | yes | yes | -| reporting of tcp wrench in tcp link | - | yes | -| pausing of programs | - | yes | -| continue trajectories after EM-Stop resume | - | yes | -| continue trajectories after protective stop | - | yes | -| panel interaction in between possible | no1 | yes | -| get and set IO states | yes | yes | -| use tool communication on e-series | - | yes | -| use the driver without a teach pendant necessary | - | yes | -| support of CB2 robots | yes | - | -| trajectory extrapolation on robot on missing packages | no2 | yes | -| use ROS as drop-in for TP-programs | - | yes | -| extract calibration from robot | - | yes | -| send custom script commands to robot | yes | yes | -| ROS 2 support | ? | (planned)3 | -| Reconnect on a disconnected robot | yes | yes | - -1 Depending on the mode the driver is running the panel won't react or using the panel -will stop the program without notifying the ROS user. - -2 In velocity mode this is implicitly given. - -3 There is no specific plan to do this inside of the first driver development. However, -it is structured in a way so that a ROS2 driver should be developed as easy as possible by keeping -as much as possible in a ros-independent library. - - diff --git a/ur_robot_driver/doc/initial_setup_images/e-Series.jpg b/ur_robot_driver/doc/initial_setup_images/e-Series.jpg new file mode 100644 index 0000000000000000000000000000000000000000..5770be6cf30be47cd781695c78117b29d112c5f6 GIT binary patch literal 42289 zcmeFZ2T)r}wk|B^48}Iu2AhmQ$R-B^=U@XSNhTXauni(hBIj@%G1(wMCYvZS27yGD z0h5zKWC1ckWRY`x@|l_Y=AZj+{WW#(yZ5iZrmLjg-FxlT+TU8;{jKi3bux4^0YE5w z+FAhsT3Uen007`3;QT2%z-e0U6zu~z#RfR{*Sx_g_J7Npoe}_?`LmuTdHUvG^Rz48 zeE#3p{<@x)p3*+Qbp3fep#qei*&tn!E;dNVyJ8{_0MbfoT4&Gx5(MzxK4lCz!_KRE zngp&90wG*PURokw!9*;OaFFLqN6iaUnCr{Co^S_*i>#+S|DVcbY58B(ApX05in!X#^Q*yMTEk>ze?g~* zL^|Ak_)tXb0Y6QNv!#`+&J&fts-TtR`TzP`Jv=-_Jj6th&eouZGBPrt2cjTRQ6NnM z=;DQNed!5AxNy@nT)z9Kjwdh|3ujwLS6d|F?k}A$Um@LG<@xz9-~FppaWpF-fD68@KW{R^&t3W0x0_+Q@jFS!0G1pX=E{~qu9-$WRO zps`;M8qGZ+0UiS`oEh+9x2|2ia^))Pjhpnh?yzxk++n+Y`!0_N z|6ML&?%THoqy&W@JQNof=j4}>mlk~_A|@{SOUbEAmo8nsa+T%UH5So(x9^Gm)9K_J zfZ^ilgtK4IoZzSpTBti)H%SZ)3mb;=WpD5_`CMYn_Ny8Zi(u=j!Z4?VdPeN~Ag{-ue&ip@GqbWRl<{a%5FT*KXW53eB3DDYN zxcBhv4bk6kD&6AJ)_Hj{0=RmHCdP1v0iXz2`T5sh{IA2m5cvNQ0xT7An=e&&64z1C zY^6uN0WUrdi)B6IW?oBT@X>x9BQ-f4t#b$gg-)4jb%SeLcS7$+jcYV#;6S@Y1@qnO zMDG!ui{?kKbSKgl6i)!%Cjcka^&s;PK`AEy#(;xhS-vmtP5=X3t3R-WsiLh%glN@? zFEat-gZrxlpEcrY6dc7K% z8zsgR6x=#-og& z4n+hTTH=eiKx{}XY8*s8dU|#a!&M8-DQwvTUp9{`sN#5jsr`JbF5`Hd)cur$BK%N~ zO&NcAFBaOYi$`clRQh~zNxnQKKtkOS<1?w+4CMumAseixE|7Y5mR(=P7UdT~eSQPn z|N8$0C$e!#%>Q1wta_=eV{)9zZc<&jc9ewlfR#K8HT17lJZsmVB2yQgF|huwrhj5| z9M5m{39Zjn}CdQfwh|`^T#w zchK-9X+P$jQ(a|wqTo=y$B<2YqfwBxV18d)wpm06;NIQ;am${<^t&xMrV8i_bai#^ zs&4temr&0vv>kq4J`yve@9=Z|;r1-K+3JuPGaiw+#cKcPQXYiE!*}X(t9&M_qP4Rr zdA-x~1mJq%Mg0IQ?)$D=7XsWa39mh3B{U=Q1q{y*;@olMw{}|ao!dU|cR%DO3-y%T zv)byu|IlX#x{UL$0XMK=41lrFl5LJ2Rg4>U?ZBuv+=JR$YA2G;H?k7VFX4bMkvll@ zA()?j^1}A3PNfT}I^j?&@9Ef`2N2P|;Y}?01OR6NvQ~&`H%C_^%G#Gq8Q#oTbjwvC zF81HD4$^ojxMX4UvT@kiAfu;q*O_8|y&rhs18GJ1hM2q*^y2GsNvn`o)ABSF4Co#| zn`hQf;k{}{8E78->EP&=Jz+5z5~$JI=D!d;mT_3=hU~d+YCy`&Zi@Ht(6A|jNO~wn zQJJqmdi8%4ighHqCsEzZBG=7RKC*=>+?u)r7o4#wkc|t-b9V9xcp`hWG<*W+*Nm3I z6phc$vZd_AP9KRtCAUOP($Y&a(hd`b=zxWe$u$}J{6V?RqGiXq(*q{}pMdxWwd!TV z^8tdpLwgeKY+n7{Oe2&@a?SbbL2>s3a6yrUkEWM69_k^(mlHbQjk!c>YdGkFC~ zm(6ybiIo8jDi<8JRM;KTITE;oos@B^q6jHhcQnWfsAOl;b-g)&At}N!QFYeze?xm9(n^ z8%*D?5{)cTSLl-GR|x6x#9p)a&^9Clv7P`PlaSTlS_eQSIchJTN29Bc6a16pKwpV6 zi&-{xwlUSCDfa&TD@#8s?k%8$LT5o-155@vxeMCgh~i$BWRSEv!<&uhlqWUdxGdkq z)=5k*WpE>KT>6u5fM(>M`e!q9aq= z04l5EZh+E_$@s#}c`pNazdo=Q=s*w!Hpp7e`YVUa-!qOFA@6ajQhYzp?L{95iHcT8 zX=O|eBEM#Fwz>ztH%ZlxGus%$3v3+%_PRPH_3h&fj5u<#n}6;nLEe^C`*EvBubWT? zV;K!9FqYM~4C7`ac6AE)jT)aPt`~7-w$0)WTbBl>EnmHuvSCAZ1Jw;xI2Qdm=|8d> zRes1xs8vaiFAY^Cv2$pQNE~i^?Q`Fx*Xg}y_q?CvZ~~z6P$Z8BY@FAy&KQ;STnj5w z7`*u1{ig8c%Mh3#a?@gQG;v~nS6aW(V#?4Qe1HViY@Lz2Y0whN%!>;3&!6f!n&Bu; zvo$`_+3r)lB8Bwe`$%Ov0VHz>^}C6}lHht>`WvH@gnF|LbXLbVqJ&}YOJa;L`&ZL~ z#vZ$oXSM|TYuig_^QMnU=?&V%b=+Q8ie)hcOZMCeF$)L!eb4^G#%|6@Qz%#cK}+6< z8XnhG0X&w=xw-m3+Wqi;TT^{YIJ<{tpmhl^DF`2M8fl>TUhaT+T*N!Svvc!PXT)Mad4hs^R-*lo0J;C{Oi8vz&qoT=XA9 zb|cHA?3O^QSyH4V3h7+3J?su2%&F`xclKzNd2(@#O+^JBB!Elc+h@K|U&cz}sLe>w z`eD};j1UTVU6#1m9QbA^Da>s|`3ghRLv?La*4AU~O=;3adskI77ly3_x57KZq|M)z zfq8IJ8{Id-CRmj2 zKMWpL21c3v_R>~Xfhpuev187&Krgi#iqtIs81~VhR^+O7%F6G!t(j~}iSQoVQ_-;A zU3y%m2}7gbKZ)J)(VMC6)uQg+(G_Ep`RqQ`UKVK|!2i=_Dbb4<*>34xlH>N90bHO- zz9Rl3N?WDUXjo@p;yq9ld0GEJId-PP1hp^c0cm!gDaMQ?JbrG3)8(I#I2xQg&xF9R z*zGG^SHPtSeH%K?hv`ncm@oA+o^U?F&fpZ>Cx8WLN&CSUx18|<&xe^=u zQa=gX@^Dc*!=XKD)W*75kgLk~|1l3f^Ysifzo>YtzKJQmtg=9%y_0a(2rp^4a@$B? zpi+GsuhA>ixWBy{U!Az%xEO8cXKnO)AD&kJhYNplUoLI*qC@rAhb z&J{O_%EF4;1yQaFR`=xB zB+fvEP|S^&VebvZnU#N3r<*;JgmOa@a+*qe{eEk0>wJIRPn)f~pVz`xJ~AvJnNp1r z`9M^iki(8TyFG8q_g`!J>%6uyi+>@(hCn5KXO;*%sJ7h3@@cr%a1nxzFV3-n1K*}= zFRj^`tjv={un8N;W9=k;{T@BLT!#0KP?d+Yz859`$KOmLu^$_$l75G>Y#iIxat!Gh z0^Gx|Zu{Nv{S;Qb@s5BMF5rKLM8=c0Gxt${oP}_HSf|>K3Fvc1h#ge1AKn46L$vyt zmh5efL`nkEHpPDXo8JHS<5h>yGQAl6Mv@COn}65~|MQP3x2>sxC7k+0^N@8jhe1oI z&{QX?M$c21P@}l8xp~m;F?Q9<$9~CR8s2jPxGK*@AUHqFUCeQTD|~S%16oNmHUU)x z9imq687G$sv8$_`cgM)h^um{o8td`*8!P>OD~YLa_l&y3|65FnPPA5GL<7mWO`Es$ zRezXStH>X(UfAke{4T{bD(uWyHgj@R znEDJD@eN>6qQP`!8LNxL zHg|jfgPX%MQ~cA^;N$59?Q+=Lo7-6_$75k906)&YBI+ah?NQ{x&~XND^i}hb=Ze(w z6TnXKk@|5@{RzOK`22SAcAKApY3b$BbJA5$2?3#BYI@Ar{q?Z_5)OP18i?@3^I6Z^-*E=8AX1Cu?_#4T0Si38HO%L34=R=@$ESK!*@S>XW?0t|Kh6m*pjhA zmc5_Yfrh4Ir5VaaZCJie6w;-`0->KQ9BC_iHQ&kkBO6st70YE?j<1mJEtS?~6jaSg zd7GslVmt=yNGN%!=MFu!;=MLeGVEaQymbw)Z6#vhnl++X7mVlH?NN5d&AY$zttPFS zebMFS_oK)-ge9XJ+-J(k*-iQuJ7IS+6&Kdck`6lyBOCf(s>{e|nMPM)4u6sFjjfec zsXx35%XLlc3mM*V;X+^G)Hwe5dqn<|`BSPqRi(9e^_Zq2HFqdDdTZ>6M*6zE&r?6o zqo3XvQf%o9IICTn7eUqZzhT6E2gha5@ux9CB+~$}Q^c11$MKw|TSOFs2_52|8KXIVL#N^*P-=P#Bxr-uQfI z)hWqQ+m9HbVqfC)&{-4_wy7^u5ZUOz%( z0{)bgNKy2+m|f|(7;t;yrFP-tsNjL!wWtvxjFJDl<0LU~l0^4R-->|pN=vnNyTUWE z6lyTX3E;5kIOpb){O{FQtqI;QPXIBe%EQsGnX7FILA`>k&kDLm%GT^$&}m$>Qub2fEcvU%~kczTs>8P+vxt*b6u1oS$X~W zfsZkXKnyHv?RFabAA-{>^Ru<`I*Dg-hGCp_yxRoj)>a3GYtfi3z=7hsbA5yZWY)cOwdAj*o%lw*4thC(fbEhs(vD6E} zSPG(4zx)k_|C%G$$he!AQ3SnzjGK>qWjrBaYGpv~5Gr0I>TWMH;NpSPSQ~2D>pL!< z(~18`>@M386K(6*Hj*;Bl7^8s$PZ0%uM#^mG;#DaS-2J=8%yqe_w%@)u+2>_<*RgI zJq%uWW&Fqo!FR*lB5;dKcj)EO(@4UI*al~*^;RhLDnc@bv0W>T;4v}`+=D{5Xwy-} z)C304HNW6o2F+Cd*kiMWpBdAuO9wgtY}byf$((g(I3`|W9|J8E!)i3fgs?^X^o@H z&26;sS%(~aY%Vb|#yYrI>8|Vcm{)0bq$+I@b-;_8X8*|7AGM*J-rGR9HYAaRwIcd6 zkn5IC0B4e5PO+KkYbfHDnv_Y&-3;QGThxft2ISZ~J!{R++4Y4W0#(_~G4DVq9;9z= zmuk#SJ)TiK)3~xzPFteSCsf4fJL#)pUfb<9lcr7p!inUeFw%=&IroJF$^Dg$M~L>Q zodk5k=z8y?<{bKKC5at*z&7aJyCz=1En~%FspBlowe@s^xNwR{@JHkc;PSoOND;U} zk!HY=W_Q0B%q)UMnOfuc;RNu4{pbvzaUsU)F-?lz=0=ETggWtv)8N6CdpAyDM!No0l-(?o2uK@#i-WyOq1AFCnmZe+obSxV-2?so!Ic0BNGr z==Q$jn|J6D+?g<^t5P^K&6O0s+vF{Hs!I*IbLRx`y*p{E2E?yag2;1dC8BoH6|k9J zMdE%J)^(k$rb(*9E3KCr0^UuZ?f9DwPd5(VMs4e>j+hMgK+?95b*G$3shTqRvF#-r z$X2hBaf!lvkSmVYzEMH?K(h(>?im?vSjGU)YgDB@9Y_GJRh!L14EjPEZ z$TDi^3X3uPd0AnI^VXhrp&XwD%vvA|C1GGHmpOOtFtpW(4<&49iXUUMeOFLvnnsYC zuF(ur1QWEA`wn9GOADjs{v2=+bSV)S;?i88;eamMNNo>yo(}zGFi?Q}sef1qOByTM zH%uuCcwPRt`~NRGo>Jo%5Krzb2>$Ff60VS9SXyiArRpdnk`Mu7nl_Zok9LT1Cc*a; z?xgewsYFX?&J|t3>?Nn-ddC88$_vcTXgU{Lod9H;=I~$$VLj5?Y{gkWMtbnlFmW`O z<}xaKu_V^&par&So8{-rIB2x7XksJ+E^cM3m)6cuYImGDjxZ7smpwI+#axBRdDS77ciol0Fr{H#EJ;bdx^k?ON?+Lh5#$HvJ60 z?Vr9p{A`XeG^;bvmG>pOwtM|E?(U{BR749X~>4H zNiVja^f@o^;4Ac4RCe#;o=~qrSlxP~&P-r8D4KUGjj~Lr;6nU^IWscS@YZn<>vqO! z0x0NhQg+Yl3vzs!R%Az3sj?&iEKo~qrGO6BNauDO!nrD-jPL~{$>@3-}ZczG~C zW-G&Ute%jo$A8*L$3XMc!G6wbncXIb`z!dmWBQ`FVTl3**+P*>OEc=gQq(%xB6ebu zOahaUONW#!73grbwy>f3k%!yj# zM_MN9)~pW>e(-*U#|tYWs@voS)~d8XsYf^jS) z0%B&QCg^($9FyxCJiEX;K1P}1ZD(1UK2&I64=HEoe?oLx&rfmzZ(aLB^3y#6jQPg& z<$jOWQ4?wPlX&(OpIxS`^7%y_Qy^;>u$|YBCS(02QPv<78c);g<-Fpw5YYDGTcnjlL>fK z$2UmBj@O*uAk`DZ!XVc&R!$>$w z+qX6>>GAN4mP#dQaj6eKZvJYN`ULv%Az?=ekveweTMJyhYL4VbBqOq5#ZkG}iw_{S7xZcEa4a^jOGw!3Eg1K+d^5IrZ>f=L1fWh=J>aCSzTSo{hS5@p|-SVF$Mau=Jqug z4_ns`KIRm?SLCD~3NzIiQTPL1hPa!4zCtMncxcq=R>)Pd*G{$~=nM$AChR0g#7vQ5 z6gpo=_zg^V?)b#X`oH#v<*e5Pi9|Ml2QsBM`J~Hly)=jl9=#@lYH)p7r|x9ZvP)@bAR@W6 zG3yI@hJNgoOVA>S>H@foju~S{1Q98EOU}^7db!G(+K|m7cBw?>Z_=X@fvlDi{<;LH^_2mW8uW(O)(Itj)(WY>4On3(V zSzDob{PFb1Zvzj_%n}^9@QLn;hPghkySDE0#=%$~AQ-jq7G~GYI3t~t?z6;)c}efd zT+h^9sZLjQz%ypGN&#xtlfpr6!qMChmtFaJta~Rlx)Yb%<=Phxp*#LH zAK8a1e5tL4u|RU8XF@VdWBRNST6U5OzNS`~=X$_Upa}kuObrzkMHpxejVl)-fV+GL zT(%A6C78<|of1Nn4%B{*1HrsBT8g%S#vxK!c|Rt$Q;A`j^w15c%dFAtJ`J(jSGkg( zbr?lktWCE{bxC#$XNdUmz0myeeoD&WrmXJm;jTTdfj6M!g{cWrUOU`V33e_d+CK7HYNT)Cc|v0rY7eR{Qd@J7g% zN=UG@73x3-;W8+~(62j?sGhf79c+I4)? zXDWSvEhiwD&ap81$Xd`=B>4w){Nd<{i-YGbD*swKhw?-``M2)-Uz9l&n37{L-&X~S zht$h$Sz%2k9pLwKRK!9HNZrM)W#jxUeL(aIJGt-L%1x(&IGq?bh>a)DZ#3s>FUFBZ z^Y7#DcQaS;_v|_ww5mJJFPx76|0rxPMlu)6_j-CKN(+L8T&#m$gBfiF3VslHMLyEI zL)p?x-Jdo@V_b2j!A%v$J7^1J);yCHT%@dL%4!UDq?pY>)p(aZ84CG4Y$#FeyEQ`S zBS;>m1h4TWO4aZBO1(C{g@^Y<2p6UVyjfQvu`?yA>+9922(2JH_ey9xyQiDXfL@>1 zv-*3s?JNClY5}vA&2$SAi!5G|eW2W6lbD#_`Sn{1!*;Xc7M~G|C7#03>e#(1wWI90 zYY3dxqt%CeJF)Uwd+V>eoXh=lY<6t-wXj5o_;IEwWf>PwDMA3~2Wl?v(TxDcGnRf)u!L{+Y5W3?duO*%Ge&D1m zXGFNK8{2bhN=E%rYnzUbKxUOgd7YJ)s~mhVJXMI4ZCN8k+x-eS+%f(bR(@S(eI%;nzMXu@reA+$&)}PlIQ6`a-DqQ}Pj0n& z^Cpj)1MWA#!wsy^w+1X%*AFO_;BLu)5KL%GVqx$D;uz&?JfaD!&B&dge1vNVINb*4 zp6Z4>Jf26!MIK*10TdT?dMSd+KD*YHRSA!Ibd|{!thzV_uLsYeN39y28@YQj-RNbv zM|07UYRE%S(Tsr(B?QLi6ag;U5KfDX@(=S+9zi6D>AVFxU>JF~MT4R8ndG{?*D(e2 zEQ$JQMqzfL2xwa#+X;Zq$75HaoA^^zJV_U%+Y9WKxCpNCPEzzds6aU*Eu+TpbCwe?j3Vs{Kf81{*7od{ z7-Hu2eikCvMC=Q~+&9ghUcDx#q!ByXQX~O+b6lhtXyF^B0UP@FU`UmW#RGkeJU>ew z_Np5;BG4(A?^lx`A6=;&&-S*kxi@@syR8M475RF7#G0gT*~CSKJ}eXVvF0y*$%^DV zzSG5S-lmR$Cb~V9+w2HjTF>>H#Lr6{_8fsxuN%rgRdGJ6D`D2<$#i{lN6OjzZuEWn=Y@=IG3eMg9s;r-zMVEw#3gj-p$4%sPSyUfA=A zKB5jw!;$Z^h9f1Gaayin=OvWYzn{mdPVDf}=o;_tZt288l!gmg!gG}ptb!L(tb}B< z8p#9;Zb?MpI)bPi&A|&;K9gRbC!cKNh1YK+;tL}RehnKLn;+=TC&9Lz_33O+0JlG7XrwiNP2uKH{;W z;vKL=BOZwI?Oonc`~2f=NlTpv>go3>x_fz#8(iLomN<-y|Gu|9;~zp84VO8-L47-W zQI*NAn7Ado_OJpbn~{%qtJE>I;9TzN{$>K_01^qk0(-R%+?@hN>6RX(WQByyp`UDg zkw}IGVi>MXyiRUI)ZFkQvi}62>&KiYOBac;o*XUnRq*9K*BWwhJCylJ{2J6_;{m?P zk^8n>oe#lh|*5Bj*P6G!iXZgk*}hzMb@19eaRVRsWJVZwF&`e zykpx_PY)y{(`Qsl@ICDj(FNbKOiybd96)KRZP9Y70nD)6|Nd_gk z2sia=;Y(ET+~!0l5`<4uE#R8j&h%sKR+SjlZjtd5B!ioPH9vP~&gvJ$cDMt4d}U@0 z=eZu5E^TDI4|Ja=Vp7v;75BT5+(}AWDc^NkOiD2q6%`WFwJl+hOw(lZ8%-&nRv*|j zh9*VkUVcPe0U0<5wKY{7tWBc_B9w?z&Ar9b5YorPjMe@jR?&Wex7)e_wQBAGQ0kf_ znVTSxf)%^h;9W+TlWIR=YgJseI#js2;2n!n$$bCFXNp~@1c(?^CA?K|n(Sg~neemI zlK>^OR%lye(2cAsYDMr{)yC3(9&UXHmwLRx6$KgLUMY3m%yJ_=E0aSzA?6Kp_Pb|7 zmL~mKJqL$t^Dw^)SxmW^Mi1sLwbDqmey8x&3J}ct2Wl0@{G7O1S$sD!YP6Lg!l-Jw zO&jg-A+EVdy!DKo%yK){X65UT)|RfA5=x+H`{#1e5^Wc-4r=}u-l2mi9z;?wp6CQk zqNtofB6Y-^`tUWAfwC2?LV|S^@6|hUkHhRFVLT%XxvS=!QoHP5F8=y!gMUc&5{Wj$ zVL~uyN!cYsH~Z>^s1b9!m2LJ17r48#)P1p0B@0|>GlYS`Losu!)|fP(I^glygdpix z6vbrQV&`B4_;Zo>wH?O|NRy&RZI4Zow|^>v{o+)ZVu|kv{LbYI>v|E51~gqb($q+cs)BA@CgM zWYdm&zUwAeQV{x*kzn`(Atxa(Xl15=dhL%%P_)*1;7o2_+VVr^Nq4zpk{V@q%Jjh< zp+ULX&4Ffm<2`SV{Drrg4lR%jGr12b0=A_Z-czIzjm7o@(782PNGtP2py>PWY>6_W z1%dnGR)lW_J1JXg?(60^=^T!#1eycnGlRJR)?G4C%L+JL45 zCwDCI+>ophMyEI08kSLvGy48*wVzD6YOa24w+JaYQ{*^v&~+&*c`e#o{E#Rr9S{zz z!^wJF*D60^+b}*9J^_sF?4dMr-mltbJds#t5Bm|Fer@pErA-)Xqxub<5NKBNd>ZCn zPkDs)#FYVwwPY}wV2t0%-FkaGR(nC0=%y)eewo!%s%gP`xVerN{T%_?|G~ijOmPj~ zPrM*x&7$l{d%ULZ{ek(pb|j)!PChi3S~w>-DBT5W0y$gp$vrXV$9z3?iKhBdms25~ zOH`<#`*`cAIkx;{E@E+QOjOFIGIgi+J-U(QSwdL!bOVyr@EA6A2Q#nM`uqUVEtY8i zHZi#s*fO5k^!d4-&vRYBPiw^nqZVtV;xAPnmj>(+iSLM}+)M_qEXvYec|#{Tqy1Q| z8#HR+FUU1g#>rjmn>w4rOK@oqt?pjzPORIo^hS7(f$=P-3f{UaMc}y+3tRPy?ZFk2 zew?g@eB9i`NDF%MD`iPV1><#9O)x%8jS#{zK^P3bvL6fLbD=kJBYitRAySBORZmZfRta$ znIrIGe#8_#+^Q#oIn?n>U$Z1YdguS14oL5Az3TfjqPSS8^xMBPCWi>_mabfWRG4E( zbi%4eMTgs%$|3dl4LqwB-^3R8_=Dq>&O-*NNt5?x=iC(29genUFJh#2)-$&gr#N)l zT9P(=+MJyoh*N`9bPJxyms?@cSN-W}`XVpqHM|v0S;}^0%-fR#Mb3q>Q{thnerF6*FlV5$dvq-$U&Di55EK}Z>MW|WbS%)F#}zWa7lTtC z7N9QeEd1Q3ZLcaQgPxY!67L*YBa^?bZ<$@5RCk^~8ZZ;DNIL<%8FCL`X{9Z0ixrad zUM^H>v5m)$I+e(R3-+f*YNI)4YObkde(6toz2VzdlfgBjYCOlsU!NICz+bq8H% z91{bRv9$3jFm#=)^3p&~BnB`JZ6t?e+l)j|Gv;f%$@-Ir+LFDlQV!gbNv?al?Gv;u z`I?(x+#`$3NtX@%NLS1JxASmw4Y#>oxpg(3sNqwS@%GI*hI+SNRPmVnJN*Araq4Yc zy6xV^b{xysn52r{5y<3VKxr4ir8D5Sw%&B1wR_Yxv}slOq4srrkZ@|b#$^SFmxBjW zG)fDR;@YBk%MobwH5r_Aj$N)Tb87X7E;6=fdsaF}5$r>Ew?^>({oHVmDhd>L+;kaGB_5t)K06At99K7x&owuTI!|M(C8CiqS6)EttuXvYrH_o0H5!CypBWE%LN9Upri^g-9LK` zto(UndHb{*t7m#&Iy*O31$9O@v{%P!oJp{Nc;@#4$0INO)+Qn6OBZriV>8w_=gYHB z0A8Av^^MbmJImoUmG)M4Wm;^BBPo^m)3eu{5EpJ(98(T%mxIQqv<`Z<%#N%`v*vqvn@k*bvAIB$1PKDb z*Q3cc1w$948#AU+ekfSP2#ZFosnC?T(((ZRCkmR%2A63>4tsL{9+TZy!ZS{4xAj|e zDOl5@ZKt#|CCQ?x!kpV}iYp9|k&wx*8YB`B8L%@L@~_s;eICwHY1Ch72ypM#3UQauyL+hS6EZGpr?wow3Npdo*|-e71u@a6 znfDGe&blgUKS!>TJ~9%S>y#O670E;7WLksA5>qX?6&FZ(2L>H;nQ(@i^?h-lrvZ{t zW1CNN+hvTdH#W!M)KngtPH#Wq)R{ykLd&kCSob=cGH({qN4U@jxeYH=tT&~>U-fN6 z18#0eJbM!?`Kp0|9m`=t6w57G80r})d9W@jQY&czNf!T1 zRV{hxkTPmFYEv7W$ND3~P{5IG13%AAt0Mg$2=q$nd{b!Iin21?bUY#8YK@@^R0~rn z`I$Aj$LETx^?(PRU)})+cLP?lFMFGnB*C;VSVp06M^%cIyFf$J1@&XX zBxGkQk<-T)e5T|@D-5rWn}w@0QG0R%uA){gL1sS)$a#ekI?%IbQ(n>t$UI`Uug-hF zD`6gKL&|bI0Wb&jD%@@wD9(r}D>E~NZsm5HtN!fFLa6X53&}AER0M<>AG31GI7TqS zRzKjDpGB|bA9Yy?R~gYW;s?wwXk+!lq;wPBx)30(5fU!ujm$rfwDqIdoo5{?UeI1e zQFjSRG|3`Ar7cs{q`mCVZsQb-c5pT!;WrI)WNF0m!M$oj`2x4%Uwn|~g>C#*J8e9W zpSS-P%eUJ3`j+FJxNEp@U6B|#*YI(CC3UBgS`y_%UP1`Zdc(CFBRVHc>_es08NyrrK6G<-LFvsgKhSw^)Lhi^xtqQu z*I^IQ2gP}@rWFc@4*D5;u#(tLc;!LJB?p|?Dwdd7m1r!VN~vN ziLO#ckgRVHl(mbw8MOtII~Cr$Nw0KOk8JpxpMKort9zidXZzVbAZ-vd-UZ6UnsN3L zm{%ol->En79VoEi3Vf6p9`C2+ZYHJJrWg=8qq%IBsFKRR2ddBYx-|vs65`hcj|lp~ zjN|Q|ksE;ro|10ZC*>&BS?XN!Sph*pBpU}m291B|!kToI$NWDT(^Y$Bm z!VCHby#KymRYjU2*%t<{eq-=g~^Rk|Ux;xdF(O@ALc# zLht+As<<*Q0psn{&xAC2yo8qGNiJ?dDeO9nePsLU2hqH62A8}lQwn|m^}OQ3daPSj zL_F`MN0u2O?m8J^W*n&3B%^he$=rvtCV&Sn0&j#oALd&V{ZkKR^lnDi_C|hjkPo7XAD!F&Zm5r77{wWY*`7ea7{wCX?z>` zd*uFK^A9D|4&?boeW>kE#!mptSmEaG2!$jReSzNK&(`oBc^MALC&+JwZ6wDSKaR0| zhB2Mi{6^e?k8}Wqmt{-e;ErQqdHv-(+>9lr*XUC9U@@!jn2&GSuPa>jSM1E$j`b?0 zI&4^37Y9-LZ?fAnkgOB9qM=gjZzK7}7es0A-~~l5s$D1Dz=Xs7e(@ZZfKN9PukhzA z3f;I?nX^-1-?(?P+OxhiZS)oTNy5-a--Oj#kLyzun1;x6X_sO=%-#pS>&4{f1b;xt&1Z&Jh4=46%E`7^JK7zrhnX1x{OiYEZg z8MHM88Ye6deh;?vUg1o&+xU1VU>b7Xbxt+t&4}MT<@y*!8 z#6700Dsy3$AJm$r2Z(Tr#Q>$0(Ad}kb6yjFDtY=T*loR-wl7l7=2oGTXt!Om$g(mB z8?BWNDurvJ6tEdSH`pJ??TFTBNRwo_2K5H!D&wQ(yg}k-n+g7>L2+$BuA~>FRllRl z)GD12^1*9J>LO>$j!B9*jIPK(fx~-`tE@{qDt?YQcDBgQOL_zsmI9Xlfpg3$N86Vz}J$eGF~ulxqe_pl?ahYRWuOYVJ?7|IdEQv@TG@&(Q{i z4qBR6*06TCJ-SkQq|^f4L@feq(b2W^8)J8#4lax+vlS`|AGNEY3^TEea z6f|eG%qVY14a6*zkdR54r^T|+Y4TY7BJ*lMkxm=*1d#IB*O*W0s+dtY?<_*Or>6RP zFez{O;B(~%_-9cJ`i6&!pF^T$)H@Fn)lVzbiL}TU#cxCWes?J<)F+ZNT0|r~=3}Ym z758==XKkXn@s|_8md2|2EeFrMkhO9Tt*Ax{UbJ&c&!-S6HG__9Db?cCnWE!qk^X;@+QQ>8E=R;;5Mg$w(rK#nN4M$vKe) zaS5*tOySZ6E$0ah;g{i$JqeG~3~g$I*X^C6AdWKK^lOFS5KBk5IPenhaszku!X|pa ztY$E$cdj-+{+=I`Qd?FU!~+G}*h4gFRs1{O^Zi?nQ&B23$VDemxGJkk zsmw%HbN6FWfPOncC{VjpG{Q#y&amYt-#S(0F; z0utwE?qpS7B5pvw(Y4W8*AoO#SuM7Ssv>Gd?$rZ0NUuL+ugWV)L{v98+Stk7b?_tO ze+=0_oN4HDd!z+oGo%=&-l_yKub#Q@66W~pQJ+{UzUTIAsDh3Saq5w&OdkJ;?(uhM zsK2(egdl{S4qWX|;wMl3E>Pdrx6ah21AndXZNO3N!Ak+Fo=fG_B@8elCANvqU(yo0 z^eoRcEk&hDpkNrC=2-UJF$|wUS%8oOOAp|vwo!NTNg*{w+4;stK5d(lBXr>g>T(MTOO-pkYsY$`>$TNMjhTu3B1a2I^6{a&FT*j%>N+@V;LSOlP-BWVa;;Pi#xB_d9Bi` zA>>&TP|1;|9btU{yGznGsn%K*B zO))32^%MPD10|+%=NCFZ&MIcNoK=fh9ClJK@widk*mkQA-;e|F?>@*hlr+OR&PI~- zBb!0rq(@!Zt2c`lo}o}V_!Fz?U7EAWc?43}pu@rQTzX5Yzrr0U@Rk^nn(-dKP9erP zuycIUo$9Yx=h;jG(e=CxU>Efn>7(V4;MO*nJhMF=&EDBRlt~YIYhGuoKi-301eEaF zt`DyGOq!`b#HH{#7~Ayyy*%rFDDiL4-T$8M%WJgP^oY>hKi0V#&>qh6A<=_$3o9Is zw-4Feo^bKa0QY@2mhrHqb;Tr={%paBOyLGpBFud1)v_Dr*{#lfN&ABLljy$STf0uL z=XltfM)HGqO&8ExW5^jw-~Mz5>xZIMg}Ao%Lc`Xu26jNU+;Xi;Ltd@f1Bo0H+V3lCpZ7?~9s|VM5U$3;b5j!RoL_Tc{ZkS$ zlI*0&=`hJ%5QRK>30E8ZMR$4ENwaWKxFlJ9wAQ4@SBcZZpe0w<;mf`jwmiK*{t=|j zXzkDGS8Ik94`jjXb?}0}?piuZpUIUsd>>+=y*stgcY)kFi2FF2n{yn_U(vtm-OoFtP zp2!pLw+Z@yBlMDs%1nM^{#>J7|G5L&>=MYQ_tn!j?+2D}O_9~XC1@ja3JQ={11yp; zim9`ld{s#ce%7-cQm)7v>?`f6O&w;lrZTB3C&1@qZNLuPpfA~psbHOptw2ZA00GrH zKT3v%Mh*p>mF5}Eri%}pq_B7L*mjCs3-ZjRo&=tinOvd#J4pX|eqogEz7>JfrOLJQ z385#{Dsk7d&`YaL*3U46CpRxzep>WdOCGC?y#1sRqO$kL=Fz)*bNYZEKZWDHqmwy( z-oqM&Zp`tB^p5N;ii#mcVfQnhyY6}I9lGZ!2|Va9=!$o?dAQi=@s#98dRNddA4nnJ z&SUGGBdL7v-}UJ*>$4&H0hAu?JXn0MWB+P@I^VL&@8!NApWXcpB2dlANEQcRp3aaF z#JqGbVf!g<@+Wys=oMQZX@#XwT+40oeC}Yzn-zMXg9Z@%{g8J z*dFAJJ9>=MJ$;3=%nqHz(0L| zo1YRDTmoWaRhpE$QqQplsZPIIv1!h0II!>as&L7u)oha?ZyY)|u<>en1+yew`AxjK zwC5$5x?aNplrytR&pL-N1W)Cw1`xq@u(*4(Dgex>d5_(KT@kjGib6B^tKih$4MqCR4Xi zRz4ISgf&*j#@Zyp~g%H}l2kzPuWoa^T%316acDb<(q0>rh8?0RT>B}LVGD>AkU$Yn>WKK1Y) ztR@wgJ1vb{c<>LjH5; z_aCj#sW()ewUud_6Q)eHltYC9Av^}F0X1rOPQD8K=hOFpMy~K=qi5G@rscY`SVtPy zlOdJ+8m}(?QM}VK#5LNVFw0Y42L%_d8j<;@4nO=hNdo3=K6ji`5T z7E0PlV;r?zU-VB#$K~11$`kp|@@5?77YopX*NdEufl=&FeLDS9guAtFr@1=+KI7`a zNMk$f7TZR1lbNyHt=qS@1btTG_1?)v9RqcBsj{hKs06c(w&vdGa-d#<*aVY9i?Tpv zLMHR~rrDl{gZ}!XvrcVYX^&JAf_f4ujc%v#`QmByfE%>UhZk?@PJ>^Q-V=8!UGnN# zj9^iytu5nDVy`k({io!}~hx_Rr26<|6;H8(EYnZC11(TiA) z1~|oCCQrEF;k<>1k0Fo$8+5dB*J|Lc;)9Jc*X{isB;oMh=@__XM4RQq#}S_%)SIOl z!wds~zO}|Eq(6mj2|6yU}z9}n+9Cd++8vSm263*5;UD)qEjm#xHx ze3x{caF@E}dcyryAm5+@(h12~2`tL$9R(29--acPt#di1v!(AUrgv-TPMP|EV^-h2 z%U_jVG8GUOs_l`1b9ME5+hydE9OTSSGZm-0Lwe(equf)q_wEg5rO#;A=q&zTqW^ZF zI`lg5*-8_vsP+tI`8RpCvB;(MW4Bg&>~&QGGnWh@8O8W*K>i)c+Ar-!f)C%i7ju6k2RxdaS1VJ_hnfLYIK_{q92` z-t%Pfg^&*OWP*utw5X@_L@}`yB2wsS46+Nte+%tge5yE9fiChCopxfyxXsUj?Hm+V zHAeHtaBXhcAQ!H==!?Y>LitVCma8;_Qq87@ueH)tyZd{5f>%FJni0|+p-!r&I{kZv z9eFk_7^5(Kw|iu1Dv6~5VAFQ0Go#3tB0o|zqxaNTt$3J-*Mi#{afEee?N*p$1}aoY zPk{l}(zhp(djT!wovpDw(i@?j!dhgk3HisVmcNvgPOb}%G0+Fq{%QEf#vFyc9RJdk z5RYE{IYO|=wj>bhZjFFtHC@4wB9Ku?H_ucK;>m1KrDHK_jDbAxKh`^bHy^5~s7ZUo z+l16Qb#4}o*$J5J&5Bm`sXCuk-mo?Iw>}h@VusUm*|UDw;;!VUzOQso|LGYYW{??03+M_PP8bjtZ zi2(15UfM2sr1C&f(xqfzl506!Ua|hOHne$51My_8+u*}?%oQ}JWL4EsXH6E%(Q~4=8FBFbpQN!AvE75!BxhK#GQ+*lbO5$)6r}n zfSjrDI@YPZ>(lY;Gt<*A`kF^S`B0%v)z}~j$o{Q#NMNF&c;{f(8ke?go)HCCE65G4 zEVQY(4i~lMm!h6j3N`-9c;Z_(!la0h~KSw{L;?fJF8G zEbQzqnYcL6 zSx&!9ka_a4roYbO#WXY8yTai*P;;dXNPAZV=nQNL2?@=q-iVGcF6GquS;pwOWE<`- z-SdYx_D)dsVs-txt4k=lSUT^L<1cPJlquXKwg0$2aQLO3a@>1T8YFNL|*g=|Xs>nuK zT!|VS;yWIM?+Ob>xo?VgHP?C!by3qHByLgxw#<|ZeSVjYCPA*GfiiK4*=7XKEV~Ex(^oN84H({EYikAtBRIc`V+|sdD-|F_%h=Daba?S0{q6QG~FX zyMHA6%gs!!S1?I}V!vN+C;q*Vd(l*Ql-|`98u8+~wMe4Zlpw9n`}Td@nCnwJh^q(;%O{kvn7B$xb7qH14mhd$WOiZiofzQ^Z}%0iRy4 zC~!>og?8x@JM)=f>{Sg*MR#=lZVox{$1l2T6y7;#8XIunkaBl%^|Qy`bDD!FNi^*2q?vY3{0H=w4j*n*44|w!8F3`$3wY z%Gc>shjEDJ;OI0VSSl7TTlRc9(Ykl<@r!qy{U_UD)i4eDyQdurQZ&sx+mqpqgIGDg z)rt83hA7=b8F9gA4W7M)YJhJGj@szlOXuD2Ob`G2wv&%+NVC8g=n{k66`%T4D;i4x z`adiI(@>StTh0n4QtYe>jxc}rt~fMwk-tke)zXXg0^D!{?W>>ck!;Z|St9u7#H%%} zO?D|yhPL*trNH1qy0fLi{r;8OpR#itG}bb- zS`X5^&MIO*{Gv;^vhYvPMtb^&DYrjU<6xq>ZS(F-8Bz@&TrP6?J67XOUx63zmFee6 z+q6QKXsX2fG^wariT)3hYM%(thvlv5O+%yAjUB=ZYD(izvcyAvpKKnLN_*?~Gj|!_ zFr{>|L1BdUTH0Z*J+m|gwW`M1(o9D~MTA0VZ9ciK8;j*vYM_D^jO8pahHta*PL%$& zksmi0jTC}4ONN@qe6R_Njp}8E)=&=vq8}V$Z!G9PT(}zhTgz70CNnJ)CxIJQiaLP4T3 zBRYQH(Kn^EN7idvsEg)0)-BP6`GuAJz$sY7r+NL4CZ~t_=fvAy-lyc(x$C9U4%kjx zjfv_BO2!b4+*6JoVmEa(?o`P^-A~nNde~Sy9($ReOn9Z}tU%A?+2eP8oLkB2s8-SI z__d#<<65x5k8YPm3lh9E zHa^U*vA*fn2-?toSbcT;_8{&Z>zv2+G6~6w{Jl|JZX}ly!4h?6r~d?*?!P`+_9%Dp z@}io|`gE^%=7XmzVDa>YAlung*wf?(PvmC4BL|=Xx0}}7qZ7NmH9Ug~0Mflq90P|c zPJen$x=MERqs13vruz;*?7-79=Ae3%Lcic1dSH-*(60IpnV`7ij;5xSbP z6_LQ7lm0SOfS>JjPh|8sHW>E7-Nx|Ea5!A|duR;6(I>o#^+}T_O@%5wqM=?5=SkEy zet>fqh<>pCkSLr{L7)iD%^iGJ^@)&auC)klKCFTp1B8M5%ShQ!t z__4|B{OSWxBA$Fs+h^TuQkL3ZPtS{Eo-h?JFgRIW-T`HNpI95?0!N`f^FAA~7cZ4H zm+!fyZJ1!Ynn%hFRCVt2F9Xi3YI4+V*XbCP%BfjV-Qc`T)0c8rZ47-&!moER8m+s9 zT$!Vw*@o0Kd~(%1&^@OrN@3dcQhA@{5#yFzsp;Bt)BFi`BRhan;o$;T9l;`_b50Q; ze5gERo@B6K+V`a7=b^uwmAh9qvy+U_wLcmu6~N(hT4t!MCVR9#dW=@Wp!@AV>>_k@ z!u|0sIRh&LB6Lx%6orGbA2I9og}>;=&u#`hY0?8@rko69I51)QU(*sdZ8eAg<_Ip{ zWY_>j9V2`GjlSs3? ztmh2AC;UEP=spbr|G{S0!uKD|vo5+dO^aCBHrRMp6jZX9M8PN?(K_8f@Hq`iWi5Xh zL{Dj87Sd)y4YeogllNBXiiU%n6HesNg)Njs3~hGiLP)d=_85`K9VwyW@{pX zhdDO^wTP)3?P+J1JyTPl`cQH5Muz&aB*|0VZmgnItkUJMO78om5C1`7DE;{xU&M*f z@|WX9=iShN;F3bn3*u>+(8&#n>$5~>3#4TtJ@+#a$k;wr_=##98DxIM{j<_TP-RVf zOf*B1guPRD@q%zcNj;;ZExjC`DPDjhH_U@sW|T5)ckEW5d6sR2ioay}p*b@Edqe*(^pYl5)t~q;HWfB9m3E9hoa$n1L+A9R=w=H)5d3`oB*vQU)eVE5;4r4I)ftq!1ohw?BpSopmtq%tl{DsR=hkGNDd|K_ zh^IX?OoPC8$8#{d1{;p!i-5@N>{%7Ii?m{F0g!RK0`QA2>;n+FUwsUSP>=|38W=84 z9Bw5r~e>|8~#EL0FI%-{!9O@-zAvz?l?T1%_m79VpJd=P_2Hhvg5 zGN&_OM3W4-9O`jx>X>7-r!Y%*=0Vz| z*Sb4wGIy-rZe1H&==hA~N~itN*gcKIbAbxvzKB!BxnR8x2fSS1Zo!K%`)TDU;-vUl zLtmVk$)gpl(0z}3S92KzkjlraAlC=@$V zk9D>SNm;#EUZ2$HqT~fZOy*3RO%Fq`W#5OEU2Cn53X9(!FIW2*v-Q_V^w~xhL0Y$Z z;+oF9TE9ojsCgNn#(hcS0E0zfoa-=HF%;}v>|qofm`@;-aq?7i6h(ae;|__hwFYUw zRrHaqIGv`spJ<5FTi33A(|o)NVH_q?Ba6sg9-J}uZ%Zvr_0zTxrIN4!%iKm~c-Qcr z&}vENOnot}a@wEC`it)DR>(wO$j_KR`n**G&`WPRLRx{TLq%+eN$|;mqBbJdv9pgD zzjBr}{V4+OmI+g&y%&;KBg_3uFbIA}i1t8alCSmFP{S!7e zxIFs1Xn}3@oVoKyF!n3MH7><|ak*+PX5;lf$E(ZMu#ib|#yiWB)ous>YCvmdzp8Q|ZCh{M1XTAPBKglh29X8Ue$hp4*gE3F z${iAufu)U5cK8}|RZcxD6NimYy&A+PWWdV^ta{koq{cQ$jr^W4MopCH zdyr7CPc6_^{Q5?L9P21uM~; z5Tf@IHb2%2$l|YVnDt!$35gkgWi0-Su8fu<8l*8`i^y%hGq$l9w9m=dGnE*VNtl{m zQ}eqxD+VNO8Nc+B?gU!iF>jM5Gev)~IluEpA?9<1tZo=v_!TF-)wU_ahSZ%6Wr;z18bt92CHr2C$yYw>W~M zx$NW*rE&Fc1H0~>ki;jD-HR>=F)^HMqajf4Q0C6-xz)z$m&T>2S?fe330rr053w9f?jA)s}-3kl^#0zUB>0KqRyyqMDq&GZ=qQdbP^&;mX)jmvvF!QnLKj? zr1y-=t_!WM)H4U*#F3ilTS2EAc*!@FD)+%R#|z&CXTDwXRfe>7r44nq$<{KhNzsOHf92+Iq#IDU%5_OoqZV}GBnaobSJVvNt0$^R=@@wTSTQEmhKMi?ansNj<9)45^} z-=Vc{Nibfaq)dF_0)s3Es>L@g{-QH|_3s~wVON|uM*118plt|j?V6hd;0?<94@@L;bslEMT2U!f_*9Vz#udL~FRx~EYitXjq zKPp1H7_=Fj+MP5YlkZ|4ekWl01oi6!Z~1EZt&crAcbYvuxnYw!G3jR>E8yX0HRLnE z^fQ*WhTWQOeb>mW4Tb&LhG6~ z#s>UFmBQfkrCQNlDUs0fbvEG+Oyg8O^3BT0NnpuYsIS#VtxTsNDrVacdz#{GudO05 z#I44tMgVk&9Co>M3|Bc84S52AzM(rQM`po7to`sPl6i{xWlB-DJHCTaGLy5ktrc|{%ES3aq0=gz!%a}5M@g}2C9|s^`sSvB^6?{t;>832z?nZ zf>Vor(XH5W?Qwc|rG8yFriDub+UJ82fos5mmna|0@GJ8r2slqX*l?A{|e$joPmB(73U0lNRL)`sKo*=||+ z!%~O3h$({}gChP<6rY2lUSdd)$nPG;Fj8MPaP08e+YDd?82d`a$0Zl5=RSfGcNsHN zd5F20hVj5exg&o9k76cqhY~`yYqhwgocfE_5=_~=21C`qH%60!lYB{f1lTm841{k% zrP8v%ys~_j1`gI-Td{MEa{=mo?S#@5m3jFBKoub!mElZw{{bTuQzht_m}dTA8vY)- zz%%Uc!EQ4$i@sJ@;~Rz7c=4DE(@~sDeCp{*6HUnsNpW;kNM;J$o(DMrex|OSNRJn3 zc!9L5rl!PI@Xs!(e%2_-N_c||`;%*2O(%+FjNcmATlQ(iCR)X8Wm^{nN};j3#qnpo zC+1_?HO=9>(j0OTp(Kp>3i=Q?UZp*3E(cVR{Dt|~ro59+_Iu%b zCcVv;<{i)`3Gbjxww#F_Cr$+x0ew#TO{eRtAn{$dVbdWHmn(5cL8`T zTB{KuG(&zD!h=JbxtY@2t(E8#Tl>Z5^EKnWI5B zwAjsfjO~021c4CjlB~$4BX=6yQ|PXXfBy%tFT^6lG@wkWpC70n?HhEfUAlMS^58*K zv_vq~y$ym6_dS3=_xmgz9Bpo(*Qjd&d7xH2a-?aUU?*SGA!6v}h}!aoBsB67X5m~G zgBk!qy(ZMOZNu<+WZj9t9Q}>CC_HJ+%0oJ(y&Qh*aromX_E3jFbg#E8pP}BGfK83t z>w(>mrsH7h>q~C_L0VYZQ`Z2SVM_(P{qj%`_%Ma6pO-yj9u`$=?vZkOim%@cg(6H~+M8lVS;985a@zDDIh>HE2&^-^lCV93Y;i+?N@+-PP-61v4r| za<#H|clykY)8^J2)WRkHp>S{+X49`T+1QxWym>CL(p>>(&X)AdNjWmwAO|vf7U=43 zznwW7<_Te15_1n16+tcKu24Domg+N5cR46ILu^_#N7jwyCxP5*k3TeY1jzg|`z7=O{((OV9b`)pjnMv&A3A@;P6gwyd`REAtT!`2GDoUGauI47@KaIt4%@~N!z ziMK1d{}dpx#tZQ~0z9Pky(%ME_L#g;5LXRXv&XEvXK32lLMm*p+3VC?3mq0?wSCUk z0|r{3U!|H-+efZD$B@Lx^8>K_$lVa@jUC1F#OE#q7jev(=!Ufa;lyS}JEkZ%_)X>= zTIiX`RHv`8SM2KZ;WimO5aVFH17p|7fKGUz`$`)h14{`uSdikTQ%# z1Xk9pDZ;Fh_;)wGB4B9x%E*1qi*scNv2H2DrG$x{Wx?~eIPA(Vx-VCm-eooz@Qnf4 zxU{GGca}p;L%f3Y9;KT;G}OKsv{xEwU&p$dRd4lL{pHKjYtF6gfx#w~*?12#s|;bY zUv%sqK9k-zU3n{QoH)^f2`F0M$<1?E_=Uoz{)c?QQp3t{Z_HF5=14ZyyDy+4AvWTW zbBlxAL_b4`*fLbDQ=Nz06CMb;h34rjnh?OYzWaho7ZTm!rvU6KpU|qXxQQZi^7VAM zs`5Ia0x~w15@p9a)mgVnVo_xe6GRMDRv3ZY=>}JBG=SpwKyL)c;3*o(p9;_()0W-G zDf=Or2#qwe6wtTaMs>UynRto`bianumBruRzMa4}F@D}Q@(EhswK4v7J5$)4`!owD zw1^LP(k?>q5MfUExo{w-;+uY8^l0OaX5_Ny*X(H=!xq%b2;hMI3;DtJveiT`*(b#R z&NOsl?+7+MXP&7+VSB40nDK^+@N6q|tLI0N6~A<5kyz)Gwgy8S+e-VQ&~oC92oit& ziv(N_NZNScI`P5Xy;e=4yUD)oU;m7rw^~95qUa=kWzE7|+w2Eekrx>mTb4OM$3?H- z5+j=(`>ZVfj%ru|QzGYY~`sW0P|pPxvc6mAsI)qui8^}*q<*>{Now{iUS3_Pr5QTxMb)p0m&qe!>x@uKJB;r69?(4nn^ z)g+JKQtV%}^ei%+-xQ#;cAI1ll{IxYDMBqKfFhL96%v|R4Ax~Ya@Vq-TAT8(lN!!E zXqR^%(rgnM_Kk`f<0?bWcD2iv6cDrru+wf1SCHArQ@DNS2m9qF4*Lv0ecI;!ky9E8 z`sZ1h*kfrjxFs&*@565%EUtE#*&QdsX#UWfjH(j# zEBk;DES%9Y{zlaC58G_z32rlsdU1%2{^|3O zWCPLC%_e;%UPS1?#O60vpr(;~-2qA9Gt38r{@d(F7+;9^nH^p@!4#>>MygTEVG zNsWpqjdvXtx=U2SNqu!m2%gr@ZNLQA;jsm*ecz@W?fpP?v6gC2ogMbX&#F%jsefKb z&iUty`+HQ``uzGYI&^w3jgI=Dw))De@sEMsvi1~`xm}2sMC{x%uX6F$>ZbN8T6G89 zBI%im+PRNh`~B_vawX9ZwBB*F6w4xf*()jO8t+;8Qc90n;Oa@X_Xj7L-&KW&TpD|B zQ76mO*fb|A0D0Nut`)4_1R2bJ5}7H+j7XTt1P#zN=jDK)lcRnL_tW3$6tD zIY`wDRnbX%vlR()vu_zn#O*)!Jbl806f!a^GjN9Wvl7SqeM@;{}I!$LR3tgRtt z^~m=M4)_wFr}g+g9bx!UAP z8ENJXB6pcW|NOQmHP;ZD*xIAds{y+06)C^0o<%bC(2mMF+HveyDlQ*q%oH{pCx0RN zCoWj)Zlo-ho%q2hXZ~@go=4%>+W1@wLTBGm?4*uY!ulD2^|S9UIt~eg%^mXPO0#>V zoLxDnnA#1a*51`E%PG@2{n)yb$Nc9)IO zu4rVN80@=w6c=qA<5T=)V^4e$n9X7DMNAUqAVUceV5M{V11O1|V4R=2+w9$D7CYo}h>&{Z(?q>$?9eRHR>K=`!@Br+%dX~M$Z{`om&HUfp zo&FW0n@p1MZE{Zi``tFUtk?vk+I;K4YlB|pQ<)eS-XX}V6+tR1Sc|4q+N$#5YIFpZ zAeTV_6sC}ZHGe6LO>KhOaUVo)&NOe^9845ICcL+LIHSa|;h&Viyz?N?ab~QOVj@ z2J*T^yDLoG&YJJRd2Q8gX|wg|K#DlRr(qGeSJ;G%g?bWCTjzj}h?9-CYXZntGuXDb zbsPUwp~O={0vtKEc9#-&Ceze12&c7GjNVuGkC`l=O)*eW93d_hs94fGB75eXw9bf! zc9q*}dOa?CDsg7|DFr>r3hLIEyDPO0U@=K{$rD@F_hmT#{CD-~ze0Gab$W(G1?;IL zRq#s4lt5jX_bwrKS=Ob}mPjI-UXi4DTcNqsK#4Tp`ElIt2ZIBJb0?P7{gl;UxXgJJ zW2j={=zw=tujBaC%McBN?f^*x^scI^o5g8JEzVjT-6uCQQqa9v=F%TB*B$KUz>3Y2 zscg3nkXQRz4VFo3!W3J{NR$=2Dg?rLt6QVJJ>kb{5qmmaW3vnOQC6F&0YbuCa}=i6 zxx0-#(tP^*CLU;Cu&Oh4z3{-Epfgv(XXGk>7Rr(_y z96$A-dI^`FLro1R4i5JxZs1vRClYaIyK9M9%e&@x>d`_K>Mof2hpxfpVkfA6GWqkxnKky)Dc|0cJ#S zxSF3yE7>g$I{?@6_R5VP`ZhwNOLSYCh_&59cI2MeCQI2Ow%8U%daAagMx)ER|N5CH z`V6Ihm(~lMbV#@vZsQ9Yyx$MlEQ;8&A_Q=m5M|vCPl!yn@?&sWhU2p>>u$&$x-=P|Zoardw`4vl* z{jerKKm!bwwXYXPS8O-TpQ*Pbvntx3@qgBdnWLnVubGq%&GsFIsuj_w;InyytE-7m zgLgwkL~Mg(V;;5nV_b0YCf$YLQd#u?SzH-@Uy+{3Q@Zc(MY$%>P~)e94f&y3w7YaE z^WTv9ms76o*b_fB+thQ14Zrs~ZbF@SgLi$LS{`IpyQ>|!%XhY+uY!@qJ3=?-rv=2W z_72x&0=6_aXMtYKrHHsAb+s)Rb8C5YfUHPvZGz31?X|9@)4)>&=in6>NPcL-f%>nz~A4E{6ftsAb{3|>hWl32nqJptB3FOQDA)H;hHg;2W}YV!Al8IF{=7i;jGCbdG}Bl_7i0&8x-e z>K*aGR!f$q$MmYWty~TDIp1AvJq66aXbqC@vpVP<-xEdbS+;t82welpYK3D`|O5oPu zCyiFLNRUt0Drf>Em)>gUnk5gizKGk9+Aq4t#`KiuKBX+Sw6+4@LRvI+X7zWk8YuYX zy%F`5mQj&YW3Ng~_IL!>)6C{4Dco!w*lYx5UOAs;Zi#YXh2&wT&5K^Bcg`fNB}p!v`6n@l$?ypxV*ELKB)o)O4p-xy~8_0s?4_`;k~lnsq=c!dR@@U&-ex$#yW z7@$VP%ep*Nl=4GZD9AB-l{v8KTEMAgIJqKes7zQQ@{p__lp^7V-sLBeZdwdjqkl#& ztB)juy;kOBGp6Y44RXWr%$h-Oo<2NB3E3!|^J_iJnJp;*T{38i8^1^lR+IMdRQsWU zjC40$-Ho9-y`d=nm6RRnGg9zsa$~-s%J|wVq;CRj@ffZVwtzLErnS8!Bw&gZu{!7I zZOuKmO`+SP>19|=a=s6l3EUD0O9ixg*0IYE7su#J9ZbU-3Ajru-|S``M$$gSB8{i& z)}!N2WNQD*zMPKka$O*rx%h~ztP_CMq_9q)E`&s(Gx>8&hA zt5*{ZjNg`7>%ZJC zAh*pkc=VxZzx$Vp9_v-zg@!A)g6f_NJ&CnI1Vg_5*)mwPR1k*^yPigG+?wGg@!o)V zqE?^e_zZ>7WHD^+jZIQ_W&(yM!b8gpld|T01=jS{=!anA*{iAU5qrC??YTBX)|chg zq=#2#g9EZ~4jQy>Xnwvw>mUs1K5Egf=95!VTEwpNPO7Jn_~wt40$P*!b>3#^(FOT` zxe@;3@R2a}2z(rJT@A`xS&ZjxZ$S8cYpa;r63yC&^M>nMHGC4gH?^k|pe8qWg|+gp zf))hC9sy2;Sa*Bjmql}Ty+F(t!F%tD+rDUCtcC9l)gRG7OYS;M4c+$}q3T?EmJEQ? zayyx)B&+Y%fJRQT*~>m?eR&Jt;dGa&d*1sjw&520he;L~1N1XX*X3%r8DK}4j4n3x z;3mR#>iX4EM%&KMrG?BSaFxkGXRDY}Xcj}_M<{6N7#iUF!b zVI600kE8v^Ugv`SuGxZ~-?6eUcb2ME@E2u}u}FjlH-J^!VhBggPTFeiT1YwZAU2kW z-r0lqbmKEoesLXV`+$g7&N~MiU%Da2ihygz!t(oM{4E7D6C0$FX3j(^@}D+6nnhJlGAXJL@uRtCyJu(>=$@xxP z;%W^QH21xH{<_vFIVR*Kz(Y=qtiEJCeh;wqX@zjqo`=08xEdVu=KB~BYbO4&e z>C1@ikr007m8*<{zJz;qGnR$(InNPrvB&U^C91Z}<3Q z8jQ%{c%~tF5|0D6WoQJ+cpgvg9!`m4lc_>Z(LZYr+d?+*)(@{!l&hU=mXj5;ZLD6t z2U^3<5}GUh`2<(VQCD-_y}x;L4}uy}3%TE*Rxr|v4S{WSBC{z_uTZ@juvMh>@mjcS zW_@0t+|EP3*hGc%Z4OfK{oiPcAwDsWTTO)2(=_EF8bh%1q9N-(#~spLl)Eq{kKuvV zCO$=Ww+nH}b5liAq1f`4Q?>Ui_W-J<;zQHoqvBT%`-!w^A+74Yi|aD~LNFG|xlC
LaJuzye@!)Cj_i;NXyIyXcF->?$3B^wV!sdJg z%wKSXk1nOfPrJ--SL^@BE71y%`WZo{OK_GU=97z2c1<>sllD?N4b2|rqsDk2HJM{U+YYdZafs3U|j{D7SOpbE|l=HNq{=w$V zM3M!J(f9>E(%Eeu|B`E@v9rck;(He z8XD8OF!DvPm#aPz7CHN|u)cn)`r!=G_h^#lr#k+ZGtQkWAtA6MOv*ChLJI|Y_ z2V1?WEuJQ`0h4b|EdTU*KA?-ZB(+P1k0e-K!LF{WZQOIJ&RBnHQ`_Ydr@OhgyEq|Y z$&Gb}`^4~R+!&>9|AmZ~xz5X1wIp!~P1pj4fJo zb_%b0_4da7p?Zwa$hOLdvE60($FukE7w`+BRlQt7_J%F=Nz6d)MD8dh*b4uKDj+%> zn0CEdsGpR3Rl^eElCK;9Rpa73E8K8UJObGTMU=Cconrm6V0k2I-{!N+7BY2lFzEce4P#-q~iPWH(KP#4vHzXg4i*^46Zp6cmB*t%1M)LhC{50y#_ZGG^|>;q47G7h4== zNBaIng9KoGQeoK8ooP@Piu~@L*^VGfrr@$18adv%HA}5@OZ7$JHNCdKZ_eHnlECmx z>S>CgX%A)oRe?Op6}9x2!7psW)ciCQK;r@94XjevD=yv2QU(7HiBs*-2`zXNwE)1~^z zj=nU^|7YU%9p~8QwD&$bYntMpU#GVwj^A-6&g~)xBQ8zQ1;Mm@_w7RT&97~0sil^O z=*Mxc?osVcHcJ^m{@>3}yC;)@Z_P)0<3=Qg+;_fztR=bC1@p9GN?UA=f`7&zn8C6DfEPO*Ll7O znRiz*8CG(HH-Z8{h;L%c{|&)x0Z0#)wo{n11k%LZLZ8W0c+6xV z&>$z7aYwGJ3Y@3xP5~v#qbaukDW);`a1I>s73eglo5~mgglmj*Cxb|0eMZ@C2Tue7 zRM{R806vrb?fDg$4f2n$^KexcV+u4t{srpOo@IMz?hdMR;MsiT9Tn3a4yqEc2mnBH o)B1PipwAuIGLv2iAMtPHr{1~3GCAKG@E87zf&Xs?z<&z=1)lHEdjJ3c literal 0 HcmV?d00001 diff --git a/ur_robot_driver/doc/initial_setup_images/e-Series.png b/ur_robot_driver/doc/initial_setup_images/e-Series.png deleted file mode 100644 index 34cfd3e6103377ec51faa1c481c5d15cfaf157bd..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 208062 zcmZ6yWmJ^y_x_EDN{4`ScOxY!GIYZ*APgYg-3=n$-O`MN3?0%4(%mtXfFRvn|LeZL z_wRY}ykIRCYvG!6u6^!(?9Xvr5o#*3Sm>naNJvOn@^VsOBqZdINJ!7xQC|YTX-}uo zKtlSABrhca@m$=`_V}!?*>o9TbI_(LK4k&&Mn;qW8;lFWYNOLkCk}<1d2MIMDw`{bz7P|W5#=zt>op|+edAmT$0w6qc>QEKLW0{%oBwkzKV!?ty+l1 zQPa@S7=69z<-n=Rcj53EO_$AATT9%)S(BW5NZo1>sH^f?wZZvQ(&%d+cXPHqHnz)|TQi*a=v91t{PEEcPQVkh$jjTE{l%YnuejC< zOmNm}#XGWQQ_a5}w7&|teK?@tNV52p%*LnpRi$`Ks3BXqSVOQO#!N?!<~RsR9C9rY zz83~rLK4SBljL7}_4E0|vPiqrVY`@h+7+)HyqIIA844sDkLsqe2}neTgWH?n(e zdv;)=p`lgsymm^7kLTv}UB}09JngC7SrAfckKZ_yrLy?he)raH(3CRZG-BcA+a=D; zyu-vKC=U-rjq54#c@mj}K6WF1^j-YmR(uyoEsisQ($zAyvBv9>G2 z?q<8;6(8X^vF2zobEWNZNo?1{*6rV1)5)Gkso4)d{82&cauOwk?yQpe)g(nRvyq1t z2ex__w0?+2Y6vQn1_jlM&NeKS#fRH%^x0+>bX;L#wQb`p*X!UJ)#LHV*yP-*vaYU3 zTelyOXT-X?@X`kTTbcw31oTMG;}tY~(R6{Xu+>N79+qfx1-8S5&Q^2Q(Nr<^|-ks3F(w zVcRz-fpL4yKltMkCaIr4e>iu)s`BnZSI|lb8uJ&qqjI@@Id-N(wSNeWu&X^!b*Q<3 z$xc9@(Z05#dH(!45V8pqY`zBNdPfilV?_VJBqXmnnr5KuC=|J&EVw6Sa11d++Q`cYkj?4wJ3cy4)@`g}rw@Qx$lB z9OY2u@({K4ssLAxB>}vC_c)Z(EwbW7LS*3kmI9w~t(lV*g5v*y_$5l9>KYpee*C=g z(V}uo{mdH0C>)zGA8ZNx98dkm>SWbM8aEgvUv(|)x?PqyROXkJS&j*A{9gKK(lRzy z53*I?&l+~?dRDqWM%ZG9?7+2RJl3~P;h}rphI#2a(P;9#uYD_N={D)z_{}f;jRz;7 zgf)}?SHi&-@6M~u&KNHjZ8)DlJXiWU-`g*D(59emKtWFV69+l6i9J7QyTW4b`1?^n z_F^WJ;6rc^`HwYfTc(h0FJ}0NyaWqwzvUN#*Vi->Yw9lgtbbTx;E47>|ChI~{!$T} znifTqF((_C>@5=RH>?rF`VGmZKHiT+z0q^Lx%&cA$kW4NGBeT@&~3E;12f~AKp>)K zNf8Y@fB)ve;aD(DK6%+;kE5vifK-p=RFg-PGv zm{WN?yAnOtp8APFw4XNir|SSAP?_=G#9bA}^CkH;4Lg!d=o;k1e9I_vG zB2?>D81H|Xblk3c2G9eyrk;MC73lhDh4ou^9nDEmT!Ja9s~5~nlrDk~4?&fLDqC}Y zK@4B0i|R`|W6OGoD(_gXp7y_!dvs!|h&^D|+#pwMBU6X`YOpP0pgW)$&$M(lWfaRf z(ttylKbB!)V^6NG%06{c!xGRXh~aynT=1$&B!xy*a*Kjxy#`$k2o;`^3Rd`CL>{m+ z39F|@MINd_hHJXz`dwb&L0kA$ZQv;jyH+sG61-sOceN0xjdDpH7!>sZ?-tqUJW1ji zl#S4agD^NB6sADOm*-0Sk`y#lQ^%90K?C6VKKnl$b zZkLr_mlJ!|l5HK0&M|)$9XpC`jQ{rB1uUKA!r$D!ar9t~C&T#&Im#!wP4CygO**<>3JdXPaAEhA%T7_L3Cm zs+9750T14z#4xH?hYezuu8T)m)|fNugHV$vx15mj!4s>cY0Dk6=cM2?GbNKa<>GC^hx*!{5_P>f?_G`%Cxr7%O*&dk*(qADhmyj<$b! z_$P=PT;-oUTGG?ET37eoJ);Ny(X4YjtkL>VhNGUug01IB%?mv(!qIW`o57fZTA3?Z zZNxIYJEcndG`!?0o_pU_EWeGO9ID7nD03@KU7(zS+sp}(GJW4@he3mqYG#C>*+~up zO-a!qffQUsNR6e7HYy7clZ8H_NTg(B8Nz1hhz7etHFhvF!QZ1Ji>u|UJa8#4%FmL9 zf{N*U-9Vv#4|t?xG^dJ z-I$uE_B(DchW6z!KDqPoMET*qSW6RZ2W1Q=T?ihLMX5c6P!UNmAyWD+Ms-aK)W2kR zkU1DO;yP&TI$S~b?D-Z~{j51D0m%f%5a`>c_RV<>VZn`a^i^qW`IAm*ym58l)~uF* z-3kgRxRjtC8Uw8dRcjY%eW#%{NN!?rndH7*{p*Bo(oA#$lR6iKod1yG^O>@w80!D) zB{Rlx%ZV)US92mHqbQ3BxQucl*l?XN?xQ@|2N`z`LS=ZX+LUhDZvu3sWtWw(_wGOM zopj7PT7hI5ccCO);LIzQr{zCEzBZM^uOlZu` z>+7m)*=}|}_YI*3dbj*_LSvP&# zfoo?_tiSFr60kZ1L`-U+g^L@?dRq%(p}46BfndV}-Q4t$OjlNET>VcrG2334SXeYL zzV}>&=_M$H`X5>9&Av6jZqHKhI1}yry&82GiW#hj%N+t}PY=dS=yFM$7 z&<*qDr+`o+IQSG|Du^}3e4_r|W`Y<)>~u_dgm^NB%cB@SNZt{E7w-S>Y&Jgu>89VC z^%-wyJ;Kap-sXw~W#L|gbSjZTQ}BSl@=v^1jPDKETuqzJtH5oVBB|M8Ib=eRzSKhs z6RUs#8jae-trB|7huOIh5PH`K{A&p@&Y#yAG7d86CpCZafP+RtVIa<2CJ0T=wvo;o zi8T$@6g7q4&79y!O9a#IUQ0)e`TpYD_S|ZGK?-sA>GTf#i+v8fADDMvwv5Rnh>hi4 z6u?#?A7m;eTxb6Nsj2I2;Fx5|f+8(|Oi1&pO-L6)Q%@c}|7kk%{|X&WlO4y1Wj0QG z{ydsA+B7E>6wkS^_7C4ISi}R4-?PrJ=4@xIjau?sBo15*wXPub&;Nz*F?!Gyt)mgl zH`vWarW58e*!fbd-B7YZ+;Sn&o#A-uX^dORpPKX-vsDVe#AoiU&kI1i9ZQ3^?>uwD zN}_-+^7WWUqZ#+4alHra}fo)WgwgT8I+|h85xWw)Vh_apNvl?-DJjPfkuEZ{pv$@1Z zE&MyaWQ(-yt*~;_fEaQA8whg{9Nm` zaBio!Y-kvSqo4B`w14820Gnv((!Mt6(i>~A6`eELn}yfa*H5fWNYLam9gDHfpyzBO zQ&vyh|LJvi5vkaIeM=KaNF5?oiZsUi5HbUW+qYL5DB1)ko4l5m?SU+N5@PiK;EI>K z51+tKFc~={4U8L8>*-N2D};h#_OjNk@l+oQ+zPwCQrFp%WSiFQX@*o2jl>S--~-PB z>z~ue%`>#BvA7%?$xdp{wBGG|oSd^|ztYWAdOe*VIwA7+a>khI+b?jsb|7;=pGXE9VP+H}$ z6VNB^xgLj#wopkGpS>>++scL2u%MiroaVepX*qV>;OLE4y~(^}J$%-RJp*^?%WYK1l})VmCji}sFwz9VnX z94eAySyiq<%YtwDhjhGb;(?S?l9s{7o3*4Stvq8(=jgAcd9@p)y)47WM-#@(CKNWp z7)2E2(DFfwNhn;fXv*)sU>Qr+aFm?r0?PHxsv@WWjnT({4-~B5HA^(h^TRHFhD_j@ z8tI|Xl zwWZ7qPk-k@nZ%^}jZbvg(Q4ByPS(aHlN%M;cdT;Tr042;eZ{MwUXAZ^D|j+vSi`>t zQ7JKENZ~bj!p)mQwbe35t4nFgU(~{=^Yl0+%2HeziF#Dh?@}i&>Ph` z!R3{>uw=KBG=MY3F$qOw#m84E&U>6H<#_M1XmRO|N>E*!RA>Q0GvFukXG>#-h!;up zZ=i`kkhoLTsy|Fx;uqpZ;OM_|iIb7qVZIO@?IPWqcnvbv5wMwqn~W^h^YQb)b(*AS zXOY35=*ES~c2xN6)K}bnTSwE{_d^fDrRbeId26(5#K*xys~kdONrzMqR!?jO;i18* zuMAWjKbDLy#p=392n)vAS^F1kmn91+lX#$6!_}a8p@Zcg3yCJlU&n|4NOr1w#SE-& zMDa@h>r*ZDjVJfH_Qt1K6^2f-R*PcTb&Ud94!zxFX%{a@g-oMo&7JWrR9N7^#L(kZ zWlia7;P{#xv>_-*Lx!b>`+8|`gH0niWR%QvL?ELa#5;3KCHEOQ_ zd%Y~S{11FV4?#XSumk$-B0|K{$|@h;7Q@&Pae!#l_zsCVj$jlT6TcEw9#I}%GQoNI z^5yW3xIBH;I(p{Y(A&RGB$eqmBJdGoY%4~2lM4ku29~0eD3%8vgY;SRU3zH`A-3@_(c7FpifGVkPJ*#m!0zHrl2`l@TM^9FABqA0!`+LkGD_#=oT ztFg)tA&{&^fG&O7L_S%wYqkByIpaWIAHqfm9J#@c*Xxx2n^MMLj>~0HTN?$8aK`!t z3ZzUk$NQ8eR^(EfQ8{P$)@_gOExu~d@UH!S(D#o=mJcV0W6_2Ct&(HtGIF&@o2rvx7d zoFmx3Q$tmJMBih%XEa;Hi98G<+!MUa2rktkrX($DY)pd)D+{N9q_z%#b(n#n$v03* zU?jGJ!gi@DqC@l?cgkYeaMkY$25ZV_fAnWZ7$X`E%5_>&b!sp3YF*g)=e}=?TPZIy zQ}!{T8a1PvNHD=P-z8ws6uvgY%XXcnG=RZ>xrO;z*+rE$fZ4JgmLhPuh=>0fJW)ZN|PN?8Kg z(s!Juhpk>fu`()WN=XJaiOpTiFSI4Kx4#!|bUy_&lXjy${B4)bNM^l_cD*&B&tVgj z%l0TuNRWe1>v0#xaQfSzQjOwj_Yv!0JDT7S23bv2y=F{OtDfRRQ+;L$SCFd0hF>K9 zW=OS(}kiEV6l%S<0_2qYLEz*LeH&bD!o@?Nml| z%&kpTu6r)tuHC&)Q3z3hb!~BEd7V$ldR=qjoUKPGp6KNgvV8=06p>f^0Z7Wq%9!U@ zXOoIt)mNW&=aSYsQ?pV-x0+K~geafw8mSz|i^Bm~nJ|bB0nrR5Pj63ZJe5PLR=La}fbbdtY4!Z;4fw z9iq`HU4C_q`q>vT#`@E)U1fr(o|DHPz(!K`KlI9JWZI#lbf8uKm(!{HU1v!&!`jZ;UHr_i#o_t#J?f<&ulQM*}~8j5p*;!r29tm2vs`H2CVc zW-K@@Am88eb=ho`uU1#bH^g*8}JuQIi6o0t`KpT zm)NrvxP1fEDsBSm?E?xi<{ApIIDZS1hPY=~pti$d;Fa z{PpG9m3>PtcuZgrF~?)HYx{=6lUbJ1iylY({@63X6d)x0^g{navS5m0$`Q(`;*+(x z6(tiJ47PW6Kbq3V&I3=Ftl&T~i&MaV=dhz*38l} z9*azXn~yJeyO|lr?SFlpoF8H)&prfFh%n302vZ30%<1dwL~3hmGv(D$5j;Uzx!-!n zYjdTOEIY`qe@iRYCWeZYC17X1{wsp$-^Wo z@|=O^R4K;XUb?q-BH3I1oSYqh&hU^NQH{$=jjHrA)lPSQwxmA^Y^dmR$CK&)mQjWl zm0(g{gLFUpA=V|%W>5c;ds%gPpgi`u<)I~Q?pUqm1g(nr!}-bMJWwI5|5qW6#W`l? z?nt@hcL(n?sQmV89_vi5dR855ZA~pL({ms8Eyx`^pPiq()^6vxT%W`R3{S{%^`40~ zx3rx2QL()z)V_MxW6)Rq+@u>M`yxL1wW30BGGrMT&JU(jR-CPWL9rr_f~+$)xX&c0Mo4*$|vKh|3&Q_6_p-lxh~N>?%;Tk`hkfrs4hdw-riC z2}Y0itX6U#q3pY&Ns=P;uth3(e$@Q+jdukYgrkw6PBzSC_nai(9GL zp7(u^?q1A+*)BEX5i;Lr#u;4n-I*i-td#n{X`pG5J2KaCsY#A@lPnZS6lz354XoJ7 zTfGL${hxdeq*YaMn6h18Q{Aq;8rVKVLXr4f7aXDMsgw7k;zuWBr^1pdGkAV^={&72>wGA*tzHVzsrP0G3JUsBp;)c5YC)EnMM;#!|IH7 z%3k4F4;VlHDibCll*9oloK#rdWL2Y7d{}L^D;f2MVsJ@p+gLtD;RYRGeQq7T?(P0w`n<`_`F*dfK5ob`#X{QLzBxQb+}Av{Z+30HX;{Mzd}1HC2og2>FjSK5{X%%3E_Pn6|ap3?Uf zO-D^6_IL}VCXIY~_hox_x4=fpUs9~=XE|D7q9rvdzeMsDwv3?_%#l2d8)D%37_$91 zKCz-cZi)I6=lPcpNq}Cy`cLXdZhNU)d5_x^&UaI2*ANR+QQV^rUw!QjlFtdx&4qOE>{ojx~j~!ES1D()o6+b1iLZhi~#N z6LpB%SKnQhub%4>8xIrma@T1L|3Q5yyf>5ICLX-*<ZEf5Yj7IMCE8(e! zf8$u0_afr%nTZhrMnlO87wP4%-$f=iZc46S7&Z#TDd5vecEjW2xEMr~N;WRMz&BH- zni%}qx;_$YtyD{01XdBFX>!&uE0(cwSg-#EPRLcv zOp2Go$ii*Z>c!#De>2~p&t*qRXjiCF{6kMTT%l0;wXYlu`iu|g{Gyi1CEY`1^}Bef zX6qD(&1ak-aYNwhlY1;Vk-LsdY&_s80H>q-?{w6t+8suIro$>1m{`~e1LpmvHSC{S zuRB_E;tO)@E2b^q889Xp0q0f97Ko8gVw_l6Q86*03jqb%3MdZBKWD5K!;}o>K6w?J z9eJaevvhc|bDJ-E^C6+9V_NBvbESe?|Tj+76? zHi#ah6(Wqi9(lNg%BMdz33ifWb}DvZMN-(7We~MUn8DQwQhO*Yjr> zGtl32$vgkM60sovY&dd|%r12VkAB|vMy1IR^LbMW+3jfm#J7+zSy0*(Vaph0rgMIA zdAf8qR_*`b4S0F&+r|sna5#rjI(J~hr2u*pIaUuXE9AoUDnWq+CdrPV#SCgr8*~R> z`+oq2Ex-`IK{)4Z%#g*)G1y?r%*7k?*AgE@jS?rzuagD7$oBdLF0!*}o|DSa>?XZa z=W;NQ{)m~3L|FEhz!>6INHAG5V8#o%Z63Z#Da)1NYcwU+PeYzic>5_-!K&JS89FL* zW&7zYbMBbR!AEyf)@2;ZztG@2e)Zt7i4l@(zfzUJjVTWU1B`FfT5I<4C)S88P`Rgx`pN|MlYVYl6q_~_<=@F*$gZwD+?PP3 z!A&&-3jX&B-)4#B9}6k1Rv9(uOppG4K3E}P;7=*`KKIu74+ph7^G?E%T31nivZ=Qv zDP6A<0|Widm9o0hDw-2@?VCa__U7K&#Od(y3#{L~7ZVdB`Pd|0n#?AfB0G3wYso$< zI!2eRfal5SvHV~WEB<(W@+b(Dh~oe94Em9ikziP`Godi7(I-b1@K+$L4~_L~s^SlP z|5$uY+hZPu$>uAc&IAvyH!|LNaB6&0V#pd<6U0`q0>Ims&(;R5ACsW?`_&MHrJ3{U zbd95Oz@j@}gJ}Q!E$vdX3dW{$5uIRZ6XetH`F-?RhS??igSz-b2_Z9N6ESHCDl)^z z^wR*( z&D}W(KX!2q;*%ZbOYxH=|x-@3fVM zj%zwqOOh3z9SK;;*(^LZZOK}77~_jXiy7qNe%3AqoYwx;n(er$vHe&e84Y|+>>S<G5jA>%D@N z@FL=C;LrRkvD3dMv-T~@hJ(p0Pdld_*Ed{(2X#|Az)E-Ixh-)liT(sQ?e0OnQW^7H&+&}WmegCwROD_ z*XN?2%BiownbqxN3w&O{j1gfeN@mx+d@X@%h`^S>jaMk1fBO8qZ_^;~Z7CbwWmkV5 z0hSHthWotMeh%vBmkoSFy=Ng}%58n`+w&vHH zbF0&`2o4mt+DlFFf$G*85r+bMmsVt+mdR+250BR_M8IK1bcL!GC^^=|dP9H)apnUB zGU)h%!usW_mq3eC$`M^yZLW85G&Ibkdw4gz4{Q%2H-{b_Lp#OUy)B#p?4Z%ggju@iMcsh4^Ce?QnuV52_S!xh3WUix_I&gBY*`nqC48zc{av(IrG;RU-#QKwji^zw(fEQTfzY`tli)hQ?tO1 zg@skF*OWLqs=}Hwi1?<&!G8MuX;O*xL9Ya`7Uljpd*;Y8W^eu2h}~$vJ0v@b(*sc2 z|G{!OmJA*fbj7sx&c{2d&Sj6~7~F;3UgfNJMCc*08N3$l`=>;Djx>!cw`8g8Hv|^h zes6-F2krmerJaua{gYZER>m* z1yDAI+_8iKQwbaLzMlr#Va2n9naXh@ z8V9g1{1q0n2Z$kgI5m7?O_dnFRn6X#^Ok|#NEGbsDrPA^6wXbMTDM`B#}dXkSRL7_ zyYNlR8u4-MgoK6MGWP60oPml(a=evfBC%&hTXDg{G$dGiBv; zbzgCCDCZejdWHksN1?l$Pe1@{YYAA_eDNwUN87BK?;kZvlQSCU^tK!_$C6aVLQD{w zXD_^clwLwA;=3EzftVPeR%{V8e*~puk?|IPar9R+T@-QuJdp{M{=)X?B*J*2FKwl* z9+rnj2Ro$TO%vdMZ&cz`BmG5z$Y}MA>D2qY5v%uO@EFFHC{O2a)x*`2t<;8KlT@K8 zVboSq(ikE_GwKb8F=AGQFEdkjqld^~bD)o^Sg#Zid|-Iu*q?NM z8-cT}18G^=S3RLGPZ#tyt7`^KCjlrxN*0s8yT88){Ee}rWq1TWQ{rfm@=_oHP_piq z=V}!YKn1aq3D}wrrH=5uG z#de|Q#hlwJblz?~FlW1iC24?NqS^>wvdU3R^_LW9)}<4-JdOT{X%me&zba`{t&Wj zJ9201iaY~?eq&;He5#^1e9Y4ITCk?l4Bk<}poc5*&wvv2U6l=qRLe*TlptPf<_`^f z89`gxzwM%w&6DCXCYA=w<>TSnvGK)81w}>02Pa{5iL>!F>X;a5a48?fft|O{$Ap_# zl+0i2B#Euv50`#E-W^%AYD*xoc2+acY33@xBkhWn%7Ym2Qh^+UU~CZXmrk7BKLa0@ zvqFdo4V;u!#LUD7YhRmylwv$HKZ`8Mnmgh*k=*f$j?0$hzh$Vl4O6Oq)(AB#(#r?4 zOf}WUz2HSGIGDfkYik2?xf~qG@TvkjWiX5FP;U*rJAq_E3NoUm$_{Z|g^mS~R{`7k z&hhbaiP$9X!K(*0vP{y-fUTWkwC?!cZ|1(M8$S`0n_WX(n*d;=IEpg@b^Z8HKZ0;W zE#Xa9D?WIsGooIn1heJ(%5$R!kne;@?N32_Ligcxf|uzgJ3EImHgu_}T)MrrWADSX zGJpT38TB2}`Rcq_s-3C~(*s~04)tJ0L5?S9QDqV&h_G+od|Rv9ppHJyc)su$K!}M)-Dic6Id)uY;fYuhHRNOBg1O z(V6(Nru5b@#M<$+)QxL*b=5E!;jVeT$HIz{V?nJ4F-y$xdhqaP8?E?9{pD&Y;ilF+ z*nou{=4mr?I~PPOinIL+9 z+`aLjt|aH#gBS3m45ZKK?=2b}R!1MtaDK-HTywZ=4-4&2Fy;8VI_Bl_fB)#TSX#XH z>e=f3Y@^pkk3*+?F>_qBp?uV+UH1LWVawk=vJWgh(nR{f$%%)D_Kd0-!@;p=^Rbe+ zFDH^^=eh-ABnLcmO(Et>bE{)OLFeqf^*Gd9L?D`;9(^)|-AH?kB_B@SkVT4~_7~bN zwmOwm!|iqrJyfl#0>+7FLa3AE-?|M#z$)lmGo8hi?U98m7xh`^sTN~TzeKp`leosG zR#gG#s=2|T@60bWG;|(FN>}Vn&d#djtA$^X=b?2Wja|evwdVLSocQKK>j#g=aY-dK zT<}AD1M`2=_>S==!RorVl*uycwjYPTwh?L0S?m;Ejd%F*D!zZP8Wr0nFNeHD8gtQU z_kBU#zg;UgglsyUh6+;H=%_(S{bQ*6Z6AnG{t15pXfy>n20*&&bQnEn(<(0lTogc= z!Y`aVwhZD&VFu`5KBs)ws<~=yL+i?WTsmyp&N+FMW2A32{y*OPy`nkt;c7K5)HrZv zZ`NVC0e+T~dGsWlHexHdThb%D`q(1Q4SXHnRI^6qyig+YwwgsR&NXc3s}f>k-8tLN z!M2F4NyXJ)z<)9Zq#9#!6Kw@BENv0Uc7ypF^C*ahf+Hb7$u-z752k$7`}t1`ixu6K zJH0{Pam@stA8A&ma&ayX6PiYB_bK5JFD;})Dm(`OtHrKY`+0njg3{_2;^zy^epoKp zf~ja2s@op90SLIbx8=j()soB8qgPp-0RQ;>l9FU~V0*j2=xTAkc4q?zYYLA@OUusQ z&d&=`(XnDJH+3itOf#1_h0RPxW)RhCVrdf87mQ8LBn{;BhPSX|uwo!({QroI2Dk6p zE$8y7;y1VtZOg4U6lpG785Ve~F?I+5Ujw~BR#nxZ?pv}P&2XtK&F+QJ2?57r2S}=z z7ABSMY(d_~m_4Wl4B9tms8}i1gkx92>_fuhnB5hx13 zZhNyaSA9G*zX|^vw818EVzWx3WrU)0bko*0E|N|UG#GC%XY`H^#>B2f&$dRS74Tj1 z_|MPX&wiQ2Z3tpJbnH{`@$tovm$jFFb?DKSf9TN@wJ-{E& z>v*zf`IC9oeurL%Yf2mBYobAC2gfHK_gZ<3Rs69<*0F_S;Ctt=ZE&3*_=?JJH+W=E zYslGv2uP1Rt_8k|AIYrQ2{op(JFrvA6b*@JaT`~&%~N9sj3zk%{X*a59Btguq;8Ba zEh%wk@mJ&3liI`4yOPC=r%1ZE*FuPL`s9mQ1O!ZkSVUo7BRbosnR8zy7_)h3<*jmj zZ%MS^pMvbNrar3=m$D?K%2-OT_|%d{*U+#3y7nwH<7A8JR4DEz!T`RY^?7XmIT#df z9$0H*ZwIxo*j@%YsSz%UIaUN-XRXDU3V0d+|8n`9MgxfqMQ0p!^#aw1y5)gycA>9c zE!4OT9ae0&0W-_!bW{FEMbzxKAjh85Kej8)DHvR>@c`6PW5t@9UF-#V|Ig?QUO5XM zQ(mi=FT<)hqFfnc%ydmBt!fsc(VhqrA0Pd_y<0N4jgXTVRW>`HZ`VFO-u?D@PjNtD zT0;ViH$!U!^pM-qcHjKY%L4>4IkD%k6IfNVjBs*?uj9IhOS{>X1iRngIMp1l1*Rjt7MRU#vogY5>}nJL#~&JOp}!x{Luf0Gl15Ai zig-6MUPNL6^Arnc+ZuCpK%94Gztx<_>NISel~S}QwIiE(6-C=Cpsma~}5BSf?` z3wobSeDydK0`%AKSy9`e^`5j(n;90lyp1tJ@RALUi1ZH{G%~7a=tj=KJ;%>kck zud~dP$8bja{r|n)Q>A!4+t}WtF3Vm}*%-z_Hpk1yrxXxCr7PetOh}r!njv2-MPtx; z=7+M@#0lUa_S&njBY+)aZfJ;0lP3!P1|j`s(uGnti;0aju>@R?qJk;cnwtMqR~`*G^YPl95cd$fZu=hK)f?7+ z=lc|nXmvgt)dB1`ZVeFt>s4nTuK0(Bg#irg-}wDpU+0?P!;$q&nT|u~@ARag2`(e& zT2j);a-FtNAQ6!?wjB?u0RjeZD4N6H8QhvfGqXyYG=a=!yw66SR+nQ7g zZ}iP)%ox@3(OKT01E&X*a#kbk@zId!*z34^Pn3j*8V(Q{qE^liCyS}d@Le83zI)4R z?H}T!KDR@XI5S)>2Z;2aY@9rBkG3 zwfx?^@;kdiytF~QJ5T=eiMMz$X)%k;I!6%>WxymfB9>VWGAAVB*eJj(pXd)2gw)NC zcgALm0ArZsMh_d|{*S{ipTy*JG4pY1e!gE07HuMu%tn~XVK92^h}Kt)*8Q0p!szzt zyZSStw#(|uK?1Qp8<0McHm-%UIu2>f$H<0*cm)`s!GY^`Vc!LGA{&^&#@$Nr@BE*y zoI}1)g=U7jlDej{J3vE?%XRkEqFjk0C@^9_u>;~JTqbelD1HPCeDGBacF8zYUf z=VO5TyEw5sW^w-~udm0Uik?Gr{@s^^s^T4gB1FV5E+1M8SFangw#&GG7{)DIT&m>0 z&-Q&U%bCWIHnd&@)>hwbE$vFU*v-0jGIP-xOyL0t$A>|u_(@|+PgE8Zz*)!Q7~wd- zxS|W8MwN7Tb^G1K83J1Q^)8sk9!^g+mbaZBVV+@#G zmV}nlG^LT$n9(0Fl)eUox5S)ijWqkW0r_p#d%i>Nx%P~_)$rL=u_{y22sO-C) zvb}ig8$}l0nAvisX3)WOKgP-R#1q zc)AU?y*2FMiD^qqPvSmzrH@9N)nEm@&@BiIUGfXJRO#QbLC^96POGALbIow1{KANj zwytqOs>%UHbp=zwsnV>37q8!tF%z8SNWyQ(&BVCtK#;2vGBD6K(%fc@1>{-3E(^7tDV zlz+Pj1I7QGg5qFb$Vc@Jr(XZFSNmhZX!wrg#g_7Ww+WN|S3a-qG#VHtj6PpY)BTX> z&rJKY9*nO-d=zI50LEbYeBiZRqqJK4Wno;I@uDfKE^fX2WZ|V6+u(6a!ZkswI-n0n z`EEDwdEQs|2?8t9-y^C{CtLUZ`JaHTWMwrl?UF$&W{MJzs}1@>Fm0{*$@8~Rj^8B- z_WNsGo(#V3ZhQTBc?k%z*e#tJD#q$nRgpHL)(g=Lm>Flwd+jz_Zcoo+@dC03%A5Rp zBwDWq6|ZX^h%v4ZK^>x(%;FE7Db}~=8B{v$_dVMdqhD`=^f(c%c6aWqX1r~u@DkFn z&)>euq;eVb_Qw2+U2ALs2>t6m2zwpw;K%k)cm#OWBW)y;$9zm$4$z5Rjl+G z;a2rY@$4?qGzA*_V&?|!}o-16@IrNixa;j9uu?Jb%_j0lM0YKL|zUyefrpD3-Q2n&t zEynjJ0}K#r{?M1oamE5!(&!r3U$;Zo>!Q|ndP)$x7p*y(ZG)#>UO2L9_uum8PF!qx?J<{-0$JpLI47*mQ$$5aD5 z)1^q@4&87OZ?L*~B2};qUvTC!qly$;53tk$*Hr>njg<4PpkU`eiA3#=K%!3ofv5CJ zAITEfxP3oWJhnEip-Ok`mn>j6>LlEBbZ1(lvtINJQR8T%>Fwjg2{;PRr@pD0SbC;E z#}@od^>p3$w7vZhCjJyCzItK7*|yJf=y|K7B5I2VSW(Dv;*azTw(e^{XzuZbY}HfV zMA2o47DiCtQ|F&++F(UA{M*0a{_W)86_2cM6x{g z*Y@XHLjfWfdnNmh=68Vdzft#3cw3{{LzF)I61XUJ4FF*up85N*Q6mpQivlsX$%fEFuHLGtzAXiCas4F zY=*6dm|6T?BVl_T;io@vyEcuaov>2vk`#mh3{6T(I$+L=BJrVKOFG0_B41ln=(v@M z9C1iVNnW%x)vYc|r3^^lkxY79zTXCM{~8gkwEtkR)(f};3|K4j1D_@9`p65HvJofk zp&*Z)^_#iKA&fmeC@UvR6A z<0XHrN3sD8Wq)a6M6NV=ui3PgB)INa9|uvrx8*sM8tl(q)#kG2m1>f9KUt+CuT`e! zy#sq1pEEjKY69S?@2bUO-Og8!l^0)KyCQ(WW;Anopx?1-*JbbX@V8I=Ym?WId1hwj zvyo=EJ+Hlh))b6S0W=Q}50=9b{dFcYG25x}7nV`iMY#hNk&LS9p($oM>WOW5A5+ap z;s|A=ZrW8#o_A5d)@79nLzg1(qA7{uC3#`^mwBd*v!<>hiksv`oWf97wH?m_A6Cyx zpvN#P*MooZ=l?&d-ZHGJt_v4dK^j2;32CHLx)G$i8<7U-Zjf$JDQW5MZt3pMO?PjQ zhBNVb&$+(uFTXZx%{As2ca2Q!Ai+^{HV%P!*<4&4ympD)1TF(OfJxxH?WFf%(yr7#VChcRJifNuvDfPVBeD>Qw_w6SbKW*13th+Vr)|C}Mw4D0v zfYsGE_xGNFkPP6m-x{AD_l46;)Z*G%@pCjI6`j>Z_HPHf=!4z(mY2x@4cV_w9oB&c4llaqU?nPwWEwssGz!F+p%x<3(@tæuFX2ZuMeft1lLojBrgrUXj_F95^Z0r< z@M0KCx@zmIHFi<-Au3&^^p|*gG zJZ4;7s4TM(S=amsu%kL>ZoF43ejdA05OBda`@gfg!V+Am1iGKB&6S|ldoxO?w65I9 zSPy<>9l%7qekhvxOV%rL6omDvN1`i?-{N4nRXt#iJ79J1^D1>(bVgzo?-%uok!Od) zYKrH@oN5P<2!3f&^FdNj_>+fcpwHnubeG%NRMe1qX9f2&qa~H~GaU<`RIW6KUK7Q+ zXOv{MBu-#Z6)Sr(=2e^0oVL|A_+qzfETz-fBb=M}b)NX>qoX6BS)qJ?=l%a6?~yua z&BAP%0eq$LU}q^T=S%p73JP&EzIC_d7-E!6#NZ6g!Vh{v@a_lY@PM0O)Wcym+Eb<@ z$>@tiB#wP%=Wv$s;bl*{qI7cIyDt473)ZbE+6*H{EGD47rz4eTp=y2rB~-}Wy@!pb zv1S4~x$Z#6i`go_a*><-CPi|w`bl2K3ms(9cHMMOU`qFk^4P%J8d^XmA*YRFT(~z8 zc$`B6xPBCrH!W^jRT&3en6w8W?K|-a;wPDv+e{2{k}^wV>cKrZq>xb6Kni8n_b7uK z1CHk47R^@721b8-9px{w3`o@C+2e-xxIo1k;L&DiiiNyk&t*4A_7KmW({v?^J+P;|v-=dU6+V)oLHr0#z=D6UX!o9cz+}Nz%opzH5LGp#g^E*cXDwabk#{D8zpmFK z-c6sa+&h1;-=b4CLpT!|Zd~zIJ7=p0KM9vQ*3{HguPfBZlpL3EFT2=)n=;L#DUscB zJ~9)V=zelDzI7iSprHjaiLBRGTX9=?+l;KZsu$tZOnqwK9ex}Jl3$Q zt$D$wdoYA_Vftu*4m)OEII8d~?;5L1yOWfjeVj#AJ-^q2D2+45k;Fu6T)L-10|01- z%o@B;5O9W&qdY~t!0_dL4}Qqw^N#~*1{}6S^>Vm5F(;?(tmf&+Tfxm zh5hzWHY>A``v7d9SYWwjqgy{U<>Q`XDPO7n++V>sBcnspV$5y20KqS^l_H`?#3w`E zR~_GpZ*GYZPBRnn7i`0KDh8EBK<7q-`f$=mndW`(b$bL|%#nGAgNJ84yx4pV%2(T+ zNRZv~^>)<4eucdW_A~6})ghPEjbJkD@-J;3%kEPubXqmx6LJE6)}FUXQ67IM(!7eA zo9|El*8DXds5tQ>enX!*K}P1LZ<{&B&0Zt6KRMe=xcM2;>`tD7zfDNfw_Ho1m{kvR z=!<`xz|FS$N9w^)b~hAK?udNSN_XuFzIhp(q@|%ry3H){To%wO0AH5or)teM=pD6U zCg={toE3{zfsiQKVO#>(BU;;P zEE2UeHL5MHvvO*3Dkl;Kx#ldqyy+bZ$p^j9$Gk7rrM^x6{P^+*_2!w%0;Ritma_h4=;oln&KIDgalKuD4A-{aTQaoXot=77KS;f0{5%MR;GORn zykLR|y{Me;uNmGFGzFWN)CWd+o*SqUIbG?cSy`Eti%F7QwWy&zzwm^d!{6|yBfS={ zw5qnG(`z!T;5T~HUHH;p5+m@rAo@x@VeHqgqTR1-U#IXS3xT~iT0%@@%oXXH^jauY zpI?q49>8#*dX-y3k6j25X{m+z_?8j4kj*qMOc5byc~b>3k{v)sUuL!Brdp&esHTRU zx}RR{HGSDERXMjPoyF*-BEfF8P-$y?MU)gR3zO!1n zgX#i^amw)M0t8^a*|YL=Y_&B4p8eFhcX!UMt%uWp(2gp9$W3cI+gEGuo-S&} z@4Kd04J|3ttHsTHopSG=Ivc6AUN~LCj_1F;cGh_)F^3NdOf92#x9O6Mj%EcS0;Ddu zn_D>bvJ-TqYy79#u;aoHVYW#|K<=N2#H0{(g%6^15e#CRv{`}xzwW?CqeZw8{ z*w#UCco@brKa|K6Jne5ME!jX_94Utsi8olS%7}~~u}&TC63VMkV;O$j-pRg0Rjm`C z*BmeZl1B5jsIjv__G96&;Cj5$e9;@3qB&E43%c30y1?rSW-G@C2FT4AT_4_#TyQJuUp412Gy3_7=`(~@Br}ve^ z-0{br$C^l8qT~4}PW>d&!#14?V&lpd9}!+Z!YF{8pK+UQqT?)W>UDR*sjmS?M=2f~ zWJH_5CE~wdKS_fX8WDkVeqq~%r51iU@t|w}*L=kIKIejt_Y29)8G~i#i+km<lK1$h`WlJUYXPCk zoOt6=6d8&TFGPAc5H9Em0xeW6);~ciinQ}yKvoGK7{-`U2|YrRE`7*m;6QPW{tmV+Lz0qxp`bL%Yu z_Gg>d9E(>{!@N*7(6hC9+^rL>cMv`FvIP-1?QCmmY2i}GpWe@&Tl=ff#kI?mWal|^ zN}AotogTxnD24K=`W&yr^G|)H50yFrhL(#P(w-Vy#aHzfsUG}t>EAQeEr{bsl!9U7 z*0aJX2j7?)m1vaql^--fXe0gP^#IcNq$=njcXB#5TxxJE(yab@sKax@hgN)%>4oz- zP9irhpXogi*qTz6xoy&oUdn z`~Ief9Ui{Bo5B=TQ{)9L!YOaO<`V+aQ9NbCM+9+xEu_Ej7EJR)zedOO)5X(GeZ}lu zF}M?DvxnMXsrP9`F-kw|wN+U1aMuxM{GNPPyQNSPJ~}hglOvO)-t30;j>AenOIwtd zElb%(gd*v-e%rM!wa4rBK&o0(Pi*E@q-N8vOLG1qf3@I${loh^WP5-JpZtMAI|<}? zBBpM+7+fdF@hfadfE>2b>9)HXa<%$!d*qxLEvbY@joaa3h==w`1gH2S1}SqQ&Q=6f zoU~NcVQnP&d?E*q5(QYxIQlaR>KRJ**RBcm(0jhjZd7ss)hQ^hAgls3ob}qN+U#N! z(G;6m;eW<6an%+3sSGEDO=oK~G^P#MJ)*v5_X8)M4o_{R+vZmwfs*p}_D=4&NJ*F6 z{Uj3*XxDG6UT5?$Jq(`aM>CKddVt6;iT_nh2kiO0M$f%Y^T#{i23x23mBm5 zqd~QZ5D6k|Kdgle$EtnivfIQ`TfT};d+0PbGvmt1uh;NTm(Z%sVukzLtBZA;21~J| zV}4q(msW1AHk|IIxFpUjy{DY8sg(|J+t@<-Y5u6C^O=o$Fdi&o!9;dkLHu z+tgalu)MAZbR#bp;!bG(b66lgt`+IFzJ(C2f=glmBTArcHHc^!yYXD z+92-*5Pu7z%f9ZNffpK8yLPAK(dxsT8V4Tx!Li(EQh7 zfyhZ9GanD^A#@L4kK{=ux?8ygWYX#UOp6mB7H^kzhk)A5SW9dFGe~CngNCk1{K05| zqC!ygd1fa0Z06QqDwit$E@n#9Y@=x>RYUP8_m>7-Z}a{LGj{$!l}vi3h?RKTE*v+- z^CmkO>9>Ib+q_)f%SlKf{jxRRo`xyl-w$=%oP9&F#3;*{9{tIOTKcAb2N2ApWh7#ZVg*T{l|E87z?9aU% zK#n^MK;9o{9xE`dEe|*Qet&Bs4U!U*L}wffragszx#6$-{8Z4WEJ<2??N;@bvS6ep zV=vi_DGwjZ@O1bCf=BykR$Y*f^%2=y8v|o~;~^YpjJ*$qom5kv(iQHDKBfyfcUY9 zo=yOT0)KZA?fPd4Gs2Ep3Dw0#vYt2*El%nr3-(WdSNcAZIR{wuaw(X#p%dsB3p4hXvU zdoy4p*#flDtV18Ub<^QD7_?tA%gg+<@k6g+MZZk>38#NvERwN~_@P?|6H5jPiVG)q|E@3sWYUVfH^2kFNj%l;bV~y{fHYF zqZ7!#6aV>XFie7!ag)4rieAjHX-XI$^M-OSa}fKC_3b+lcp{k{x?Rr&YjV>9QN|;5 zWs2_eZ#kY=o)(m{XL)MvdLjwd?`z2K!hZhC67}~cn=aDmNP?Uhd;N`0v)j#%KdVf; z50COZFwpim6(IvE1fbkGn@AfSAFrs(FV~>5q>wBxMHKZ^mrS5mSvr?}?@pR_JD?h1 z5WYQLA#DhA;k83$qx||NXS!FI!(Ra(R=A;0x?&H5?zG}K!mTYFA#5h`bOWeVx2Q0Y zvLIpZbj;6Gqa$oKMjmFOIF79zH{i^PN=_Bv& zl1>3coe{GJ4*YsAS(M>1@DD9OuGxWSUfZQD0L}BV;h1lEe!iiuIkS1JhOYh3r6K=BzfXky4{OH}4Sz@0HVHUJS55UjHz-c^S(b%WK; zlf5}5fF;??F^E*#AODMl0l)d|qyr78m0Y*xOk6J;m%E-?AMKfSwo)$7d#vM@wHm(5 zq#X9wkF;!VH|V0~9($AsViTJ_AB3b^1`j?{ZBSz(i%TgMtDN#O2BDXt zdbC;s(Uv@a8q^bFa$!HfbviiVvfG8dONhUbK$(XB?^%EQU%!@AVY@E+sbTQPoUcuk%#WPDe&XS4sw1Ypw!d2^j8a~%79Mhw~0_cHn4IVpt9&@a9# zL#4!hEElpAfkY5L0(FZueY+kMl`2K#iTrbgbfmPHxC67~(SE(ul_2j23`X8d{DoR; zqW}L-uhhGT13nget=0zz};YK%lQG`1YlMMVmmsY*!XVbg<<9G9Z7 zXkMCPsB7wCbd%&|@|S!tL+#APp*Isz;roF`8=a|6_j6!NUQ!`n^~CQ>1Lj#f6GEeA zMOSuV2a=~JAYfQSlw^5-^rX4?HXb$5Qh$@ZV*JPI3JJXc`MPUkVnoJM1z6e-N6zIS zl%b^Yh#LfD^ymcabKb{hy*$pl({AElq#+2B$)M=LaWTuhq z+x|RKG0pA`27e7KNi&fo5reo=%7!44bR-1d-=9Y?u!VaDDpb z?7iPc8sw-09iR|NR19cmKvmIrX`<%AQCn=k|H-nrxW8B#$4=*ODo^}~_bReWD#z1B zDnR`YP!$)?s|59sd!FYBdgZ!3s7&B7kt2K<(5<^dwZ?f^ffqP0q*lt^$?5LS1hOAt zj{?TOdHeSV5La8+C+j@i|14|Si^p<>m`Lr?)MDc}dF6DSZ~ zthWh$VfV|t4?gX*Q1-_qF_tChk55>#>>-JjRp?DP+jgMv+rI{ZfttG=@9^G5LHUkD zl=&g+YBU!6duvY#9iV6cO$C>>%W5__6KOrS#Zp(4|7&9q88dTpgF0UEgaZR?kTgX{ zwslJkqxUr}D2rX%PIE?Ro)@&bt`*Ih>v@rpe?7bh;U@`KQL!~J`0YC5e5sW|*kSD{Wtdt$I9njLs2Anh_#?mnz^tFqF&Ly{S0@r;} zPnYQx<$wMeFpGo~Yt_CeJLbQ&nE@lm9SqtA{EY6%0_4GI*!zBeruCwt7Q$>joSaZ> zSqwe9_6;!~HC{65%8&?dpu&@)YZCUzDEpk`Ct(kt1%gYFNirgZ=m*`H&h+xBrk0fV z!s9-MXpo*WK%r!in9IPQ=PC&VC>g%ka3j@-mWA~Tn+t)1udfSmD z?$9p%D`1B5|2w^#Ytv^zyQW7Q3G58v4fU`wQ{KU%$sdpwS+wSf{8n&~q_!qnb_!#97YdY9;2~aUtQT z81$#f$fcKr<h2^Tt-*21YjY*E3W6akCJPl8km|+nc6+kJTrCIzMwoQ7V{4-JD zLykvzU6W$*htZjl*Fi*WpY8v4J1O4vyn}QvT`uu0TkEuQ{uhkl@BbJF+(a_xYyZH5K@JC2;bUF^y0FM7v!wov zW4RHWi~+RF!BCv&kR)cjAfEXhW9+p%o2c|ly>H_;n@V)Wd!9iTY=#?^%zq0%tmd9( zcjGN(DqkvdifgOf*6% zSN1e1De)}_2S?v5ypaU54?Y&#FO_s86-+{IJboJga7S$P((}$=`9A{;v>X{#@R{%e zLx~X(VZ0}I2t$fYr&X|Jg@PN>mpAMp0;9W)J#b5rvO8-CfZ+JrBNDK4iqt(07}Eu& zLwX6?PPRDHgxIPD&O=fIb=%ACpcV82toc1E$C3jEZTPpsA z&EI+x=qMSQU2j{^2~dd*h+u#2ycIZk2okuR8{y~D6YBW@I0V!h%T;*2jeI;TIZ|#3 z(;TTc#VV6x2%23v(49_VTfNFW_sSxw5t_Fqrap>#F=1G5CQ*;OVbL;i)#9r5UeFwU zoTPbW9t@}1F1@s;ROBLqlR`1L4fUt_t(pJEzm3)BLK7?RFd`y?Q6}v}N^YtL(l^MW z8*LJY<&%c)KQZn!d6Uq8eK5)DW9P{z6J?qMbL+!JDHl-1Yd?1E@9yobEkcKN9z)2} zZiXiNl#HvZss_QBLlG^x?^fWBAA}yy(2)n;Rz;(zs25$fit-KJemQC!`Myx!RhcxS z9&a_03QoeZqo*$$J7ETY*PHUuFvd^!mt$<{OnpbdbeK|-MiCIRO1b(6+L+{Ss~3w+*Q+b;OlIH)cC9YziN}Vb9A%?+HRl$D_NKl$5zO2=v4s(EGjN8p0maGWn!J6B-t-)ZTK~g*R^BD&$p$V{xJzF9S2Led&7#v|5P-AHbI(} zr8-pA?^KvpIgcu~YT1!Ww9x*&vE<*17hm&|R@bA0;*6s0ESTp|0Q6+RAcYPG8nkxe zU)1#1+z>Q&?69s)@VSwnzz}+z2zq%!>3MGtXn3vvy#XEZf3hmD`@sqX82)P%RlitG#Gx;CsW3&G|Qvx;6)y_5RnX_U85+dGC6=)#;+onY7%a`eH` z-V>91kCS>l0VO~Prc3|zKt-N1jZ118_K9Yxs`<|0p=VxxJ$2Kr8pkTl*y`-kwcB_I<3 zW*cgD%s%5vf5DI0nj|Q`yKz;+O6l{f)A?HLWS!{oSGD(x&-~@! zrX8%{vu{`dfuSzGSY3@th>BJH6W#7FCu!~XJbi_TEeow|YKu6XND_sp1Bk9f)kTB` za1O=fkP>%-W}}RzhR#ntY1hI;FR^dSvLe=J6|U`lgwli2eSxIt_*TT9zgF=yY-wo; z4cMxvAeVE_X`T|<`0N(y-H`;I|Hf^}ibB7^~emGB)W6&Bt0i?x9?`bm@Zr7t(m zW|?an)$`;N(cM&4zS3dNRt_0R2Nm&9WGt!2EiQYlFz6duU@1*f67Djg{5L8mK{0dDVo^D?#4?4-2jon|*x=+Zijku1&oX^-+wV$3*6}iKtKZ9FawiUK znwe7ll+3l|i~l<1ANe*cpreDygCcF@(&6~vDZ*Adku?m>>x8dJtJY_EIrSfjA^X1? zQzoTRX^i@evFYT67``j)?NKG;zlfQG!+6`VF6<@m!|ECSx#eYB2Qe{sKO+s0gJvX# zL5CZLM`n>hPaG;vY-Z_?THd8I(-l`$v=fu2b7?rW4#A?ZU_BYqls8w(#=xuOkuMz% znele4#zqD=QvP}!9Lr%vw*!VTvqoqa>6|IITCp->hfNOpn#at=vb+a)7DSMZzie;#nl;i_-S3fbk9g^ z*yjsQPUVnf&$?A?4x6sV(lsqetJBlH_XyLsL9^;T6w%u32U&E0$(IiGyo99XOgj}x z`$$F31z9hi@ZeMWz0Emmhk7(IeK9rlr(bZkS?FQh=+M1lxa6%)1hULs>n7h@?|Z*f zFUcoG_cOpK8vTL5fc7eO0`9DW*`wl?1pcUtFDmI6ns`oH^6M(?m+X#61ep-Q?)X;rbiP$RnEnA zctG5Fjd75=f{`XZ9iGw86M}xKX-j3?;KQx~uu<~$N{;n;; zDGH$C8EW@4VN&vCTEZ%KQTv!zz11UkV7O2tOX#)o;WJ29T2Z4tk1sgD!QYyTWjtxX zU|eZPYU$r2@^)=XvwHf{w_u2_(1A!7`xz%7ySPC7(sd^#e;ZKs+zuK<^4}x@_f1j` z+Y?U8PV(CeeeL#nDv@w3H`43kjiO#6Bc8|*!{8_)(H@lQP{~xkXAo$0)C8$Xh}VZfvb`XrC>Z#Z#CYw&?A8}+khu|u0a;7 zkhLx&;Oo9j^{Y5oExdItKbI|@bU*OeQY&~XU)aFP#!=Bj*a+QZ^iBvObPMhZ!;ZSt ziaQZ_;wK)xyEhsaQIa;UB~darLQNupd5c)y z#Q;_n2QJ4C9cEjAcaqr`YW_V!3 zx<~``e|WGEjUA&F%^q|ZyyOF^MK?EaI|qwTX!UHF z7ulzdPp4T2P;XZoXwO?B7Bb8i%)6|3b^9fafLdO^S0%p#QH?6?-XYV8a9=nd!X9X< z3~}=U&QTf<=6*!;z!&CP5uPy2@hkIrbfQws*C-wDS6B|j6o~S}(!WpLhL8O*zU}<# z738EPdaL9!igtZNKMNzB33Th?p!xE_;doZI-BqP5FK!!|AaZuSDSO) zCRfgx95=h(_2oXrHC&yr&8P#GT#Vmw^zM45s-^~M=HkQ?f)LB}2N|>F7<^TN=o#&Q zf@w&~$cSRd$z}U-`CM`C-4)D?IwQB&uNhiEETt-K z9Jtkm@q}|t2y}LSuCF}+`4onzcFS&nzBc^nkU^dTDIVWUY`!FdoqkdKGSrG=m)&jy}UY6t(MN9^e3qCj}e(u-3Ao<+cQty>N+K zj@`Kq&nK>S#00v5H{Z4!h|z@Bj=1bCrIA8?f zS9~XW+z~sN9qR&!eC1ZORNS4@URAz(O%3bF@aCDno`XJDSzLUbzE zh$-=bA@kNAAM6ZyML_=y#J8PzwhAKHwh+OhCaGF^mDM*>-_4D94|gs(trt}e8%OaO z+szrp+x8GR|2teFZ;o?ILd50)oQ6cC8x1MQ0+5lG(V zkWJ-PVXtLnwEAihEc=Qknie<+E`N(6NZ`EuS>Tp&YwG<4UlGr!QOuV{lT6eLY&=0E zMp>WA4CVa{793`H2?f8i6@H&MC_uITXROYjyJYBjIC>>rmeGS=qGWd8rrlE{f+QCR zm@VGQsOGQAFSh+bbR(C8pIfR~JPrX7IiVmf?mGy12Fl78AdrOr2^PWuF=p)$;eEXV z!N?+d9Gg!7frG}8T%x5kZ+5uf1f6tzx1;~A*-o4s@`M>ht4CZFzI%_PS(%QC=)n$?BfU`aw zghy)?uehsJjbxs-uA1SVGVw1(}Y4&#Gn=VJ-%lwld&Tasoz z9@mqbsFsY<4y_h9mf?+;S3L0sbJYGw=>0vCMrF)gyaI+crvBSAPR!QbR*Mg-_D?99 zxXaXOqW$n{Hpr)13uD}xNV|K#4Un8$49i?+)V^|K#QpIeVxZV9by5%r1sT(=xMie%#Kfw$Q8&Z?SxL0_WbV z?khe2A#jAL^TM-VC4N+Lg2|P=k;nyy<&qzP1eT}9GTnY6uyjPrW!C-CZb2sa2rGtL zZDL|c=JBJzu0i1H7aZgbXO~-t>|^g)c3h1_{`#^-28PN1U~FJ^6Ku^$QN{M@(^=ApzJF(|M}}r}u7a8Kx>DrDwcopg{m2f?9`tgzabZ z0CLOm1lH@OgwLDy^*gM3KH3aY6wyEiWfiolcp|6f*`5Ftauk@DX|yXV7Y*)c&GlPC#-_5Em&jX6#nT|68IUR_O^^z2cQ9L? zF#7^t`)3>R?=Kp&%!9Z6UOBZzTSqulACwE^3ljUL#Jjp?e7oab3GoaRY%-P|l;7?` zs(hPhDrb^4q|=xaw&Ey&HK)iF_V}8gEE_a!ZnMjCeceEx*64-dwD0iBd&y{!@5+?D zScmIs<=A@JyZeZx*1~;96u&1uw=pO+mGGddV={lD*QjzQ&v44HFFces`?*o4%H5|z zhLWt{7I@;J)+<>#ucp;;BrJDNVUSdr5y)!?Dwth8iFSEY2qx1Z0=H}jjJ3H4U zZuUKWnNTzk9>+Fl_G~2uJ^Um=pjf{n6bt42z;HW|jn@r2v$t9Lq#ARtn)cY&f~+ka zdvQ$U$gBg~+JG?Kn(pJHB}>ZB!VbvW{A&vZc-^9InzcUkK_o&<3GX_+`G+fPE! zIh4r5$wtI=L{;7{=2R7PX|5^?6gI(?895B6%kwhe)SfQU7^tyK0sY6f5+>z%4mP$$ zb`UTE7KTuR*h6?CkMBTX#gL#MLDnaC;~$@XvC|iaUN(viC$wDV`6tu4uKi=aQ1%vR zh*W;0XN@~qs|eK%8uvvt|g*Cs6i9V6b9N$eIa`j1PUwZ{GY>_u8V_KeLR(P0OFRq(hU@W&!z zIDbM2K@vm^kZ0GVk|&8I|MSz|hwGG#9y$M$f0ew~x7Zp)4}?$g4%~i3H=L0HqrSxG zv;H7_K6;zp(51fx?2i+$oORx^$~~SQ^w-Fgird7sebOJBi!1-JTh`4{8idR=U8^dZqP6-K4K5^>`+h@a3XDSe-{@Uz8_i*tBO*Dcjuz<+sNpU*}6pmUozpUCLlGqjT2nBbaVeK(mFE^cb zuoxc@f-ontDBi)^mP=1|M}eX3(g%hxY{sqhf9%{5E!D2i_!? z2u3}uGRG!{y))%5WS3Ga+H84O+OhB?f?N!G3D207UrfLEf~6<3*z|zm8!@XZGcY(& ztKl%9PE=Og1R+z8YQV>!^_Vy4EOy z|F}yBk7JKd&xiY8VcSL)?xoT#04O2W0j~A%@FL`;y`^+?Kd)*{1x-|95o!lotbu+M zHBnLa$5q;6?c2!xBjcXw;=8|4>&*=`kEq7hv&d7gB+#U6{!l!LE%k_qmg7$tVD!cg zi{ej|1G40`J@b<50}^Dk`keauzN@UeZ}RUtT!v8d8VG?_zx`Q+5YjqstRe`o-TS~? zW90umfjQreK@}aALak6WQ?oFE*%b20yv#BTY*=Ja3qC88W>5u`e$vPf36nvjapv?) z+fEn+vLXwXu8Is(M46a9LL(bg)K|cR)wRcFuHNcJ0K%gcUZP*Rr#fpe#A_9@-knAY z*qrrIW>%G?g*O2Jz2}zxw)TnOW+WR9LX6GOEMa41$08&+z2MjJW2jCPqyF}^@%2`w z)o_ZBqim##J(BkZCsAwR8O8t*r%B{0c9)sWT^Jf>W6{XF_{ddj8X0Eclas<5Dw-*p z!S|Hg(uHUdimJa-?Vpqevy4^iy%SjQ10tta7wtzvZtF(p7X>{8PSI#z8x8#;<2ijP z+8W7-jiFWU&o%u?o<7<-Mf~B<#Ay|E1_LUpA|7st*T?xWTl2k(x7oPt%jp&etcBU!qJ|Vif6%a)5z^Tl0f4= z3uUtNSZZu(bMJA>qsHI4ZJQc;Z!c>`M+})er7x}bf7hqfbdCNdb0yoI^=W%|P+px= z3fTUAEk<}fR8mrMswnyO!VOaZ!?BzE&L?`D+D1VcuZhIl$f7OF{+6w$La#c1WfE8$`CD-k1BVRpq| z{fhZXe3Czt@nJQU4+J9q0NJV_!Ty!Dei{7KJEHv-&1^_mExD+_#_FC7D= z2Zz~iQf>1KXum@qb!J(a{`hOlV&mqFg(zlb`#ZF!=U5QB?xK2~#ExXt&~Keb%Nfoe za8c#wP3^tMKt$mQZSWCqCN(hN^QqBeLiJNt{uWWeT}CPr5x6CadzdM2x+zDJW&k$) zfarMAAH-=RAB+z;;oxpw_kTnTQ53=!d3@fG{Cfvo>)Eq!&m@EemEUxXVYAk$jmeQx zv!cK&A?y7XB0}OCN0ueGVV;B=*ue00AQ`Hw(LTRZR$koQm&`u*e17p!0c||rBmL?@ zY598Dv&C_4jI!xI+F2RtPv>}N^}H!GSgKH&CqBDgtxhnd1rc*7*dZ75WeT|dr+JCDbB;<$~dVZ z9iCY2-Dmya)kBc^j_peoN||*ujgZZsbu-4PAo`k559g;exddl~g%E~ONbinv#tY9@ zH-WF}^Ek8Zf(S~`4zL%BCL8*yvT&}>mMnXGluGJXYiZqbJiGP04RoVVshJ6(OeQS9 z>uoYFO9HDA^V1fZ<w8d{uiOL#Yn+e6q@w`)IJu_5Q~o}Xm8miFR_LolB%*#zn)U`k6H8mjg1Vf5I7 zCSOKE;jHQ&ZW?AhqCdt&ITgf4%Hf*gm43NkNGib{ zO_4OT&Kb8AGiCmpGb4M}F6;PqggbKLIEVyhiUt{bum{Qubdi;{@dxxi#PP)sazY(a44@|@L#4tpi3h~&QYabO5# zPY(CZ^J~~AW?0E-f0HPl{KUrnk@;&7Ex--I9!itB@oXy0^`0n`Rp0BFK*@4Pp>=La zwh|HplMOgE{j7wv(6i=X{1h>6YUFbX7W`VGz+H675ON`20bv>m98p`m(A9mIpF6Gy zJ_J9MXg>#=&4JArj&}=2V)rgCJ0oSmTps z^7vxj>4EzLY_k?p*1W(DBmp>L#%XH!r686GI$rrUmcsKKd7AfMuX>=vx_vclQnE!BpWLS>hCei2yZ|is%RTE@})fNm*h zi`4WY1|^fdHndTl^kL)#JG9%ZxV)U&1Ck3eRjwIcy{b9f`KAKtLWnT+8~4eJXw&vv z=0|ybA8uNS*AlR0Ap*nq>6=#iR@F}jJ5Cy6OT;~^Z+gPHT39-?lN-(x73ixr>BhKl ziath2_yfW~o~Uv7QH(i-p6w7P(R8geYJjm7|C?5;7p*~e_-21$$r?-A119$8^H%`x zpLGW@h2E~~{j{Y`PfHehawn+2Uf{u!H0I6>L6w14js(PLU!N@-vR2DCun= zb(ufc;#m8is*4hnU#~wbF)^VWo)G#!zes$y`Q~fpDDj@@OF{HQYHCaFuZi68qxh;C zv{)H*0r}D>F-H!FK1Nzu!blxVpsVnYCXOEX-e){pWyTU~=UVhlH_pTRfh>yuW)5^R zA}^T@^`&ULqyuNt+^wt`=LFaiyHqefV6LdY4MZy7yZj^*%2z*67Xyl)%$D+mj*y9U z*!&DT={GD*q@{QeG{L=BZv#6+OU&@##+jI8^j?TgvM(%1EeT^hPP!Z$#h-b5oqQ^o zVg~koMzEo%)^-!VbkPRzlBss<5owJ^ko&h@McLW0n$>VVQAWZB?WSl@Z9n3ZQ$JDh zO2SQ&9Kq)}=*J(X;A0Wtbr=%Znim2H8N&%%2I3*h9s&Gw8Om^q5?Mk4&t+K0Iw7xW zJywx#pz&6#Q)-{LfUa^gjuFxxB;a9bbD^TRfDyu3++1cW&S20_S zWwIz7mZIrC-Sx$vRrs$j3fQ&_gHSjZ5M%p`*+{ao?&jTZ4Q;m927i#va2-(?=^s!f z^M}!v?0T}Q1pW-AJ*ugeLi~?!e{_`HM6uM?39@RNhqx%`)k_nj3=N#2Vn8nQ8;yn( zg6H>RMbs4q1uvQqrH0m`m_oi zCosf;)&WhGdSl@=Gx4(~;?eilq9(GeoZ1o5h5v`9vy7^;YrFQXNJ@uvNH?2qknR*w zO1eS1OS(b2K^jE5J2ukYA>G|A@GYKqeE;~h2jhx$oiXP;$m5~J#SnXE$xzzuF3MA{ zw`zPLd@j~C<8mjL6;HcKP86zqEQ?YEuenoHiBkWQnB6^8<~g6i*89$0?BG-&aCdv1Giu z$jLhhsWW#hIQ2_Oq941+I&K92b9Kq3{FvSdsUHU1=%%kDjfiwFi1UEslDubKgWfEzb%ER$#`q<#Tu$>-xjtGW$_rKoaup-;0=w&4cC zcf@KjNb;|W+-LcL?enOX#tWobHQWKijE)!dhucZe{Nxg|D~a$Y{jlX(yjH}?*XD3GDi3MqUJ zBBh#MK5PjKp64<&cC$JzcEIoPBJNidI1@*PnrU+VLmO9n%Z0IVx}juxS)@23yd~ZA zxLH^bIWXF^omv7Ce;LHY{J~YVPzmQpCg+UALlxo7ZEQDBz0WgA{ZfF_A1|RDz`1Rg zd7wf-zb3JiPBtZTDS~bmsPMDB&N>Ywn!LbrkfC}8v*G|NLzl!5gVZ}q_;GG7`EnaO zsA-D??w-pXW|A<4RJu$0Pj0T8KfBvS{0&WFRIYm=$5&RKItZC-t;r9P=8lzN%X z%#v_0MnLtw?kG%tK02wDvHZa3z=Nl`D7*`kB_0j$A9Bc?U!W+S6j7yk z6*3MP3K3%=-!F)0-XdpX=0cCb|D}%27bW(BN|?qF$Rt%RpGAP${xa9v=~w8W7*&z zF4TrDetV#orQ06O8imEx?ug`G?km%2<^ffy&t0g}^63ByY5Q8#yn_j8(y&R_f%1TTS=X+zObnp3a5cz5|-^pq&1fRJm$;?w+SRr;oHYT7B(h^*R18g&wEFE>Hp zH+U)mnxvNwdRuzXm?gYlWGHlVIjMvZ^ge0>U;{>l7XM~F(U`ph7ynDGvmjyJ$r`Bf zS|CleJSI;<4n?z;l}ZVT|Lq$fUOwaE*)SL3siW?{mNWZ`)h(o&XdUy8E?(8K#s$K| z5ppn-Ta?ZNg)>J|7PW!s-%_(M2=B|HT>QK=#M|yclUfvyyf13QtStWoEs>1ogB|#x zcEHTEClFPvl)mr)rzU_J@nzo(HAU60(_SH(E7w0yAMZ_ecg^Jy@?>|(?0mIDI6ke+ zXwP@{5nfLl78fjq7OM9FdWUoW=L38^GG(=1;5cr3_*V9KT6-Yuc@(U4H)JYw@#pb+ z@#KDHhU?cfJ^5*WUhJ13kzw{?0%fUH59Ul#gAnwO77O3ikoc$m$ctGS;z56z=`S|H zP$4sZ)Z%LBitInq|1zERsLbE|K;pf5n5jr3BR(I1f+PtIXF#aU_cyk9`V3v2sydug zp0BaORP+N21?D8vrKVbtYk?WG770>$HZk;zg!C4#`BrY|lH^(rbWTL+B=S|)fC>4} z%k$5}0Xlqx!@rerM}j3^o~OLFjb}akESQXnX9Po#(D7?KJ{grl*wjt(p!XG;XaRV~ zSmvSy>OIMIpyeyba1I&}vzo7g)ek`6)NaV;2-POM$I$i1fcvRRhpu8rxrN}b`iQU* zl{&UIj)G$V9aH<$%B0iR=>1)vcdo$K7!S0V{7u|t#c%L9nsijO6)BKt?la91tR^Yd zkcuxurkoCf%opV~DoAgZ9cW~FbB;L^{1rIPZh#Ds|G$QtR1m~%Q$dpVr+A~BwP~rulU+_B-%b_ZyQKtd96eXRT;6R9)6qWD$ws~^jAfR zrXQxQ>kYX!9pu1J6lHj;5H3!ho$FAgpg_ z0!fO+q_7NYlF?(Lj=;^is^=(0imZy64OWV06k;xtz~k-4P>NudXm&+?QY$#~Cv4N- zkb*G37cJJ^b$$DAev%GI%E`EXDEHhdkz&$mI+Vc=0uiwC&~7$)wmr&5`7kxM&<#qF zN$)bc7UJVglMG1@accGh-m6MqgL{FHsCEtwFd8Mix?VyMN+&u|CyCUzZ%-YYg5} zG~Lg>=G`NMB9~uOV~Ta5``O^5LEirpLa-sBQgfHY1+!aAcqm&;LgtXzySQO_N8dW z61r&|^|EXCx_J<9`%(CH){~aP+>n4zx5fa!>0-0_jVihS?kTRUsJWpQSDm$fs$WG6 z$o6Db?~=!aYuk2Br7k;oKi1}!Ns1ou$*8DCnFhg;@iThtS#_U0Qm>4j)ZK4c&@9A! zpowt(0{2TFhgDSpFZ2hdOt3tc99Nd%W7E~;)fGn28jX_B-R51}j?Y+4X{qWyw9Gh7 zTG#%sd9MMghQR${u7}6o)92jzMo_dqy}j1|cgs9A0`E-HV0%3HAKO?4f#hk1L9;(X z4n`Hxv(FW2NeM=y&$tcVf~r2a>{AC$1@akPMJgG$zNBtlcq-e8AqeS_Im37{2b}*L zmYlg+8JE1J@RGYC%8d!e=c+J{8Ic3V$wDMoa5dQ?$1*jtk7iU9 z$k*q=FqMOQH7%Rc+4<@o{(g@X?`L~?w6E{0pdeXLR|<@Z^#rT7l9H>%hhWfQKqdbr zQ#aFK$$&JEqa$MZ{nVi@*thdGD_(#U;R${J#4%a*6%o41I60v|4iJIV^71Qw9O<6t z{T?3k|Nq|Pc$unRq0nyb#Ju8_)YkW^+vQB?Pz zTITtb0x}~i?YHQ!mt5Xg?~G(O7ivY{lAkd6GJDET;*GF!5Qr3Rrx7h&CH16H$IKx3 zwU~z`W6k{3;B5HV1rag7<5XP_ewCQg!G=Qb^mzwXvXWao`nMfT5M;f=oDR0s&Hp;0 zpW#Y?e>jwJcc{Xyay0(TkU6$=S9KY9;!M0)CRXIl8NFv{w0s z8;R4bm~6hakpN3o=^2O=2XYO*gf8dwhH$F*4?*s_sQ&*^QK@g3ifW1SL}3LhF4jrV zgMw->X1GlMB5^ogE?;pHa*X1CTCgQY^4Qe^OEcJkh7sj^iG%kFsIhp;-gebMP#6fb z#kHrTtxMy%yuI)D3VAmHAnfc9?#;F8v(DJ%%gZ&}c24z9ku=;|1EF&2FRbnCLlRQl#2@_0M&~DuOgYwJFyG?|Yb3 zyePtX3bxE5S5oo443 zhxkjt2G^r;s+j@H8i@T}6Fl)^Da>#tFl~KgENeJKYC9WVYyi8_hjL&TZZ1^H`UZS9 z6z74SY8__PD*Ow&Z~Q*cFEND)lyns}qo||?njI2K%ENOKa3KX1GvSyy?q7AP2I=P! zS=s*T+SMaObjmU4F+2P;?nTS%N5fAJuZ{qB8vyuR2*v8bv+ z$ZFcaUC^iIa{7;5N!7^%*+T!g&r97@$4^Ir7nVlpF4cvN&3**o?%{&bngbvN1~z(!~Ym) zeq{Y*luAT=jl7gGLHrC+=k-U;lq#OfRf1?EaK-{4BO%)Xxr{^(x#0fW{Hebs5VCma zpN|{&l1ADKKl#OFiZmT5LaPVf^n}oT_chi`)ytBN8I~x>&6H}@6qDuchy0nRRWD@k z(Og87546XQw*KfU7YHv_P32grr_=w+c48FsE9CttqWSi#eD40uzKahUNHTRu z`P2TmWdr1a&SCD2ifziP);1o5?I4Ea=2|Wnd?{mHcRPb`g`anxZ6B{@9j@n1FCuL` z{Q-QvxG??vV6pA#it40sGuB2Sjqj@4kx!vk6Lyi@&}`EQt*sE!^`1(}a8%=8?8@^C$@?0q@3L4M93 zC&3Tn^Yi_H`Uf7BJXIOSK{zr5QHxsoMHeg6jh;wG-L`aL!DkxPevTK7XE2E~EkHQ9 zW(Gr$e2m@@ z=W1K+)~gxA<>@7qkE0D}J0OfYTz~4&Dql$)QkL(5SZ_6P3z?7T^X$8RL(Z5+lXUm- zlrgrqbGA%!b2jtP-;$vpA>Z??2Iy#z8vA^PI) zh$b7$DD6O#&Zp`Z7nO>Wcy*)CAvxu(si}|Gn}AOi06w&!cI67C5jVBp6il6#BdfgNv7#N5_Fljhl93l6g@W|^hBinJ| zd3uE>GYZwHvN{PA80DBV~$da7@0 zlNt|>b!`v90ows{1DFOtx~bGq=Fv@c&N( zRaLJ`4Z8M3=vI<0YDa$3*MS!cVmM1%-#^%k#~z^41vqEg zW`PT;A_($w7lM|Y87jLE%p!OO(xKS;lmRMV!0bRK6?H(j{ZI|&~SZBspO%H&*pkBf%`fr+eI=%2Cw+HLU@36 zoT6!8o+`-F!YRhCwU{neFL~h18J8cNn0%Al>B|WujIM1;HcF#;qVJ#ctQWHsZm-Ix zBxFC*vzhZrM#GUUe$D&K4w~Y-@-VR37Dq1K^jGrQCnJ=etBZ^c1BO15mqf;RwU;8g z<;dE`a6CtXGOl>;OaS2}m91{0`~3(?1R-~n-A2zV+v!iAFZN5yPdA#6*Js=BIa%6n zG362&w}3(XXKQW-m>z=Ew$6Z1tlhoiD2IE3r!W7}6LG!cBwzjjWB0unq9Q7>sgk`l z8tExQl{20lk%QqhZiE2SE5pW7BL~l`^?H&dYSX-X6P*DWR+P&X`+nh93~R`B|HN0G zRF6u_9aN#qY&5&hyPZmh9mVUF=MTUnXwy;|?_@cvLXXzU5;sJ=>Gsr2wCKGNSeTVl z-X5K3@K%-%#Q1_+hy9WSz3g55@^ZhEB6Z*ZX|p6rI?ni{ZQIb7XSqJh>$+Un`SB`T z*m+6nIGxLQ0i)l@Pjl%H#%qeWF#oiYPjMhVdG8$(!fS=z3VEX<HlZ=CS+9hEG=J7_Pf zhq285-t>##(4L=N5gx1eKwD~di5oU4zD9`wk=WA~9v*Jb7G{_WX(4uC4GM!@prJq& z*MIYnDSU0}vNBw?HJBpchD6$O?yv2#~2`d3mx5i%1$v&8LbO0y+& z)Da1cMo#%ks_986sfhRF+i*RGku%AQUTzWhnoI_vq&JM337r)y`9sEZIw^sl%b+sE zI8BY=6Hr|h>f_<|D<2a~bKPGl2TIe)P-5P;4PGBb+n;vQfa<@g_0irOv{95#mw&Uq zR2smd313100_8o}*AUk)T|15N9sGWZ{_3)%RG^TRXl7%n6+gO-V2n4;gq*=m>nNo& z5Hc4yRnoi?4WQ}^Hv*f!yj$00RZvyXa=VPG=cOU9c06d8%llzYXraVMicK5x{ngCACAPMWW^q^Y$)3D~Baj{;0j zzLNpA4Q?YS)~_{xoS^rBTMm$%}of!G=wTa)gYPL zyVfs;R6+kzTzs>M`O|HIU(D`xq@9trE?uCg1Jl0`n9?#6Y`e>o!<;94accB|ClBK? zW8Ib3U=&a)QJUwt#J6S7o2_h`P?8@CW^GCU6RAWOs8z0Nl>#6)i^;-1uK*c)ZjmL0 zI@NV>{XqAbkKr>@Az=4_q9zv10;O6WmT(7Iyw}2`9}ldbn|^`h@LdBrRup%JiCkd? zM{fC#7rEpPO2no4Z;^DcCDZ~jSPg?9SF=IXt#1j4=Jj!Ma9snup=Bak+yU8B+6;(f zhO!dS3wk7-X|)gxHF&bNNb^)|Elp6F@u(O`l&V9ktY1vb+ELm<0C)dBPNo_lu0dqw zOAv^Gsp})r8__X!`p?W?>n!rM%GI8ymd8iNR?$mKk7z-%y(Ldn?uOTs@A!*406h6# z^s-jCrLC>4pT8})@Cv((Xe$cc8G+FZ2{E9g&VHQe1#6)*i7jj&1Y>>sV<9)Y(JiL4W)v+Wxsh1{K%43YQKgiXf|lzAW% zCDl)LEeqC1AYX9z>`(TVpveBJmwGRhuPR-Pc-7h}NW^E!LAOX9(WKY3^vysEwb(Hg zG#G)RuZpn~?D1D_ZWIb)X&C5qs~H`F^^>i>)Ti&U@4SWpd@&eW^#Due^|f3fD97zx zFUO@cnw^OO5SHd$`!xYD@9}0m4w*J?wt@tn+-U75U}(Kt2Aa%9FhlxC)EgB)_j<9e zLYzWIR9qb{lI%X{PiF=9Cx1&$t3E4n;=4Y3YT2wYkJN3CAhx`(UeJ|WtFA; zBs_kYBfC6GiMvLsNxTKKwAf*jnsa=STFqR|QqYou1FsU=qK_AW&z=ZIH?}uQJ_G(f zw=lVqk&+lXlaQj>{Y`s~*wF4Xq^SL)JumOeT@^2XfB*PF<5qZC8T2>LV-o8B+k(>w z-Sta$P6=^vI2r>YxjP`$oQ>wkgQ+3$)~aRMcbsBb#=$V6@1=b^e)TMRjZS8PA_a-ASVRjH(S6T^-CJxudbMB5RuqdcMCad@^(J+U}}2b19b z1M%{2C0G4T5ejnMG#*pd1#~DRPn~2vBqf9F13ga0s(4E$mstFEnJO? z6eNP1HBdGT*cU7n1|#C={AhzA2u?1)_5c2EKDBS)rwR$@;1tDKqCL!0i!_%U%Doau z0&~cC)tChFnwz)2ancaW8Aec8-=0bdiIOK!rpR~yopmpj6v`?rDS5l-Y)fPsYfgZB zb?JBm4DXHM+~5Anf^meC4(Ob(+;vLcVIlgF%`Fc8TM_-=Ej6|I_nRaxB?rn@S^|Qr zGh)~@@Pnp6;dg-f=Ih_YI(gzfJq@nJCFKZl{LdERJM`}UvjsGj=M|}yfY%lgM;6r5DSXy^S51VAQfBZ*t*|m)ZzA|q$Nh0J z_R>S(-vvO4%WkLUY+1RAu1>nXrG+G%bhC!W^JJ>eik}HbT9@1DATCTPVMP9ue}jH2 zq@h){(*61?L^~vsu>y=&br`kai|cBzf$(7JfH}cpI$qy3=-^YY_2T5CtDMkDF7^hE z{OZHXvrsYZy}|JQw8sP06xjaC2wY5kytG;wU{?}`T9&u;=mRn?C+OM;|e_o z2DhI@E+*F2){-twOvGX!pI|ssK8`p9J0j+rI4J3h&4JkZxkK01^7)NNz7<@qe%IopL_N z`nWRU(fzm4JGQHtOY%%4PCUI{aYtFIjyd5b0 zTr&%M-Pk%f6!yP`5HD2TsF~pHV%#=e!a*J4@VcF1ljTBnV$7O;djS3 z$9n4lhyfz#C&OE+DSPY%tRCQvy?2+Pj{9HSJyD}ols1>g+40g6&GB3%$a^fi8)E^w zBN|{%09(^}PZA}>Wv`29Ja!Xsbx80VF0ZdvXT;b--&hk{e+hkqGizw}vpds?|F(07 zd1u$KY^|6^_{PPD_(h5FpY5aqH>(;w2Hg98ar@us>jTfOX%OV%+5H&&OthbIf7vyv zQjq5(y#2ZUdJ~$sst)wcDQ0EUej*?DD&PMCDk65`y`I`*-%KI`Xs zb=x9?kpWoefOd$9NkV=y?}ds!D@iD-jSZ*oB4s&fFniNE7X6mW4t{?qle@Ve3dF>% z0l-USSPEMxRQHj-H_O)GL<&r$%goseXn?v0*SNZ|k5;2QeOhvd z7FldbA^H##FXlaME_5pmdq_q5%Z7(!_a0`K zqKJ6*IrvZoV3Zn~nMu3EAiuizEMdp?Wi{+srNnI6X+6;&Jr)G3OmuM_1{V7$;hVn> zh6JG-Je09uMfE0BJl2Q}0A)1>t41CtvodwZ78f7Z8|)0>ag=|>^X_<&nr^pv^&3}z zNtBUWq!n`B7f@XAAqZwl@17ub5}1{swUv)c93hv=yinu=ftdHjrq#RYH)rQ3-sdhJ z#4jcGf2G*}pkip_!aRLVD1@ef@1Q%eynIdF{;Ok_LeLszRoM!hF6l)}TBbK;f``l1 zX>Cv5ps|TO{ZJnusMO0oW#KfC&*m?d>X08!(rV{g))wg;XhV|#&UPM3OjJ;vb#b69 zEG(q3IT5_ZaA-Z;t={1Il1Lm$$HchUQ{}kde8iI+6pAx^T1uO}%<;P~ORj{(da8t9(sUkcOMX$ zbM5c6B}qSU`b<}*H&B$tlSLe22mKL2$!Ttjh9Ivaune1_b5Nr~1=LC{X6kre`R?q& zRPA8B5fZ^Ola(++)L%qJr0IO=MgaLeL6(#2L#cYnxb>&sIjCJfjM)0SL$U6z+aC#E zit7|1uO@G+@s0h1gAHI0F?jk1JN1jxO6p|LeN>@4;8t98rQUeHT4B;%$;L*hRGay^ zktz-P31Zz&0m<>w3VOwGuh$>N7S4^fKKm;bh5@JS0JG^8Oaj|OM2dK=X7C5Qj!@i+ zQ4t!4K78DZf!y|gX=OeRjJNNk3b5HY*$(9~Yrd`B01vthHC#ziR2* zb`DfB^u^ouWD7e9{lJxG_u9wy>zLJH!iGO=7e)%Tp0BCHw&UYpS1~!XnMPoVRC075 zlA`E+8^}VH9bmtNS#-RIcrPha;RSWPQI@V7%7UL=lf;&N$dDGewt# zVo{rVtRDEjiIiMrt)j9@6$wY_ZBAy(cprje%}J)dIeoAykhd9q0U%TDdax=2Nz)%o zaLmuVKmoNqoaP23z%}sGyI?{mLY?*}s-;|*gA~g^B>b%4V6}EC;2dQKQp>T;&R*c+7YSl zf!!?0VqL#cHCPMA4jX}~rDKv{UHduXUZiD;-6h0g*BsFTxBPIy zvcMdo%(&TbST*<~`*^{a&HNt9SggEy_ev!BJp~n83Z*`OvUB`JzS^OU;i9@cc`akO znk;;$W&s#mlY^0js+IoT0M4cJ%`r<13!MIGrxDu~g&3ZD9$5#P*E{025G&?ED4K9f zz3#V{iSM68rp1P*4Q|^`*c}JJ_OV~FIoa|`(r!8)K>O-;*#2*@-P37A$U!)LbQ?_7 zVqPn0{Y@^|{=jLE=uewAR%wkO26m-rR1*{FO2qf_0wguog!vsZ$POm3%EjtM%}yYW zvQ{%vvsMlfz8APztpgsaUzZf2lNh$b;l!gM>odOp~f2EYq95;3W=x1S7kwi6bURy zMGBd89>QdnPycceu54i8HrA&U_}0whRhOn-)jAD{!=@$oj& z_yY9?7YnA_@{5Jb)gIh^KL+#yMOg z00x?GGG=gU?>Q!JZhSBmZeIU)G4e1X1Cqp7u49153-BvAmzF&6I4zJHwcm|i6{(lR z4^nvwcd%U%Ql`kpN>jfGn&ap)O1MopHhLpLgB4y@#{3_b&3qSVV8H}Ri}sz?e-ioH zK>Hjdo4=y%HI1_)bTM>MQ-fVRy?=RqZIBE{%Yng`hOb}6EuS3xygP^bNl8^6VWed% z@~qzbupyd=mD6W@VM|WR=5JLX8> zq8Gx$1EvSrYV>D^)uYEpNjgBfnSbUBJd9u!lLdn&@FO>hFRUE=8=rODrWd0H&O`Vm zqe+(5B#j)3DMiTWKK}ytDv(&5xid+|Pxq$ITynsQLa_u-{YFAtl?u@xebm8D5SM$Q zz9fOKOlxvLVi2H@ViZjQaDhUkMXg43tv6ui%L~_*t4ljx(1VY_Vg$(;{CPmdunOU!p-EkdC@x z!udvPcIP(#z}~FE2$<*s>qA%PZ!0}@rHiMYOK0%wT_cKS1HtC}Mi;R0@n3?-^zni2 z>f7H*?n}$^spk#1-mFH?;czAPvB}|!o5%D)o2JMumi9iSZ|-O(cmGD+&Ju*H?%PP8 zKFu_0XtxGpymEmJ+)A7Cs1cMpH+g|=8{ zZf$NjbEv@~P;=~aDw65*1j`5&r}wI&OJHb!yf3ZKbO7o84(Et82vEo;8yi3_)zf72K*qR98&@6r@s6mCb~x)AV_6beugb-D4M9Jxn8)MPpaH3OF+fxvdw{8IuM< zVfbqrY0Ew#RclsUA^(TIG})Co{iU`a*-z!ZO5+3PV~gI$;2O%L zO4al0>yv5^X3u)oXKPa{v?a;Ds;GXAmCsL{-sc1p5a102lrY9wN_iQO0)V`dc|l&i7z~#mGjD7ciVN)zK7Y$_nulk8Sl;Z9i-supYt}}^^UV}!x)iI^ ztC6D>ks)A+?up8ZR~i~54}HU<7T-6`aQjt?QzNPz%>Q}7cwh_3sa_Hc6I8kg*hwMce*!{NiEq!v@Xrm>F-!~s>rc`oTv zeI}9qbL3pHHT)5jvffYAHI<|jHMHTZlwSi;+T^|n_B|)S98w%JX z3UM!aVp-0X=H|BQ(6~rjAADp^;yw6X4FYxb^?nMo$AsCv|h8BDCQpT`6n_nrv4p=6HCN@6CX$%Sv^$W(178&a&I-_Rcy zRS4Fzn@{v62XKDt)Q9IP2?Vhol^QwlvZpAHDwxo@_;qcW4Ftqb(H6RKaI^wgWU#i z^Nr(2mji@JvQrpwbj+Yv^a}w%+m|7G)*MV)pju3pZ*+fY?s;9!{gQTOo@&IdA^#Ce zaBv#ws!47Y{#K>)-K_|=9LAQRuk#nGqQo+1WbI`W(&^TC>%DFxB!av?`FL+ zpnNq41c07c?zuWAEqa8mlLXoPKo95Re|^bk8!Z#cp=x~4hES|ZtMHlY>(r~!p7$TKRI{Eg3x%DJq{_S=e~6(znwUySmF&2=BE`xq z#Z)PTSDAmn@f@Aatu4C14$?Q`rpS%?8RoZ75vafM!)$&IF%&B(uM1lQ9jJad>IZKs zt%8l%#P9;9C?tN8;{Wi|yZVLGaumVtdb<|vwz(#i%u^}nvVRq4sAn7EcCpR+?JrNA z)x0Qu2DPC^A7m52>hwWB0LpYW=ff{>O)jbg1nU(pI-`daqk4luwTGJj=s_oRSZ_;m z=ZG1&%q^&N@<((rD@Q_E^=(doh?0%)#k-N6?i(*ZQqL=OMUS24{%waMWtAbG&5v9O zq9Y_`=B;H;Q@bu@I!&7w!Y#+Y7j16$e*I&UT=~jA821S0PQ6%b(%^%#|J2LF_3w(Lut(L1&Kr#{P zV2yM^9O&LcK~S?kg1~I}Cl8Uiz8+N!C0f0UZKju1muO{2UKuk$IKJA;)Fp9`# z;V>k!bExHj5(uB&w8Crg9oQx-Gu)__O;sLtKOcs+x%0ZT|7veJu1f&%KobiKT_9#^ z&UD%HtLs{zAa2{ky2G>W%HwRAM)UT;V*LqZAm2Vdx`-E5MUow4XHwZP>Q4_O}qDyjtz1cn1YAXxO*+y?=E(#-LEVH&|l_LlZt|mh0o`A zENz#*48o@;anuTYuq`lw9=dh3^v-xm(heg+RY|YZedZ|nB`P_R*+^y!)Ple`TWPAe%ggI3*E7Q3+O?_p>;;ox z(+eDNMYACG&D(+cqs*@aB&|9tZnb+KO zW>C8Vb_xaAHcN6M7x6GIQVn)^a^knv+5M~WAaiZngoRXv!o)Ws=yAFw2}p*$`#+`& zNY%j(f%vcI#qj^qd;tt)v+FJMYHEp4cl%S8jeSo_;f>d>*z7+?K;cQ5Nt_X@)>x9U z2+?JnB)D#mO`XhBqZp7Yl*Wr}nWTODiH%5`B|oD7gx}>br@kI{)JcXiE{`pRc38Aq zKz-2;Z}%jhgQEik%iccS_yc^~d@# z4`Yf|K4eePd})*Fcv&2aGF*vVPWdlaCwatPv`(=p{noj?x(!|j1)tzaJ@!+h%-`Pa z6*8|^EduOEn>!T<|GapfYywd=^^k9m=SglWR7tk0ui$OhU~zwp?lf~-FQ2vQLe~!v{>fHpNj}TQ zspJ#2LgrA>2r5`AC7NGMO)6EHZ%AIR*a%ZA9Zv)m2SktvrY4Gw=GLRi)Mo`w(o~fY zLB5n35Wpe$fAGWI%^6^0QjHSps^owlM#qCo28opljKoyfRO)Xs!{674IM7mg7X^hg zI(kb@)K#FM*JX@sYB6iqTiM;r>tv5gw zVzT{P19%t!e`hJcKSZx6JOmP@w|jWF`5orE5P-2ZqJ&AH92>j-#EULJqLfM>ibR4FE6kDO=mrGx1FH~o%*6dfb(=>o`a?RpD9p-DubEMcH2YC z&C|UYY1=Pg0Ua;fNhvl0RMcfXfbp4&B7S^okCiXnJs=F>mx)v;Rxv~r+vRRAZk8x8 ze*Y$>Ka(7pBTIy9Dg-487X_fM8rX|?#)ZPO-tez9`WSqk^-G*d3Fu}#n=vhsE}Z0Sou2|Q^q z@C36spnI#*-=GGX3~_S&Bb9Mqe4Q_d@8>G5-_BbF33^;tI1dvb1(K@zXVrLD-HEPz6g zEPGq7Mfu@rYl06J%0)OnoP~-2I za4DjL=H)^c_BZcoGVko|{>m4e_>gIRE+ymt_S#0^^5S{M{eNdv8_4JWdj}N42@pc|f zuZk&EgKoV)w5rp@$7&1p{%w4KcwAe_Pm*ViV%+la>Feoz&sGf`&+YvoONA);uX!BD^*$8{9tp=-EdU5*l@R<=Jx!sGJ3hkK38pu22bpWE=BA^3FhG*Pkj_o zuCICO+S}{5ifOXCAqv2Tc?;6dyJToG`nDC)417`~v7MkyUxC7yXOd$>nsBgY{k42r z?|~@CDYWkc%l4>kWYHTc40) zF<$Em6u4dWPj_7pUHYu+G#w2#W=e8eQoWu1YV`Eq)QIkk@l4`%e!WG+ux1-KLi>n^ zK{NI9%hZ!^iF%pI&9M$2=FrUXUZS~ZO(9Q|n9?XoL=itw0L!YH3vyZg*!Cy;Akzeu-Kq+*NqusmvvWxbFu%=Gb7)}iqjTb!D~LWy z?c`njnN)B2*R@clQJqwFe{m6!Cg5Mnpldqts<--StM_Tpavo^aR$o%ST2ETVabIPa z4>ZG0Ca!$4sQv8YeKQJDf2v)tYGz>2C#bxZad%?1_Ujaeo{XEEX?g>&IS!r~jaWEa-3R3d)0~Rca zZ@X}KG%C^H$ zAz70!42Bjb*qRwGZdUPvS4D;z6WoVi)2UR(w_Gb13m*QfDT(4;Hxy5w8`VT*{?wRH z&Y5O;rAoXMNw8oN5d{18-Tz27yM{iSFelCNi{GBPnOiqig|6n6g#RrqwpSO_<{PVI zEBA3R#-sc{p3X8V%D0c!B1lVvL#GHMCDJL~9g^Y@(jeU+-Q6G{-AD*ZBaJjecS^T( zotyuA&iUXc)^fo-^W5>plgYyJEavAFp5j&`%;c9E=ocZvp*+z zBAh){pg0_;B448nlc<-BbKhjvCHzK!cUL*WSte}`yXwdV(Ee0Pzap2cUGFV$l$G{p zopAjac`G4ev_x371RKO4hHA+05fzw7F7UtGR{Y9Bapv&vma3#LU@`u=uX@aY@sRfQ z*eSMBs-VwJ>9BzK)PS47U3w$W$$oO>!9?MMoaHq5+B{hvyU_PDhk&b^e}Z+^q5C}@ zoQ;tP-MD&&A#`3;Hq=D7Z0VP;Y`&ClRVG-m0QSsl@S>AB)NL%WX zR%}YzA}}e$V%-H=Of}NKUpim$ zDim=C(2wdCM72p5!XK5f{*4$_RhDE_zvXWc=9xrDziSH2oiUKk+{x$ail=r#@QUI~ z2AEmzCz}F!V58FG!sgMfA0@EEkmd-338GC`L{M=^p{yL5&I2&7_?>-Mu z$SrEwjk=?Zu1+?zud0j`h8KycTnJWKN0$NZ4;|DPNB}xs zT`0n%;a-#)J116;G@bj))436SCgBj%@CGsZmqGh6j0Dj)CxIw;N0;H>PrW}c%<*nl zE4?}W5$<~b>gQeZAj!>4r$EH%ywT9aGZ2P>P4!aDx!kx*6vif$!e!e6=l+2O7n?yTte+_WAvV?7Djmo zIWukJYF_Vu9j%IVzaO42-A?{|^sr4gn_}z7(^uN9X-4r~GeilTC}(;dY`+-d*^iK# z&KX$bAPym;M?wUTC2pS}Ds4_{ zn8LHjA_j7so6?jvJ^^|ToWDoX?6J~-Q_o0*0V$9v*316zJ(?@Pm0Q+EF@H?%c?T7y zXmvdkFcX2wZ?&e|KmBE33A1e#f4tp?PJt{H2wXLRu&C91Wh}-}>zBia<(scS_r9aN z9trmTG2G;qT30vOp<4Wd>&iGFZNzK@JI~n^n=sH5fj9{KUqn9-*xknHta`*{17TW_ zt)T{87jT&v_{tl<(f_{Ea#K-t+fn@e6N0LkLM%Ul>&;Z;aU?%KK*8KZr@+S%2PJ? zR-t}B0{fQKJjxM~ScRwf=V8?0=1>&%w-B($18;tcfEyD~qUd_a956wd1`?wG9V?65 z+Hi1s`(?%&UC;zicjZHbkals39;1eT2*q7_?%Z6R0yLE_Los%60~r4a?6tp|i5+=G zyO%50>*avha^~U(5SJ&0K)$IKV+Pj;HNZEngff9?jzwfy%J8Y-y#{@5<9kpkv{@;J zy;0eL1#1sL(@ILz5S`cm-uUzVbr4>XHE1UJ^>B~EbN3GpAz`xn!&nHqyMWQJ$%Hz8 z9T0CeE3)Rhu)Qx4v3URC95g<73*Ds-2ON40zohiIJ?>eWSeoKakS+L3h63jR@Vk?G z0g&%iXAfj2tFEUBf`P06u(kgk@y9m2{dK&4$_ygd8D44q-@eG^|9KP(K^#~6r!(ia zqmCL*i1aZ#9qLp2875iAriT9I!)5WxZ^DqUe#x5_5od1sw+8{wU=YSPP63JxV(sr}NOwdh z*oMO!)Wyk|CSqXR2d_!+(;C!1%@F}|LsF6^NK}a60GH~K|MI(6i2{92yQ~H9VnHCJ znyhszJccCAJIu3=`IxZkvnzeZLGXntKlmnPCvo_!H zFEzTfccNj;&gwKW^-D_XzZ8Q=KT~8^;EETeVqA9^NdJl5mGpGNLgNL6DvX5Qdkfy| zfgMi7{P;x|7Px#e=5&>{W#jz zMgd6Adg`h6^=!QS(k3cb)A629!-v7u60~>G&uZa6WuPFlRMzF2uo;{^pp!IMHdAA6 zZl0~j;;U-Rt{uR(y}KJ(Q@V2o1wM%BI%`r=?lMzglLktPAK*{1t5f9F6M~gm-ziv=*iyXk?pk+xi;qbI{jLrAa zeu%uK5)abxA`bASFOd{iK*X(maEhIv`dun*Jx%qS`@nMAkwd0M`I{DlVJiKGJ@L;E zl%^!z9(QchUlmP~2*RKFy)%uJdC7Y^;J}!SlFI8q54g5->8vwgDkEojyxK+Pu~+pd z9z6T90A>2vZ~^YUG%Mn~femBFG;@J^EK1NPl+6QL6!S@ZxJrWmEO)?&Vwgyp!I;5m(b3RN$@mu zjDrxij6z)(4>?;f5NvQ<9oK$s;JVHYEjs=R;jcI2}=-G?JN4iP9u~|KgrGY+)J2N zpo+#w4bCCMgH_+eMXmsDJ&(qPv`AG`6kqO&!k-VLR`mEJqA`7W+AW@pQPxH?&T#C~ zQ2KK`FaQeLoxB2B>>&kiuPCtgpFHO1ErmSG8*an;DVk2Dgg@|?)ST{la=ik7yLGxe zpTbn04B$EiTXBiit5W~VZI+O=>i-1)I|$UZH()ULa6M=X4$x=QN|HAr)L{7#r;+i{ zC2iRR1wL{#sq3pQt)SFhkYK8O?HRSKA0=`?W_WyWWkcpGbK>>qP7rm${u9HYc`@ue#f!g#>$S)vYKpowO^^V{f|24I>CvX*QbE zd{+qDRJ`nB_34_RZ1DY=apwHNd&2}+`UxIqPQdx{-T*|yzjIs7ufM_%UHj3K?Co#a zo*$MN+mKG6&Cz*Icr7fMdlbs2P)E3dnpQv`Elb?98L;wM)(aBUk#3+azO7)$!&j(c zjO+As^@ja9Q0e1k;HnI9gC?jQF{`5vB@q{~9Wsi++~4>wnkk?J%uqDhYaRpRzXpa{D_#Y-++zY@f;m zhGwvx@nX7o84CbHqr^iN5>fZGUZ^7s{C(?nzH&a-ItX0C=GNB4b?i?bJ!hCenDIZn z0iywS*ew#^PI(q6rpgYMQwQKmxIc5vjDAU{X~!XVjx_Lf#Mc_t`69V@-JULvxZ9ba zk8Yp4`233&8mhPuz~+Rl*)c8DlR%haW$Al2+1>Mcj(&}Vbc$!I)2X2)sQ<&p936|3 z0ONid|=`nWjJ`pA-Ds>-VjOs#A1% z2?t!{IlJDP7E#B8Op|t`;>tjyV)?;oC2+2~wi355p z-2=o$*}(fblbI{KR!}teTUhG8_)fbdgi*XJC4|qdSRqNm6W-y92meCDe?^s_=kxIkZ;h$L-?^c@=H`rU?^hkl7}kCX8~ zwCZcKjLy^hy2%&RcODr8R$M(>lV67fBMu5u%>s0TWj~@zwAX=h7es%PuzJjG zbw8>EciRZp7xe6^1n5Y!u|moHsw7OHn=w^hat>*`F{DvTwK%0f?&YN*AMuFXnrxHM%`>i-SVG?(!@5mR03e{ z^7W|I0HNi9*1k)!`>vz54;?wwxNWt zH9z0%|8!_ad-d2R4V+-MpBCp+nY8P^CM8XlvkG0zFW}QV4^}c+CaJ38)8@X(_Vp!^ z8Hfn4z#Tdem4lTPwT)@MNYkYXzw_hf}+@bT3`;>19}<+n=|--GM~yE~bnoB?e2I^V}mp{)5X$86OHo8(nM_vXz(YZkD# z#yCyd=)D)bj1j9i*j~Kr+@Ne)J(Z&H`Zw?1OmUM*_Z21_>s~9%DRhh(95h=ucv-b} zdHG7H3siAWYQEkW9>}n76HIS>UuCmz!P2lrgN%%w{o!?2^oq}006~#GxbOO2fAeD4 z{!iaadKafEiw%3Cy;h$?>R^i7^TI5*gIV#h`aw2PTqNJW8mZ_npAUwH4QS>EF!056 z%P63FS+Fbfw2%J%k`!p7+mNoo35H+4GJ_vkm|f4^5Hb(DUiHZHi9zGLIS6FUSxK!E zsjHZXB|e#9CDGEjxO9vlP0J?%e+Q{;(@@YEDKKkOex2n#h;h%qKQQL1E&K3Yt#q<) zeN1{d+CM)X5Y<|RKe(Pe`y`*$gK$bz={REu_=F-rIBj*mIp4QUd%_XG41mhAgde>2 zoj`jQtH1@>#q9|N=xug3hFFX1sSKY&guTf?x##d1?_OmGh)UB(nfNE5!aK1MjT2t) zqEMVQL{qoP&=GH8q;Ql3zTD-a#T4<_WI$)O{;^)oKp3^GB>@#8PF2Pz->Xqr=-b(+ z6orgT>O^3r@MVZXaik*{NTfWTSg5FUI4H}6f=w)nd@zc<5kN!r=$?e(v2aLW6dQ{V zkNh4MR0y2ASKq z$`8fNq5feZkOzBhI{4MC2l#qj9q8lDlT{T1R*=qJC2b&8wDn=C6VJj94l-YY)x-c= zu%16A&oWbKLTGfs%>Lcd=l*EKpA3K<$(*NG>|!rk$y@Kv1of_dyNr%5c7wqPv7kFg z>ur}mgdVU!&%3O3e+s1!{*B_4&!rNxuC(CLn;{-*4&(l^yL;0ak44)F1e;^;m-O$rB!H!GWS11afGGb67z3G6Fbj zvL4BlS=9pEn%ui{0fFH{opNf_ZL+tSgM{g_<{|H=oWxKqKY01-lq)vWW_a>(l3C-6 zWRp(?Ch*j?cptV=rK*RC3cZM=I=i2N+!4KZb5V#`o{;TZZ`8Og)4BpKGYSkb% z?+@Rn9?DzCk{zuUKKN{5`?OUv=?$+%yd7FjS&IU91o)$K6x6jQ>68Ns9VNElzt6l0 zu%(CAx#pu)xia0>P<{To<6O!`fPa6PsMzCs@&rWf&(E>`4rcZI+lEj3Jlv(Q**(=9 zKPE!W8(TkXyEqom*Sh-f4#bZ>l&=OoWyBPPcZ!~D8hFPm_;?4Pw0L1C&AU*FIVA^J zTQ-Q(9f0t2sCBxl_dA0JoG#H!b-vI|w=d$*?9k0fGTnUM(jXj6Oe_@_K~Q^KHIU+& zjdPhP#g+VWWg6JGPuapK}LK_R)9-{n3$y6~-#qiwuRKhIkn z-)QSJNGM%lrZ;>4`?61eBZ?D(Wd+WT);w3$xNpS>)qK!y$SYZ07TsRq7djrNFWrMJ zp9s`<_RZJVTw@Dcjq*MMcV5NyjWf3#n#bkAr~*4fx}759<0CMom^-L;Tr9m4is5@s z{ro$aY4lGK;bp4j(5J+Bzo^;O17P3ENuN>*kI=yZh!UFmB)gpLHYi6~7Q`Uyf_eg+ z>7=-x-8qzaQH5*P43S5hSJ*BT%K`j)w`1;dU;%~V7Ej+1%p0{ znrvPvu?_aFBpMV7R~&%E|95r{Qptbz>K%Zwh-^a@P58)2Y?KQ1*b93Y8`Tqg$_Z`Z z$ds;QTjpX{A($KfLi&{1Gpdefs^5MXHNeayJ{l}hS738c^#P5OO>C%fWSGtF#uOIxx0>>j#2;!B3H3FVt#Xy*87R?_vZHq_ka;L z3|OoTMB!G8O`*kVg{PhIK6$DYz&1L)3I1J~ait5+{wSMdLtW#pfrzZD7j6A3k_tcu za~6W}OeRB~k#aTUtVWCP zBLD-#Ktqfm9Q9I-`80lt-#37*06vaIX=Bw(5ouk^*Uf^00@qu)Uja@y55E2Bi6iJ{ zAYZ-_0xLQbctQf_(`)vipR6aEoZp%9Ej#^(1}nyNE?d}cL8Rwe-FJLhi5BIM-nH5M zX1!w7ffqd2DMk=7l8?g&3!pXG=iv!(E=n>=ynmnkS94;gp%T6JSGUuyYo_8>kw(xK zggcb{L)u7r{Lp$a649NY2Sm_`OR9OzzQ83i+;8V)dnKm}I{6$Y8(V-8(2_tQ>j=Vy z>P1}{uF*RpmIgEwrpm4d}cS_ zsR$?dNTL#HgQjoHx%!^U=2WMk@B85$`JGp@d>U6ISkg{LqZfbu%$i(60{E0?Pg<|` zzk|jya^TKJb@)2~1C3#hQ9GV1XWWZC#s^<{m*nX7etKknH+m&cOOyY)oI(A0&ZqTM zlMn_i4NOu$9h$$U#Pl81Bb@&3<$##2QyvsY?Y(Td8}zQRDH!%-h6zwZAEyVBdQ5WK zxJrtp_{?x|y7*bwadx{sq$|Cs$w|#c*R|))2lKHQV#m1+yA+?7yntJ9-!x01SiQZP z8Q4_Sk&#ih$QG`IZ%esGL6Vfv(ZvNmHz(D6Pz@?~0RM9ozHGpv-;e+@*Id?m!|z*8 zOr8=0ngg0xb5BaU@i(6@>d?VhDe|t0jK(dnc)nUOTP&mgyvqVIlt{pS`8PpLu}dZZ zEVny|8M`Y|YrnyTFS!(iC0G6kNF54?4>sNqbDw!OR5bgd8A+~b%KZY8#h0icd+|jz zRVcs+0`;`}0uia9lD+na&S7wYFL5M-m+-gT+Gj5vG1GBovllKzK^YChI(r_R(Np+c zcHy%mlM&vA4C^_UH*RCD>f&a$0s7qS844ZZjK1cxzvw`G!ywrWQ znbrD}vRxRUn{V{Iui;r^qi-IwX6!ceu8)gv8Sz_>f`L@`^PR3zq1ZkXn`5sG$|C;~ zQY4kZW>HRg>0F*Io=*49kP#e6dnX5zg8NS{2kn*&|6hYLy8 z<(Ri$G8&ynIlZ4w=w#^HHYb8*b2+O(ZU#IxU2yi|B4Yh8z|YbYvbfmtzH|Z#Y>D6W zijVf*4g>$u&lq_+N6j+IkK)hd9@?ltV(~)%S_l~h#qDh3J;LX>sPmqar+KRD7;c(n zdcc5=ZTi&?s4HQMiahVsYyV9*Y4P>O{LuaOy5i?p)QQyrIDHtxKBj`HiVuaBk4rFM zzv8ss?c0JtIv)zzXDYzTgYBifX}WHIO$ECRI3Bj1tJ+uER(Fpz(Pm~xe{OAzg{7;_ zu}Yj1V>!C~jDu`Ossv48FqNHYpV+_iLM%@mcUwI@>JP)~O5dOc{1Ek^SW}|Wv**5T zBR}8P)|=C&S1L1nghX1k&uYOrmNstguagY>0ofkc>9-YtNXu67B=yDj{C6N;wGBBx zcLomz!Q18V@Yjj|d!~#xMt{Gyv@G%p-ycT<`>8E_Y)rHzCfchk0H#a=%}!XY$hr-v z8R84i;CBWu7BJ#}nyOd;qd4mtoGx45sEz~uM(rARPT(S^0ZyulgkxG$=ixJkWaKwr z>0sVufmVJcoA?a=lS!Ik^*<;&%yj_|WwN(l=_9)DrbmD`MEgDfms!-1WOlx$)h9-t zUV^0%aZ7?gAD;$C7KL3d;h>4wPq6V~WN}mxf@D`HFDt>4Z1S-(Koy`LiXT|samDBC z$xt*usHo0h=JrHX)JA1~o|`VN@z-lgQ`oJca>*cTJI*fl!_7aJ2SmC z9moS=zxM`Sfk0>y-G2HS6{P0CLaJSBPpGf2Pp8HR&9_(As~_Lt6#cGfcXB(8Uquu^ zpgU*A`lNjar)_HkLDZ zXk#?+UXNtv>Ejrlcj)>559if9I97X}7-g;3e;1H5)QOvco7PyJu>%|Q8oAfFN~>P2 zyAvl6MlB)jG3@Nsq}l2S3or`;fl(L32Pm#nCMK-2inoBR%38OuIXF9N=os<#oo$rJ zx8|RD=x4P#YE~WWqFo3h?DzG!SG^D*Y5;~4xCO3PYlFO{ItxD1Z;|qHe8tcD4_%IY z6Z*yKfY&XW-BzGL`WWc?lVGl(1ccGc*G7QT1%6krd5=S{c}Mu><%Zye@&F;FoJln+ z>NuKoBBz2sTLO@(;FFWx+ooTK0QtGC6Ai!5m>rcG0-g^r>mg$Cpe|jwU2hjwG3lEA zmb@ycvsNqD)M|8QUh7e!ij`L_POuY91{X=U%B;!a8^aW=?Yu7KiNgHyjB`cIj+(fJ-q+_p`}d@#skEQ+ZgIG_R#03&n8lp=$iT;Qa)qe?#< z(@8ShdT!i8gUe>V7vM+MLcRk3h6#8`eW#xj6?BEV-gUiFmZYCqPDH~(7ntCWn>+azK0MFqJf1?_CvKt15R5?q`TOp7Z{Kpr`ly+s z)cPI^=z6VQ6_wj0K;K`cFnc@77DBc_%c8l~P*BXRtlwF@auaci7Q9bFl2In!PMzEj zADi_vdQ~(D1)UCJjBXW&H-Vh}M8a>J+l{wxgn&P9192lNh9X)SZTDe_s_M!Mz~3kdg#C z7PD(>0|B?tbZouvQ5ys(IY`d>^L)o-KnyQQgwFl6HJZOf`|?eXMUC-!%paE+VoqXs zjH`D@#-Fj7ML+YMuN^_P)wp(wYtd%nDZ>R@ln@$Jr*WOH9Mnjvpx(#W>@!X=9dn?k z06K?+cyb6HtJy6Ua?;3+#X}p8sx05E?!Wt2pd4~;3~L`bOkIvYJMQ0wqcFWPcEXJZ zs$Y!o!c9l(3OnWWVxo#d0c<2PBlVyfO|9B_Xq6E)h z^e3}k)T9pBMJi<5p7;%18n zA$&XR2$2jd$=0;Ggh}vztjaE?4st+)n*-)#y&je@YH>pUWs8ql&sJ4oL*`Aw8c(wb z&e+0&7)x^3sepYw+5Y}MxXZcOvMPbAQ%5c^V}N|vsOHx{ephOY*w22r{1~09Nw3P) z1qP=-4sT5r54R2}dGZb#kbIS(sfOc4qY=b!k^6rDdjtP2w+--uv6s~NgK2NjkV-Dk zWgDU!AT^5knx}%h{6rTJ+SPLk3)2CN#L~8`#k;*N*XXZrQ5$V+uk)m_7dEw zZ<0sf6XI0D1)-h+b!KcdV-_7aS0i%gpjK6g&wX7&3LZO!dG)f8-DMvr~w#f4d8Kak+#1kZBb z=oWVZ@@TG9bhb{pGRYQfV8H)g_w!*$N2H`reXpD{(UGooN+p&1#!9 z9hUm7_^+<*p#rA^Z-4ywVRhGWcd;mBJ^L>;2qwQjOtyz@Q*rVw2UX;tOePIw9nwu2 zMCMRQpe+ICSlLljSHpMD4EclB5yFNV8bEGu4KH;bZbvW@#bwjq|9D244h;*d*fwS- zCLtjKYk!!D3V;l$bTVeX-~fA-m=ci0AFD+zt+Ms1r)x`niQhgtO_hB)1E_DywSIl3 z2E$am!=_U#(BaGAbawWb+e){+SMgu_)tbd;y^~*3@+V&vO+mwO!j={w0cc~Nblx-< zSH+4Jch1?i_79QInUhX*r`xv3>{b$irFaOaC8J9V6gWZ#P(qMiE=Yp?t2?Ax5b*m~ zc`WWLH^zZR7x_2H-B{Z(!6K%_`K|IoD;*k*OjM8aL{yV&Wl72U&2>>}DL!5+1CoqL z;yX104h<2F&J-oMdRRU?VSi3>6@r4=v1jXFR_WXKB_$ErmQ=6TUjtOS%2q#f<4r^K z(q+1^fI>x${~2qu_{EUM!_<^d(JzvAoO_w0HcHCnnZnGCLgD7X#>19$Fk76g(Cz@9 z%Uz}qO_vAYWUPT#;8w&WS7q6FYk|P{_Z-euX2L=G z-NdL?NValwVBom0RrSXNh-I)$S9{DbrZ?te#-D~4{lTwrr|^9fC+O%fr1^X{{O)2Y zOTTee``2d#pW8J`-mCR^p8LzS`kMof^QOHqC1E~?pQ$MI6=GG&;_xnnqKb-4b!aGz zZdEKffD#Ew zgm}FQ6a4;#g!>1p0kGJmk&-?MrP3r(&F4`jM+@sHq?9CpieA=O_Cz%lTPQ-mG=@;Y%gFCIlO2+G87A-=v95f$CNoi)a)rNRv?=*;$bS z6pW2c0kF>7+#$<$(a=gp8K3Q35QFJ2xXUS|b5ZxpmanOsU}+_?hn3)Kxutc>cNJOE zJ2C^thTKFr%5b>6&My zL&4az@(bOOfV=stUl^JTjd%?~Wefz?*!>uGdeO<5u9q|#nhjV2+s2yr8!w$(u8^;8 zA2KNU{#(`_j9r0u_p!KuXC)8c^|tTTwCSN2=q*YE`u!Wj&R*td!Smij`iLyHnUTnC z6$q}3N_nZeiA*Tl-}}7~vv(fN?qT6x*Q@gF-kh-V81&qfpUZ1*AAE+W@u*b>R>C4L zLy(UuONON?HmLsCNoKpmAL{vmR;PHVi5?3wN93IK~*0bb(n$_1~_IU zI`VO@2R|-mgpUc=`9$MeV9q&FwfxcDH7eYiAJhn0&4EQGRJE!NsEwb=f>m-QtK8u9-BF}c z5TqYJ5AnEIa;!hBsm|2-i-(Bzrp%zk4LijvrXf{_0hTlSKOH2k#GaWf4>4H9=p28qJeg42zla_45iZ)xt~CqXTL9IdlppicWgSZTTBbuP?N1sqDWO`kcCJRl?$QkSV` z$9M|6@`ev0i>bQ^^HI!eqJw5H-vj8(g?QEF5mQ(b-Fu9>S z2ti1@UA92IsuIfe{7joe;f3!|XRKkYx|-g5?7$Kxqb)-^t!gi*O^DH)mAlVIkBRoo z$s~qSthJS4|JcR${K>h2escDz1*+KPtM1%rq3&q!e_}#s#Y!h&Wf&V98%S>TeBKch z{c(QlnALi=;cDBF-RW0>`Antz3GJdlUQyNqPP#9iM1Y--Tx@eaQ z1mO})b2e(m8+xcy(6D=^c_w0I(cMb0Ce{Tvu1ojZI=<$fbIRL1w%8FDQ+?n7heRM&vZwxx~ zd${dHpnt>~rKhTj38Pf?cZqr>d9Z46#2QadsU9?bcQD%$s#Yiuga1{KPhpD%Bf>u$ zU`eBrTm2|u<+|r86sz&^q$OCjcau$>Sb-b$WncqvHbsbQdO5v=P?A~BkGi(v`f{R& z(X8-c1&YRYC(*Z4g-GzTUm4;qU6|Wg(S_k0^CDVXTKG{Gf0DA;f(8}fisK1Ngi9y& zI=KkCj1?+fUK>!jrfJ`>fLDnkx41k~K`!}rqLvt10oHUM1Yj&C2Vd9UdY^y4f-GR+raUQJhmrkv>Pw6whK(Nt7h0{3 zVOjyj^JgQd{R4Ms`eAUUd1vPXxq|A3r;5ji)hhM|8|CCd)v1v$6}!_( zpqo}k9G5aYr*b75P&H0KQzy-l7so=|sTVYny>Y*epH?yga?(lC-pUMclRcoP?`j(m z;hWrUDm|~*vH17c4w_CC?@xtWudW<~y$|$(Imf5F+Nz;}4?HIgT%%tBsqd!L2{Z_A z#2|Q`zWsG3utuyz`)7b&&lDc^Qs_Mf%hH8RnhaDkF!O+ggp@Ru(-ND@dcJM?cx}4M z=vBqqH*+Y}`7;SkP!6#eMb7b@va7eRW_x>DgfF90iXH|@38Dy=!M9aG^v}q}cHDR= z^HjU5$~uQ3ucd`WF)gO|Y-3bC^}4}o&wy}3;OR5ga2?a;2C3~dSy6Z_VWM8&?{h?} z{=XZA500XTilwLc214;KC_JN*?BH&f9?AE@Q>OnrzeyZ{DdmVjPAcW?I?4}BTa$kw zqh$-flC*0+y$2seWus<=p0;ehYH(k*JPtDFrlU-f1!v+nSZI4;ngMFgocdWyNeP06 zgarH_0+NQ^hkts}l_XjCl6FYLU%r@XOU7QC%&1IwV2pMjZW{WQ^%gZq(kB*VxA+=E zLpSTe0`pXO`XbZgfEOB;^MX_1@K`WfwO(FdU$EscR-QhXY$5o_HWYM`os`>pg)8~& zzy*%i@#z%efn_in&=FoP%*}ahG8TTlu3vD@l3soX9oQig|o14Nyg$ ztrk4@4;;>KI{rEx*4#Jim+9WqD9wAG`B+8URag!lvZwNn#r<3aq z3jo`4y9XoysRh;Q43t?#90|M_J}tWcteq4?Sl{}&lq6%4Pp>mQPjA;X6yM1&=o%TE zw5eng;|9Yidy8q5SYQEa(h7D1Y(j2aJ4Ie&f876@ZPiW<4g?N=x z1N2$VRKgIk1#fY{oPGlw-ZpxKua7gc9#&su3T)@aW808&h7AoVx_fwhCVL^FA`L-q z$nL?_LKn|D-Fqffv1T|&1jegX;wmP(giJl)<+JMfeHtJUzIh|A5^(5IR1yY*faREv zzcJ;l3rmNN?$&-EIDex8)J||o2}4>K-B~*1J=Da0j+@<8f}{3IY36cn&gO0cWQ_~y7!c7`e6sY`sW!lVV9 z-2Cho1X`GKv3funTbLq--?y`g%|%!H`GhJJNPxikx)IqgBOd}OSakCRnDQlp5fb+K z2__7ck`Js;yk_?zKd@{~ZtC{GI!$UbX;%llFz}2ewY^npIRmfWZB5qA9wjJWJBr(##H!5JB<=W@xt)P#YOdp^KZ*SMwj^UgX~7F4)Jibx`lQhH_m6HPHQ@FmjDyh-E)5yVhouJri>^>8`%B)*Ormbz(VvA9|J4H{t z5}J7VEwhra7m|*I;@%(g)j#egF>fkOD6k zN@o^Fvbz`Os63z`69>5^CE~Qc0NIs83N^~wTQ%*8>>{P+!iu-g0)PSCeNQg2ipQ)2JkR%@3q_< zh!y0DT}m&Hh+%hCGiCbRyHU8U;{sDW@7_qqB`7x+oOQ|&&UBvb8A`30`j8OzlCO~u zlrjFQc$Lul=BI2_2GB^fn14lu>yuw;6aFr)W@0LhFqzA#w6`W3etF~%jy4g9rGybo zeRfn$emTV)J{95fI)u0F@Y>Tj-dt_oy-KLI>-rbUxe<1=_az|1ml5?Oe`A6svjvu)E{ymd_Hom>f*$Aa&b4*S(k8{lAZB)fMo& zr%i3%;&%^%cv-%DW;Kd~>0zIxZEM$7U7fYdg57Y&+fVYTsnRL&xoN)(FBciO$jXTX zMV6-&UGVJ7s&T=aTozeU#89Gl`U@}b?Azbamtjm*p%_YKJU+@vmTNMo!XqcibgK%< zI!W1OsLxdN>oS9`-8mF`O4N&{3CVe0{_EJg?ZU`htn~snAOrvr2C6PYSkN9x&=G5- zOgz2ahzLp*s7*Xy^sqf>xv^2?-{%1BVoctir%FU090p%dg3f06r|2xUOudR|a54av z;+8`UyRaOpev3hSs-rIIUMDi9si<&9Ih?82i75^n%RDTZyIo&pRkQ+qE8oPttpCfO zZ%$GIy;MNc?~$iBw=vI-8D47?qLqrwYsvOyK-aGPi17I4R)dB%h#ia`mL?;ch<-lA z$-y}e=P;p2l*L_Q$=&5cSaub{V=tKK*6G__K7J0W}*J*jj} zDd>(0Zj{2DEq8Z^HJfGHR`WkniQ$FE?We4O1w+B4{|I7ncLB9H*a z*486xtsoo#MZPra!wJ2G(WwXXuBcwo>%GD`y_3%d9r z(8yHuz4TSQOuTGi;LoU%Npz?-Q62W3&EZ5VEfu<`pE5&gLqmgB&8O#w%@-8u+_v3y z)^sxNJ*RhX9Tjv*C2)1?Y>lkuwsee@9=7$R+fB41-cbTm#N(4Y0E5ThAF9FR>!EGY z<8Tm6On-wyn-o4LsBOy?J@_eq>(!tw&)K+I>u1p8?7azEGihLSTL=5ujiu>^#UY#S zRH5@DMLPl%$N-CXc=apO-+GQm!yOj_PnUWw5M%!w8SH81A*ds0 zz(<|P#iriiq3!Hc2Z;27%S38z4^wv}xl*>)Hy}m2EPAJxes4*OrIpGqvbUamfrJ1G zQSLT}a$u{O9E1F5OBbl+LhMdwW|DaNaAoyCV?dbFNSNL&sc6YGkxRB49`^nd($`ou z3=2=?vLOg#>LFvY825*M=Ln&@Wuu8`8!_I&V^1=vse1hoDA`9gC3VN(Zy(g5g9&u6`4!Sj^6vBpCdkNlQw z@9c{08HObO(lAMJ0{qcZqefJkQT@0QURdpq>yqsvJ<^N55={rg3;!oer$^0CdYmi* zRdGN`ZJcy%GD^%sskH|#6Z2U*>QfETW^?-DQt;3f@e%S>ai^T5io)!j37#F6mNd|( z|G~jMo;HfE^1cHvZU-A4gX~jfVy?14Fa#%ubGU(Tfza}n02oBQUH*cIwG0e|E7!Z< zHy^vV!9Hj5sEn8j-=t1XOq`|H3=3^ypbTY2mzX(ToR7iba>XE!)G^yz4kZZ9!5Id# zl=nxaR;AtL)l9)*8r^kPdQ%-|;yut14PTlp^*w~Jym9rmG$@~Dkj+O3THL2NW2g)W z{-?^bdtQFt+1&w*EpYV$V_=CYEn`r<2`p`=e_nqdnVwc(Q(_GBqeRm3?i?RgaBP0y zOO3^UquafzMY!IED{InrhA1H1hK-a+omjjU%kM4sXXf{x#PraAeBBCUVo+GfkQ8yjIZr?8c2rAv(wKUQolF}`?G~$wigmi-j1CUAjqlr1w6y3UuTwB9;g{I|NC$I@eaqT#bkHe zRR-+-2TiJrgDQ|h_+h9_A!0{0NL!=|zi0E)Q3?KnzUH8{ahwIAex%{K<_mr5U*Qw7 zZ5Ql`Q5h zSYtI@07OktxGs$&*7<5Py~DaN^Y_`yId0Gl)O!7gtT4;*vQ)omwVt!VC<4Y^png&8v^hG1zW7?k82O=Y(^aR?K);UHlaDyveYj^!U|supC0=cX48Ic-?1y zf~$x>iS86B&8WHdEQAi9K@cITL8dR2ZWF7XV3QZg(H)8)kGJY7Ckq5nib-L80csu6 zi2)n)hE!8E|7n*A^Y1%BL6FAxae?JPSFt9iAO{^y0R2>~*X}rf=T<)F2S2>A;hZX& ztrIBIW}{iYS?FQNEAf%IwG~X842dMY>fX6n1n)qq5|1_Mr6l*XvS6UU7Kg$2P~Zj! zIOeQ|Jzna|@vO&d+tux6#Y#b%{q=NG>n#n=Bcj}FwmTwQlQVvIH@6V%kc&ePQL1QV zeulKaUh}`s4A(lVsODg+Q_VMuqMBl_k0Kz^IcDJ&zr~e3z7dHSl#n$_$U$s1;!(ts zCl@HPS;xJxQee_D=gp}HD+^$ml8YvbG@JFvlyB!}O;m!!Gs#mrK7FhVNM+NG(13LE zHKXtX`5T=$~d&)u3<4^*!?9%R@Z``6_PCj5qO4^Qf43bmP=ATtG~#R zAw>w5&aII6TFU|xN^ikpPQV*XPk`hp;!|CM@AtEu)7QBfUnr=0FjS+=c7M-ekBfNJ zeI);OEl2vkT!89-!$veW=w3#%uU|IAq!CXiVqYjMvx6{ac+dk-h}l|i9m%5M)qR#> zDn<0900U7V9i0A6p#nZkhVq*7Pu`RUY4<2z&Nw4`b)|7=lX^8rZZR7i@ki7$2iIsS z65|EVB0;8}WGVUAuYNgAkUoJa_t01RaYkk#!7%Oq*D9$@k*bk-nyfy<75KJ>9o)iB ze~L6nfXuL*4uUh30$%^NJR1vCV=O#7MGiT{b{ed*G6;f~wc;T9`0tXLBuT-ee3T!n z$ML!MOz@FIAn2Js?xt|~*hBRL{5&Qg(bK_dj&@C)!CUTs8W+xWKZ++$nNn0TtjU%L zdZqJ!Fw5r~b%$fHuZ&pWDXyqLKB>1i;&of*mRzO3O{3%9@k@0nqg-%|HjG< zdELk&O|V+mi6tU3Ch`1MU~S5z3XHAW+QOU&;Lx=O#7v;>d`$s~As*XlZqSX}>@EX!T_)*Gc&<`y#lu zI8+oO69H>qw-#n3nGEGG{t#TYU73f_C$Q4k6LH(*V6Q5Ga>_$&Zf~f4thm=YBwGU|;|q zstL&0$-{q&wUUMWkN`;^_(6hSE_%f?DkpwJ?EK-zR6}_i{mz>-G|GTJmKGH$80!NN z%S-h>3xUUP?ni(RsWIz$^VW0yQC#H#6ODf5(z}+M`9o}Xqs`AX!@@T|?{I|vlht4$ zR{nRsvDLp`q?d^6gLxE9aL7e7warx;$XXO>0VVp3ow>Wz*rJYnE%}1x`}JD}>b4Tc zPfZ1Eq>hDb)~U&s0U$BT_V_-=zbUjaB^p^&A0&mRuYr2|>D;*K zQLxpovnA_aFqV^+_KjS$Abl?4cJNw*$Z}si+^I`a*)r_Emp_oLPBrt&YXgI@k$U9X z3bV6gRg9_3x+59%r)2tqXyfS6Sq&E0{UCR9XdNZG4qSI3Dcsa=Z1zwYXpD7>^{D&4 z4Un+c2<5U4PxK6L)b-# zseQKEcEP~z=1VGfSsp?YJY62W?jaQQFlGkD(eD2)`E)$*LPM9ocM-F(;ra-a)F@=L=;K^G8e>VC}?oa#x z{ARsX;$Rw-!I1Hh4_~k(Dy?~W_pM)pc0nG0yipi7QoA~#PUfy@&uUAme}WwV9VYIF zc0}&3c;78*iS>q-YRE$P6`TgSr&W>#NZdL`fP@Pfgluc4nk&UjtBw;!D?#k|hI9=$8~4)Evh?K4^XM=YDJsio zM`LgwETOSr%{R=Ed7E8vtiJguIlXMJ8NMg0k6Mj#csEmRw^!Ap9VKzE2fC++_VjB^ z^o|#PlkDtPqwF@0;s$+=G3u{g5~T~xqg`PXT@0W2Goe-CVIy;+fvwIJvc}s^l1bo50deeS#`N8Z;BMOYf{j945Bi= zmJ`ltIXhX#|ARj~-jfn}#d9IMeD}@J=BYpRE2lhT7D9j{F`KT0RmJ9nTNfPrx>qLI zqtf8*fw70fur4C&;dXN%OCk$+iz5MjE_LzY-oE7|;h`Q>ut<169QS06aQk$AG+Hc+ zL~?Er=a?nVDBzB&gk!J|pMIni(Rl*rgy!oQ&9qz3(~Rn z+lNX64lj7vYHstVxX4939VZ(r)>g43kpb_mY>#qm%<4iU&C_HwKJjl23UMlGYB;Ms z(N<%5ijNDoJk4$LBrPbEqo=@ESL9JKTi4W&5Pe4TL{TU9`_q!12GbjK$M~7$GzJ_sWg}Ec;cFBU zxIvMJo{lVh0wLzC8w!2Ma$laa?l4qN ztdrpP!*#aW(Qa9GQ;6P33=`>=7J}JzQz{%s!isK6SY$&VF{4157gs>~q(CcAi;M?7 zqUY0$EivDL5o5&DR89_ZnI5Ho^Jf#W?c`5&Glo+e?Jqj3(YwswXKld^D{uj(kiybQi_c+(``@m7B^ zi#0D<{CDcH(k2hOy_e2x7xz0fTG~(^equ`CGl~Rikmr8nlwP$tnw?!Pz?HoKe39kA zRkbBhWOd`?thK5NBV2Cegpr!gP!shKFgzb-KsVCXkGLX~?H<8$F)kqsPzuG4{}@8N z3O6m5Y0%Em#A66&K_A7+$V;J5E6Z)kjtcI6zQgO9S5lA*pQE9SJepNZwp0m~T`OKc z0o?!qdjLvK=jH~ShsB1oLpV+6E{`FY3=3P?TvH)=z3FZ{#s4 z0TvkH&zOgvf44QHG%zBWIx{u=8pDmRG|!E2`;z|z{>$%y4LZ&}_|%eKvYkID1PTUR z>Sw88Pm8tDI~2ZA2qSX31z%LN_{G>fz2ZLqO%G>DfVayo5abSx=E?&nH;__UV5D(< zmZ-?tnxH~W7J9YDETNdM+2%SwO~Gz&COrtLZ^;H9+hCf~t5Z084-NOTo-+l_0(Fj$ zgJ+A&W6n{lh3?`ft&I!+Z&O+%&D`X%SrZcXpGXir`@;up4WQ@3D`n__Q|?Ekr^VUd z2`+)jmz4R%HoWkhdmdOR)4z@)IXC8mcVWbSgx-2#LrJB*wdq_?s5%kRCxy7DcvA$q zQp4b@`I+X=3HCbMjB(;>ST3Ra_s+h0Fk(iXzrhct_C96-U;coW7V$?&nu{?*T3={8 z8#Ukgx^uesLPG?V2(ju!C#$G+PVr7=H6ndtVxo5U=jo7_!|vq1UZQH%yKE~JDb}v^ z4$kGAhs)=MCT>_YZ$x9O#-r)T{G#>^?enXSoj7(yzBHEt-$MHnXPkE%nS9&R6Kz2x znZxt$iyh!-?zc#K`}?Bh;cm6!?zb+r`1;p)W|dU#SQa?Y`4>PJy#v>k)RTTPWuDraxe{6}hp#*PsgWrHV9I(x( zz%||p#uJ(S(j!V%$yZFt`89@xtU9i~GQ{sRR|bE2SZzs58GX;F&vf*2S_J3hN)(*S z%%GVCP_) zi+IHXN2D;@)sLJ)4?fi1=UoqHt~6hVpoFrITZs7r)zvbrUHvk~-rabZwF1JOVO=wh zG1BCEB+AR6`)A>+9?K%g3lZ#b?M01qMyJhQE7c@$rP3KtJ%M?@c7T_n8#dv^9NTPnGG6@>OHDmd~{pB_)Tu_U5@?I%*| z!cR2IW@7__unU`P9jCIHFEUnSB+yevyOc&<}<|8@!!GnxYw!luC z0`!u_zYzw9i*H1qRsnA3TjOd-jqi%v#XL5?2-^Ma{CtXIdL3c?^KvDe!>IlfXrZx6_v}u239fR*CSq$b&j7X#bPiT? zz_3&MH8{g?Efz0iv+>dBLJrYZ8duQ;zU@y7Ir>CGiIwcXu)LndYP%)=+@y(GX;`&i%krSAOULq^Ft%Sr**=#A}G?6?dHc(ntUAr(E`Qa?_jNo zLk2uHV5gh8wC6koix#u00-Y(G*PTJP+shJF7n!G}44{;+{KtZy$ZyMP3?ls)8g1xW zxU51T42pd~;1R$<@f4PBsumd!jU0?!yT{!^bOorRHwcw8`*@k=*i6i+CxT8(4uFfa z?5bXuiIV}`Jx$JR1i1!b_6KrcFa)RIJ(|SrG7iwCH23`2*4B;ZGgLD9!_@pvw17&Q zy}K1GNxzW{F(vv6zL(sCj(vfi8uH#Z-;J{C_u9Gq$}SF2sOe^>gHu%K71gVMe?Qz? zGTih{J8kvD(%j{*9^c4`PVRmppV^u9@R1@Sxg8@~9Bf)d10O6n#BbFXJa4EL46EV* z0U$1MLkC;``zM;)r4ZEwrS%r)VUdfRFW9NkDGDpko~%2ifMcb(xp}1$Hhbxa@)A=T z)=A->%ck?HPQQ|+r~6x-#j+6n@9v9LpI`Og!rDLQ5U3N@cE^rEmrW8BQuD@&>pvt! z*b$F`WziTJ4AUl6aUd|NoPq_RS!04{bXp`Ahtt8$iEbvXB@x<6T*%+K>Z_Po#S!iz zJO}{sm!N3rQ;Nbj8}jO$Z@bUSSKp;7{tx=)`M&Xuv@|l7Di+RAy5MOM_$t{)w*OZq z`COL?95@R3)6+Gdr%XJ2M^{9LBS2e?eUQ^J_soUo9k4e76Eey}oQM(09ez zJ(Ga13{?D=^B+AbQmf!^jND4M-wBM0$stN{p+g!n;3^_}naTa?I~9nA%Wk9`#;X)e z|Fk9mzHn}$9?5Z+-w958=bXz8)VcCMs{A^hzY$+Im#eFt=-sd8&??ss4fq6l(ec5# z#R4DshiFtxUlEX%i!H9Bgwhx5|H(hU8*Ja9gd41;~ z1qVEzb0z%vo9E}hD!)4L*igbwb;fQ?SxF(H@ND{-!Z*~Mny3|JK5=(}bB>R*?EfSj zP>ILEN*WXi-fpYmd>k0yL`=dM5l2{^2k9~P=bOKs#)P#kyp!WC?PEV8{9sj ze4EsgzD`Rah93+%n8k=!?{$*DFvX({$e=UO*=lOb-o3uJs{MxkW#{zl1D?S|0K!WF zU3yftg!+3scaAn^)n;Z5NWl{*FB&UpX)%BW*oQ~oG1$!Sd@lxqla>}iWMt&aQV+AP zLWr~zKO+Q{uu@XTBE7mlKgrKa9fSQ6Wq3A+Wrb@OeSj)0`^VnMTQYM(5kMPbn@N2{UB=qypX#hayOzwbNQEBh4(=2q@p_Mo+QrY~x6cG_-1lr0}0 zmap(fC~?5s9mlom(ffug{%|$y42tL-H}~BgSB~W!d*=P$?M;u~u8_QZ>9=uGa-hmI z9_~Bbfgvi&m8V_RN5VcGg`6F&5(<%pxG)G3X@eab2njH#Yxq3#`?Tu`9LT`EcGV&d zN*JTe2%gdfr+ll;PjO-E$ME-jQew*Exx=5DMlLh?u7G-6s zZW^olc(RWy?_p!dXE*yzTtQM#=DAlyyKon)DwUtXgG7DZLKmikNBQFhj;cUTrPmvvp-xc5(lfPRzA5cexuv z6lcoW^Z`-X8j8k1DEo6U5UwVfNCX_%mhVX$X-hG(5P=_c)vQ3vr3>$idk&Z>#MC|k z@lAne5wEQRGdGkw6je&%o)Y)DDW%?vq5uyL(&ssmRGrz!?buyCj<&%#G;gxim+Due za$WVsSe35HpV$JhvDb`vso6<#JMHKQ=8@6)PaLyUkJ0wc$ zohU=7MIdE;E=j%yV`wLd9XI>3*cm(#hrBg(QBPyMH-hdt%T5-o^0Lf@3 zl|z!%i9sS+WLs7cwlBacb49W#K%2rTo+i%MWNdK^o2Fj8cyHZ1rkO>jjU`$VQLqcR zA%Yn@e1n}$`AX}Y{jP_pLiS&4VI6{v?6Of55?_);+$u{L@MO( z#uc83cX$!vjjv!Nj7jzyR4J?Cpdx1(RjF919bz;r%n6KJ4f)xf7Pzkc6)B>4nVMOa zW=$&cIrFTf{tOX~b^hTMkf0!r^R81MKLc?)_}gXAXXOMUg3dk0?p2`tyvFA0x3qlp zhbBX4EmKd`@g450YhMxvdKYih2kE6;7X09XTsH7a=k}zzKD?);MV0ay2IHzy5K@;@ z7?`?zxZd4FfmXK0Anm%(%M7#J{Q3%&yF1p0TknSTn_yeQS=avx$pjED1o0Bo1rl0} zqQDyEG@r{i%(N=Bw5Uk)(~8JbIjXn2m_PraLS(Zmeo*vR%dCYI#J^$e%TtZ0Uu9Cn zf2L;XtV`|nBi@!Q$dEOse`HjbzN{pIazRNjo{d>$Rk!4&-EG^yx?@9cb|PVs8`9ZH z1&8upi*TlsdFH8;D~1Bh^Aqf4>0h5Qh>ylfDxCIW<&Q?PsLe-LWYa&+p&8xJ^fQAl zD_3{mz;Zmb9Q;cqi)Y5&UkwI*hN&re@vNTeK-U2E$!Aqt(u8kvV(^t-_c(sETW&w_ z;*2s2ml`0MW73!l-P9KQsZbqAe4}fPU`n5K{SpXn)`lG$p<&;j(A@rFsM!yNjFa@zAUTY=*iFe6Fyt^y9#O0$5gz zcUFsXqn6<8<@nUP+x(qxhRb(hhD7Dp?IgVge1K{HeS|LFj+U~S+5YaS3lb)!IU2qt zx}pv@L9oZ$K$%#=(>f5FLr?a(NoD8pUNCFVM2SoFqGhJ!$tpKWDQ}_Q&uGT=`p!Se z<8;X_KmMIY^rl^8ipuMV`k>r+-gcq#vm&3{>P2*G8{Vl^P2C5+9~rG5E0a7>{gIhe z(tE!bYt2-n3Fs6V*gJu-?$24z?+*#~@GK3B|7=msMPr^_SD zcR=#EUBT&|d5CJSf9Zh)oLawekc=c`biYj{jGztel?S?C#RgCn|2$rJzTmU_;^#q` zIZONm;}}{{V0o?$df<`=brcOu7QJralduolS#BY%q7&?<@nYC6P3WxcjC~Qd*b%jn zz)Wr0ZjW-bE^YYy=IrsAIQEzn1|mOL#E}Ww3URfb;5QwLhl5(>FnMavfBmY1k&CF( zN0b!9;0Z+So6p;&NjB^llaH$!t0C~r7^oUQM9-?_1|(L+YlWw-7SZ2j+G z1m&bk`CJcH&mh&_I#v6_e~1k-k!=juNp5m z{QjN?@H1K9N2YIKu7t_MB$ZT2w7ACtegjn}qFg%nuco7*r{8{Jl=C8)XK1&{I^D zxIekvkkF=K7_R#$E$3xUs;RC^iA`&nBNvf=*!B~k(hh=a1lP#a)Q|07$eUS>j;jSf zyq%jP$OWT}vcr$%4EwCra*c+q+=jk2K< zbkrEynNNjQXwsvTE@znQy}vMI&y3mDwt;~;?B;NIr!aFlXf{~kLi%!RDM!tyGrf7U z66mM}Dj5TRCn%D6oXH>GrL$B4lt{99w+aNJt2C8F4hiCg_=$Gy4HBWb(2<>l0haXcb4kkm*Ye=HH9_Uwemo2n74E<|LL;z6~M*nOenK#o# z_;ezdnYqPpSj4z=raJtU7Sqv=H+#w}U-DtGBW8Pwot6jXrN;ok{mtPfxK6KvOwMBi z!5)vd;Nru=1up=btyciDSKj!>zzl}*OPe4l5GBDQ6r6D2fp3T5Jd9{7*lf6L(G9P1 zq@?I~1N~XEc=t|Gz%@YM-Fd9*hCj%wH)|4B*8&?GC9>evy3#@vX`)o+vY`15R`5Ywo{dMj*7 zu4_Nqh#;syOOKSd_YL3S&#HfWuv`OSM#YutlJb?1#Vc(2bPs$ki5rg3ht7cagLQ84 z__;LT(N^=W0|^v#I7i_p2?tv)%a-d5lbW3%`DDJ|?t;y46Go(xwT8=M zbO>eXK6216GNve~+aJn|t9B0?3@|TT)13r6+8W&tysNkZhBEi%jQm4xt079zQ3{F- zW|M{O*lrFbvZfY2B9}W1e~2C(A-lgx74nSEOGzh{#Y<(&ErGM7$Dq=GG;Wn3XLfVP z`QkUm{+cae?QY_*#`FrE-xxVivACS#9|$dd1t>Af3P2*ZZJ?FImBG`=ml{*~*t^nI zYFLY;3ZLFBefZ{g%YmKpweuKh;qRX>`(ba$@jd(kS3~roqSvp1jJ_M<;g`NnoYmgH zjvim2vUCY>h!wu)OjEj@$D)M#atVxtWXHae3R1e(HnyEOjFS%25d|z5O&x#it^BtO zP`F-Q9etcX&rl&12(YMlVYZT|SifIpJ9EIz1kKSPQ=8T*Sv0k7M-Jq@Y1-tYwI9V zt}iom6#QlZ1%v08)lgCjiK7pyNXv}OUJ$Ud=&hpH1^!Vi23QP#JcvIOe< zC+j=bZp3xEa`ZR=p+we79>td^q*%UVX+wr}M0V^bMzV-=JW`oJsAIk)!On-)qUGI~uD(lKl3v4F^q1zxKidrxxuk57%)OPhjys?_|U;U)=3{9PLr`=ZGgKPgkr7*|!PedSpTdN?nclp@?f%BfyZ!y6ks4`x zwlQ>t=bO302$Y_Dp&QPn?u#f|9T=x*1Y*K6+SIhonXt@rHAU*lhY zTzT5VXaB}=l+wGXN+ksG*qn75Q$0v0OwrrpnntkZcHeTw8nVdIrXt=Ip(8koP>8s| z<)^CF@9w!AzeVyZvoSsrzuOvl{|BqZbDf{n>9AFK-s=2>DV>Vt*+Q)2iu;+$53_Hg zM2N;Kb_3G;wdUvD1(r=i(Ri`%;xfKV>`0h4K$m9L{RMMKX0>yTP zcgfF-&HZ;iabu`XN~M&{d_v^V_GzmAq-*?jM+05)!Znl$J%DO!VFXLEs04hjJSPql zKe~oOzf91pNad6i?zWwB)i0Gc9n{xU``%znAwi%ytm87k&GKQH)@;sM+RmT3bh zT3s1_I5cOJ;IyQonK2*T|Gog!ZX_Ugx%2579S3;>He0MICH~Si=ap&Df>Eqee#8e| zb)xJc3P6>IL!1{MB_D2u{J81FFBXQNNHzhOkmA6In+^;~0-U9ttSw%D?d|L=fD85C z!E|TPVpDV#--YE6YUI@9o~g6d+X&p^-+zesRom2|n5uiSD|cM>_!IPO@Rd7S1hIkC znRc^(Z(LwD>-(x_fixuMsRc3WM1*9v5}jv^91`Y(e_bQU7JC1%5*!MS@1*Qb?Z3Oe z)F?Ij5f;7?T|wk5P3p7Pytwf5YA21-zx~+gJf;6~a;mipq{h1iOs+L&YfY|xi!o=q zj6G=@{wqf9E$`FEaEoKAi4?0_PGG{BO zF{Rs_;Ye*Tsl*sF3gl&TP6ZI{h~>ryt;Ovs@4Agk0H<_JC6+tL`aLf!XIB`G$U&@l z>IP9Fha(Ie*HP~LpaM2_Wh>b1?236nFixXvRc50FCHII)>U*cO?xp=d}iOsy<`) zg&>5rUR@Vd_iYe|@?|D7deM#q7ksl-Ga-}2{}t21lwA9t`B5zABh35mGx zt!>aOM&zLCbi8&dwNAyPc@_6E8uu`XQNd?PWo`_iP2_ zIlY>cMD#^%&>C9(xFDC?R@;P?<3CPguOp<)(J;Yy+_}XU3UPtbW%t!K=dZ}>z3u&5 zyPM405*f>2SfP{_c35H5l-W=YDc-b-h46EOIGm^T_o;7y4M!x+ zk{7+pj3cG(EZ&>lI;vK#K(-N_rwy~fdk9-J(d!e4W-%Tgb&17cxh)A?_2Nx{STlVP z!~k=HH4`^}yNtGmwmG9cbtliOfYLXEHHhnF6!E~No3|<-NsKvgdm@UwqNzfk1VIy) zIQw}MoEoh9H(ppBia8uIoA~Yvy!BsoJeJw0HOi}smxWI7yUc1%!d1sgYi=vqPdx|^=I?J*x zdv_8v$xv1!Hupb$wQms%1pU?4DhlTD!Ue1wlZ{9(Too~)vQWYSbDMj~LX)E}3~D0L z+67PMRbaADvhEj}zck-VUy2;#(~PBUF$7=?i6lj5_=tW6Q%x6dYFgUWVA+q89*O%{ z72(s`+Ff0)&`__q0!8}RZ=CUY4Lr)e#=$DaVuOQ`|JI$sXEkayS|o8J(Xu<5LRr`S z<>@Akg7OCpiH3Dzh`yA@#N{3P6uJpRENz*bk>~zPvYLlumV9hMmo-m!EffSk1#9=u zuMyTUiaWHQX*yroY6KF>N(rziuEgkwnJWfFm^k`2dYyV?GHZW!OfrgP%t2*~3g7oC zst)A*vWp_rBDAj@7g(&69Nb=iysFm(V^46p@@{BppW|VWKb}BYG?mffQ)_)-nz}o` zYI{56Z>W+k6xnppn6N+VUj2U5^x$FqF5PEE5%?VZLGbu$eggEfPTl)VrdUOii?|uR zpsCO-A4%HH1%bMQA^YnSPmaPJWg`E2&O~E?8v=qhOM>#sRK8Q>hxM-X($on_Tq#tj zg%0$6ez($VhJynp{B|9>1f{sa$yh~<6)(Xw#S`8kcM;p{#t)rz3)PfBtCta zUQO(5J$&Yd()jtjb!_6=y<@E}9%SvLHTeDRPqQ4)Uu}K_J+hUsRk`lyw4?SroLgAI zzFu^S<6C`U>#;fYo=YBvzC3);yb}5Nu>|WbxgWI}97*rr+nSHkVKkhxPvHkY0Vt=Z zJX4B4&k+SY4hKdpA19!fs~h9B&KSNHAs2NnW?STqoTz7w@xqGjAm5%puj1-C6p+3w(^c^y_FGI_Vhqk{9uKjtB6DE z9aD);`3hf>UofDT3pig{akZX0>%Mhdb?l*%mzEZj!E4#nU?T!9g|Yc@RW&uPE=|Y( z+?5ES<*Vvdfw(zF2n3QHo128=eAp`;*d7IAAoV9o?;pi%)sS#$Z+g0)#hOgT+QGm$ z#+Cs*q6{fYaed~ixEq9h$z~Q?jme~nE419|YZF<>q@5{QE${6E?}+6lZVU&Tl;B$q zdWxSsRB9=RpTZ)S7RKk#PPN{MSqy=8hL<2LuF3Q!qa7LNHnz&FJLlWS4p*8N{W&;T$K$#9+GeZ9-iF%>N*CnY&phHN|_#S1cb@U9$gnt!4^Kh8xdbrtlChlyUn zko^ul{Zwn$8l)2FS~f1S1Xn5=T0%De>gCh_zVwa7x5iYAxJPL2(?(pGr^@wVZ-JL^ zb|xyDLbI+VTY*sYrSEao++D^8QbAYp`Hb1^4~yc{Q*F5S6nY=;&V+s~gx=Wk!lxmM zqRlm5zVKSVF4_wI?_$wk0!*wH0Bp9DT2ir*nDr2$!60{XUY$RX#`gm_PcZyjeXdTp z(*`-en(;Q37k`f=?@Djp__o{VaVR2K(Q^MB`0@A`uQy&kWSw~#WaDc)`zQ4`I=#%FQ>7|8*FnmioaG-WryO3YUBwyMyPfn{>^f9QnC-b zu8vr=P8OpF*f2;L{onCR1v194PgkSl!?-%V)lSH<^u~cehN7AL@--cb z|800p)@9e!pk`GB5s7x@;Us4wH$KEw|KMUH1|n&m07>B{q}Ia21EWiO^&+F$nGXE71FGtpkw=qMK}6sdD%1kF`%Q`_e{Lih(mSdIit zn;-<9#F?g=Np@0n?R78Or$0d8QUNS7P$)g5ojWgPH*%lRM{4n2%2)98(wj@{bfqup zZQpG4L*`r}Rs`j%;0%!;*ypv6m_a|((&v*;LcX|^Lt=La<$GqHy**T=wGM0ZgFk53 zFF$w0Z$4<;WzqTl^LWTmB~3W;R81%<&EY`|^yFS$vsbjXn9prh`D>duZyr;~43yaz<(SKB1+!mKhqHoYj;&nrJT2_A_LNKGCfTnW#jb-5-TIyLmZht??w~W-51!G1nk#GXu{O z&9$58inZUlme}W-err`13*LNww|Zc1Xk$z=8USY~JNRXZB_6KS8jjk-he3&q|J^R& zFWP*ss|$djTg_IpCc*(ebZdVwmW!y0o%n4!-qy{Nmc#C!Y!o1;M};x#=x8^}g1gg3 zD~NZ7#sHgSJ%G|%=_bn3<@U0rmYZ$0N3+3_A#v@ueAcOXd}J{6RFz43dwyvWQ*PDB zLx)bO2!vgjZtiekcCP?o5V1fw9_+g@^tW7X)|0B$Mh*;zk{wd+f=h+!2)kJd;EPxp z_(Hl&pQ01(jZ!5)abQQ>PL#bERApu4E@^jT^9HNfEE>3RFFK=5bz%O2U77) z#ewB$r>}=EdehX<6nXtVWqkcq9syDn;_7bs}26QOf0*#C~b34T9s zq|`X}$>D}O_Xb{B6Q071hkIOY@q?pE5kfjeKTijcCH$`1W-X&LxKql~1i4MuP|<@Z zK}1pS5nD#K_rVnPfkYHV@0Ze&PiXf|tY}pgXT3uoFZpcTQDH0Qxz=rAC)UfkU#?Te zJ@!q9-IJk>qmoTJ6|1y8U~<}&Zp6S z5EX1_?S=;+<-eyAj9{<$8K+-!{%x)~qs*S%JYmBn0P6dyI^{dJ)*pfD;`&Rho5k_F zkmBi#X7X`7sZW8JMQ|0|U_v+}rgV=Aq!Y%4kCbSX9ayfAr^PC|C?7Rnw62#=8H^WH zttyxhih=k~9~#4`o)?p6{f!w@xXD{ClAPyuU?kq}e#g6{w_taBq1vo6>2MJVK-`}L z3RoI}nrOaD=zsfzT)IZ3&062lx4g6R5HOozGjx z-t7e&;Bs5l_y)~So2LIXk;bhEuQ7S^0M`2FvTjvQD^aV_#uVM|B4+D+!r^37`Z;)I`%l737C-YSv-WS zNVAroFWB({+KnP(ieQVKHtyxu{)E3mWgB0q2_z)c-*rhaM9@o3NlyvHDH05y_FC=& zsBi{I1dWc2yk5Eq)CdJuOJxhno~Txm*jC7lM+*tbhr7mK2pR?L4|lq1Me5^(lXro{fnU8_>Ea*2=t+ML?_AW)7n@^{YT zYP)8~?>=pcf{e#T$gOKVMD4|g0Tx9i8!8?E%2T zB(Nr>5VU>wrzqCvZr9|obU3AH|2&op3_L952>sWRxZkYFe{;igot9(*2p_< zYc)TaxGm^Jt1#j;gW#L<=^IVuH#CF^luV&>;Yjyf_?Rm)CH1d*idXMtTN~`5(Z6{j z;HtK-bjhXGIGGP`7L&9?)G8H{lj(rn$?fv@NtQ56EBR2G(r{TwCZ>yoE~`w%J?{V+(S0K=r^8Y*5Z;{Xw3UZ_yKdbb<0 z%LH?_wUA#Z&Frv@#%o?{`aWLJ-Z}nIFDIci^`~d5V&)T!R2#nD_O>pX5E z!)O@%^oj3ckFyv@Q-Im*bkvK`{qk@Uf=SuENcDCC>`I{U1qZ;TF~Qwqa2~x&-0S-5?^J(k(fZAl=>FJv2xQ2uKYu2udT} zAJaU@?n%M>Er*g>EFhFP~5AM-{G2QHlK* zNdsyN(-wQy|D!wCzG+EaT>L<~hCPexe{wDMHe4j9B!&t@vmSO^;ca?fr*Xa-9ev}Y z^{g3k&zq)&Sy@@HZii;DKrO9gnPiq0ef0o~N}oQ`B?H25nJ)Ryd!*`k#%ZxwRN`so z7Q}W9bw_sDFZ&xD{&+#O+ND3MzZTw- zqq6H~GG8XRtNQoL$}I&Y?@Nl%(SWdf_Q!Jd1LG>aZ;=}1;by{(^}y=1xgw|2sjbI16(9?Tk1Q79pXajHe|qdTW^prJ9_qh$BjETpmF3&e>@O!@GP?$k z_%XDm>`sG^mv2tzgydKo_A<)n;c{cdLUc6x={g- zXmlj%akI`Tl2S2kz_pm`kAQVd6qCR`-`D7(Wh_I6OrClT4)zFqn7dBgQ}Fb0Artj| znz@B&tx>VnDAdDXp>gp3U-dODzN`#=!3u8_gmMWAMj}H@w#%|3VP(&{l5Yohc`c0n z6EU8?#yAUmyRc=8TFBeLKao?m*z){F4d?GysHDVYxz^Ay7>sXB;d~Mg8jXF`Hb8?( zOgqf|s_lvv0AT0abBULiEPB-#dKHd$ursmtP4u+)4`}YVVS+^v2pieA!O&wl_{t9v`Uy>N`xAi?frxiwXJzT@s`&YhGN|1cE6}tAP zO4uu)uLTT_gq^99*ABbW)8XhZj`SKFyGOxn`lDNmYhzxw=;fbbfQ%H__^7G--Fm{< zh)#+m_&gQs?sJ}&A*Rt>UR-2aU#f4v`lO-I*pFsZw}2yK@!lYGYKw@A)l+jdR8r476B5FKi%d>6uXnnHI+@)q=fS@yCPUcgYEH@{=r)ky?MCL|v zT|la!oHQ6KYU7Nh9R|EeYZ&Qc?y-YyhxhooKaWh(whUJ0Ho5t?|DeSf;EEVEoLpT2 z=xnUocby;LiCF(Iyr2&!?dK=Vrd?@#eX?QTvyt`>DI5b{e`g3V<>^)FC-<|j`ijvV z?AoNUMM3K&LqVPCJ7$e|LW%z&$6*%Qqj_t9?FEXA3=&}PSJj0)S-0^18gF1oKmP{P-I zg_*GINbUOyTQi5{XC}kX+B6QLX=KjM&KG^|j+yoaofa4E(mCG`5#|2~jiL<9TuT(E zG({dMY+j&GBdlBj6ZN)cWrPW2+X-`abtJKT_n)84%Gs$ANR(_bOR zOH~S}B~oG$a(201$!Hos7~*brn665@qG7x3u9M#9y>~tf{f+?&SXg+3P19 zl(Tta0RC$#D8up0M5HU-NL=_;0`A_8p#^vQz{U( z{`|dPz_-$X@NfbCkuYavt^c05YYXqeDTzJ?u+E@|X?w0eueUs3m^gubpKDD|Vp|Y! zX^}2n)==ccayDm<83eM_7Dg-cfg&TtP#Q*?nWigsmLe_wc-kuf_UGckmeN5U3&*8I zHM{4MCy<~o7z%B46vQE#r%6>X*(PnHLKF0%e}Rk-CB*RB7f{43^C&hz6g4#^LoLko z_@ISP)eWR&c++YRqJJo$$F@*>{?z_m+YE7d4^UX3?Virj7pz@O%N|ay!>Bg}oM7*T+xfAI_y z=`g+)tBx;NKqNuiY9+W9eSs_e~+aEZ4y zT0Nd3q~RMhp2)xi4NCr4c@->M z`4^)o$)sD~+Udx==j%&zy`;rrf$!SjrXgPje#+_2>{pc9k0;=w&EeC{r-ie`jK9s7&kOE{|+%u<>(oHxSw(Hk$? zaQfD-QSCrkz7E;amaaQwngUcg*=A?KS?E*UW7}=J`;q9S>-9#)sayYMjU1I#SNJiI z>#2nO*bjrY`>~@H_P=;BpXg#bSbiWN4|d)PZkjLXB5_NLi_=Q_WC3>A=D*pY?Rq}h z1QMX_mO!|h)KD3HpMmQFa2VLCSnhrt1Tc)1<`3~p5RTnx+b8ZL_XHf;C^E_FgyAO3e)1nTmWl8z7ci*iwNhg-Et&as;}q%V`AS50B+OGPni( z_>uchj9@b`dY}I^CH%X?e>=QEo1$2|zP?hU6CbM&w$t=)p|qLqXpbBNwP*%Lrw{r- zQc~T1e#7MJ>$j*hubqpzYO1-9o8lV+boDCdx>&HbxqT zQ?=bzF0s+dZARXxVZ&WgEmd{i2Ja=lcxj}ts;&Gtgt1kkn5R3YpU zWiGmJ@XMfJk4wl#8^<4glo8mFJEo$Y~`)hs($DKC*baQ{=i#t zr^c0==kEX+Ro{e220sldQ=s-4#Loc7yVJrjuhYR13p@u)a%{UK~nzRj-$D6WbDlB?*%~ajmk|>SZ_}RJi3bg?cw63+Uf+Yg*ug%s9Sdh#))vzQehPz`fYu zMh@mk6d!tV`KLc*7;fBulV?5mKv%q$Ff`<=jzj2F=5{XLxjR!~LpI-cYo|S>yVSV$ zRqExzb;4UX@F6qNC&*CCT$HKU;$AFlP`)NaVpSAxXGlR~Kp#6*U{E3NFK8*vnB8Pt$d-w_%BRxAHjjCLw@?+7vkDH=N|GLY z93IHho~AaP`_O{>?`662ISgkNOx!SWLCaA5W+L%wlfQisWh=KI;n-Nf0A@1((vQOS zvz5QfV1Gj}0FP=9H2R-yo~~oc0GAj106$!EW2#suC zvnz!D_T?o9y}3-xf$(?zcgEaVJ@VUMQdl&~-A8RZ|3!6Wm7V!*%{pKtVi;0)U-f&? zDQl>-1Un0Jh^_)h3z?yzznz(|o|#e|;Oeq#$?bHRmMNBpEaoj9<@xT~7=bN#rEXiO zf+pkXs8b-|;WDXbymQ+r72};#dQ=T*Z)zksga@|&LE0z7R{-EHy_f$O!PV^#LVL5- z-IxBAP)KS(Wb!h{cJ|NP3hm>8?nJdEwK2fPnzO6^LBj7z-bM^s6j58v)C&J5SL9re zPe@70fbkxpu4Z1`mr5#+QEAAc#V@@=MjIz#K`T>6MqBlK%6WGLimCH=5; za{_G08X8V4P0vFlMdU;(mE2ipO(`6*W_g%UXj}Qd0SDMg$fF|rEV151*jkfhcXPA{!k|nvKaornV=A$lBomc%mMU`7RTLKR z=kEPld};nB+gSB#8j5Z-pa|n zN}1^DyEKyE-7B-R-(~vVPbbE5vKA^^$fQG^^D+X0hdcm{qtY(=Q!$IZ%0&`R6XBW_ z4o~KJ5jqUnla^;TL930UlJ|zoX$FY42nhk6=PMzU9!a77Z0;;q48+7PL581xJ( zudUChlGO#4EI^`S($M{GYfPz~dv5sR6_O!B@4GXN(!&YyJCPM{%D{De`}xgSouK4@ zq=?(ctA6pe1AxTMGwJ_d1d<)OQ zbKHaJzgaqL(8Zhn$b}~Tnl~6uAZs#eT9Ew?ukVu2b{;}#We+vFB-Sb9O11b8ae4s% znV<^NAS;(()j~$b=U{v?J-EM6m)eah_K9lg+RX8>_uyajk>@HWmTk!;iC5)QTaUM6 z0sCO<*=p?FPUmwyaFNI^`L?w$`cJ6|cEG?5O4KbMJ!NV{<78ieRzc!m|wqUEJ?>$iKoJb)`CZMEw7dit^ zb2cuk-z-AJv7P1@ErKpwivJ70QOd0I5eLk> zyOExgcVyPA`JC1C&siNl5Gv+!xNRPKAe3IUxo__|wNeV3%!{0jOMP-X^r2;%#$VZo z@0rfyq(f+6y6&5?$|P?Rj_LG$+If2^DdgTbEK0=X^WZPl*;z(Iu{4-{<>7lTZp4~P zR{B?8h#%T2xQfdur4iX93JhunN>Z(1ip$TbF@;eOxZ_0s$!Md8QD4AQ{`%){rZfH) zZeGJrARvqDlNdXrI{dhc#&}pMlO*IA`o;ffa7Mz=lu)I+1m_~q$424cKm+lW$#0^`mT~x5qmYX@jirfDKp>|W-r)8aAo$U{CBzs)KNyj}uW$G}PI#KiW;XISj&xlqLHG_OEEZAG^=1FxyvPc3bS9)dc z|4eF<6d7L=phhN_sq4U|vTOs5(%#E3H#_z4pe@}+ zCpOWW%_d^g{!|C}g>654&q@1KGlTbhMIHv$_S^ao_XCy}!+xASy8nAz1usmXfS+re z|Np^rpNM2S*{{|UH0&SznL&3}lKVhlAm#6&n$`r){an8ofE>Gfde(wO(P8_e7=Q(X zmf;-mP3L5S-s(5YgM>8<$;-*&qgqfy9RD>DLLW;jpKc*CM!ZPv!XtZr9fO)q?p5&A zT!CR$?Gh9o66CDLdg_zE`vfM11)G}&48_oiI`3jBs20O0U<+8Dn)MNV9WDjavF;&NAe|q5ntEWVYzY!xjDdt0i zGYCq(@!Tf?>DE*x70cn-s&684K6g8%`6P9|qog2Dei@*pVgbZct#_+NnJt%#_H$p6 z#@uSyg>l@yYGP$lh;q=YJVefCZTk-SVh8*4gUN3`o&-?+JwWfRLWU%>5Gpdm^x0hQ zx1_S zN;YYZZnHbfKM=f8>rJfx*8I}M-tJ!DUGd}9N$>4QP81x|!$&&YLGPoY#m&tL02i#E zqCkraNhJIzC6?FxKE#(f&cEAlJX~%DK#Dt<7bN@$bJ7>W%P#Asv5!(-04vliwxNxY zo^n@yqrh#GqMZH3^cLk!7Ht;KYxie#CTI`UlSlQGy;9&@U9ArNY8TuWNSVv z!JH7@&`IcKy3UCEE5+Ek#cLTSrZ!X=aaGYSXYyKoT=}NdO3kYrUc&j;^I4oi_%GVY#D8J z!lsfDOsUtjB4=N_1^#wiw*m^}9T<0*4W=+u>ehsUv;0LKKkgLIuO_$WO$OD}9sN0( zFqm#VSc{K9?4xJu%h{D^s}&|zP0JN+(`x0?U-ycQPLc$u}8C_rd-8s*DEe4rByH`5#<9`Num?#T+K&EUbwN~4uj2<4JQ z@G4p;?PI7*w{Ppg@;V1LfMw@HMsMQ%5ur>kCT$_}+jtr7Div(7dgN}cgDC5FJpmaQ zG(a&`7LxIDqT*1&_O7XuB$OGDCMoCHn>{kMlH>1=yK;} z^^U)~n$O8VotU%ruOw&NIv6IA?QCx^Z)AKRAcoN&Kit~MXM;N=4}`YaOt_GPRe|;@ z>mk@u@8tqJLwXAFWuVUdZeSoCT=IUuWIz0FE9ij<^v3DI@Tvm_IWi+b2gMZjwud@0ftzhJ zfr~k_tZ!T7?uI!#C=YBQNBPC&q)}9!0*WN<=_x(`7%X6_AT)=VXeW}5pmWjo8IaBH z$d5GA>hSE0?;zW^x~vWXKe*ao?9K4g#gnuW_Q95TD)GFrzzYoDX20#h^M4vFv$b2K zZ1`!%{bg;@k63eVb+S>Q;waW&bfzFjBns~wM~iEl&0Nui{)i=Ssbtc$8crN8k4$So{I^?e{0S|3zl+*x$0lG4pZf3aa)-C678^)FK4w09 z7Gn;Le=mGJ$eVFGSzX=Da#5IN^R`xq>amSunBWg+kR|*xZ3OB2?_}GNhiQXWIt6NM5>w5E+ewuR6S= z6yC#7F%l`Adoew2XNpq0t$L2AcckLS!tGZZue?`!GyW5HWUp?!Va?leTZte(8B`7Q z1yQ1W(x4V1sRa*3dV;d-`m(Aja41!;6MvboEm6rG-JM-5;L|osP7u1qN;BqRAk@+< zJ-#-;$Jw&aUGgqhku$@r7fMu?EejL^^$sT4=+UvCZM9Rmc48fF%@|DXv}9aL&d44I zQwSdQ2#MA2|9pr2Rx=Nsk$m!2BUuW!x>|J8pq%RKSq6g(;2-17pM$9nFtn4A0@QgI zT*Y4Z8+1y{lT^phgW=B~QIYGBZ_@~V=S80_*N5vZW5!haIOK1ZqpOWC63jX~F|Do3 z_+uKUTs|%Brkh08k|@p9N9!h;`;>Lu81+mT_PbtZbz5_OuL&5+FCGv6&MP!|hviy^ zdogvJ@s?1gCeEPKrD}F}e*0=IaVH(ajRsfLS-h!DB(h-b*3{fg zn6sIEeUpH8Rto+)`$mwVme6WRI&fr-Xkoy>2y8E?3H_PJhz+Wn-3g|~kHe@FZj(?{ zHKD6ybzfc7%wwPyMcbs2COt^4v^rn=&Og#mXDZV48@eex6)pJYzJnoK3XM}qui@ih zNZ}3bIBdDCqE(bEEj6w&8%_Ft-`>TA1#et+6SEq9z@`I||X(??Ddj1?^o?caQUN5PcCtu#MP@zJ|h2ZYmWc6pJN$Yr#}& zC{07;rTeiVRsRbYKFGVNj%Pk~^IvR8BjIL@1eprS&okc@%QO7rAAn(&mJkE^+*DSh zA48l35kwa&Mz;=4(#4th54Wm7)$Po5@>f1o!pqOphtqxUcAteUpe}qvCHPasEUiw+ znsx#%@yEXxe?|6L=~No@MOYbvy~EG711}x$zczmvRskp7FMiDESkf}6dVeWKU1*gu zNDqTinr3f4r+jf`x>CedR(=@HswxRxjV&&5$NOfA@Bl?Qgva*bVI&%OkJ5tEsw~*5 zfq!Qp=xI}cIhWG>etdF?EQTN>B3`=X{+B4yaDetGaU2|Dahhp{~?^h zs%I&Pz=<4xFX@Xmi0Y}y_aj9Gt>A^cBy|C?ro9k}^0&?(Wx9r?`8%h#Yr<~yU^o}F z-!{mKBz}#@uaG`AlI64Ma|q;%G7L7^;dyc@QgpxoE;>qx`4JDr3?7( zOpphhP0$6r3s|??ob7HpjR-1rOX=yl6B(RV`I7ERV*RqUWw1t5c$Rz| zSzu@TK6F?RpwZ`AeKbFwEdz*Oq=_0k;Xj8k@EJm;itHPL?NymjhP$VEk9nv{UrYZN zczpX`kJB*n6%tSpsF%;_)^o65O9U6NPJc;#`h*mDK;Be?LjgGiaN_6kqHA34pY*?= z-HiO5y(?9kL?lIm_SUA!6n}_2MvGwVG6@emTa)FR^UBj9mD_QMaN=*lsMUFfF6#aL zQ4jT0`4v4ryTiu|d8*o=G9hrW1YKru4m!Q{JKCtzF1|GM^Y&)^j z_}*CJRK?;aE))&yu^<|{dr;I+9c3T}s&3E@gekVeFDZZ&r4RhhYN}`}?8(cofz)!d}BLCtfJDbhn$=0ZzOa%qjO+GrufkQs5O_+j^9J@k#L<<4aB!rlD)xmpXh z{QI*R9)6z5sd>654in89>K0luy~^|?pfss6sv?k}Db*TGHa9dpz%)RXj#>mevP(|BAwQ))`fU8UkAfVPXm z5wDP$pjZRc*~8%lcF7~u7$5j}>V{mB2?b5JQJA61y##C{zq7w5Ng>muu$%0X5+uDN z84>lSd2u0v*M%4H#Q#yOmq$nY#_eqf456cWI4?FC<=9iv)Ra|HVhKKL6u_$>0Q?j9 zd=85vI&F6rZTF*2hv0o4u(tx{5PQpiJm;%0vT*#xyVwayNJzf4S0~!P`}`8j(DJsH zg-lH?-oH$KvvfRM2$+@$wMU%$y(36dUFJ;40qo1Xzq)M;f#Ug^TfH7N0 zMJSCnSvgrgx~>3bGsB^H=PYjUo|I`L9&ZZI{glY z!$$sqMrLHq;KS^vMvy?6mBba9*k>qC^R7N>(c$Qg?Pgnet#Y}2fwX>Y5}vpo?Udk? zC&5n?q$RYlCU|l+dKpvS6=f=neC~Svd~_{ZM((r&Fse?++6Oi=j1<9k&k6nk;8x;# zpkk3GrX+OdK7NNX0fx^;Ra9C*4#Ji%-^a zLZ;z4KWBe|F=Dbs#l&})qyDuH##HaJ+?Zq0f)0)KLlB1O)tnY1-GUPgHaRyZV0Lxh zJ&vs2V1;Ry#HZ-iL1?I*Jnk3!aN zjch%*}oayJ;5UR&Yxz$P#Hg zN!)KYrU{^G<(iDzrz(8OuKV`=d$Ru-i2iu80jCw}<)RyI6jk6A%F_MArIXlhS<(7R zCdw<@N{s7IPr`642Z=EOWtDvxmQ83s+*ccZ`zmlQk!~TpjkV+Q4_W}1GP4*vpTm_9 zm!-B%HY2TlN+>K(k)c9jxP*mKFA~2AX@(|CLD`L1pEWVqSzc%3cEXt&Lm!?ZUF62r ztcv}7sSh=ti%=7?suIU;GXJwgWsg6=^@8%7PPNaGsAtX_GK8D=$uFj?*8!;glr45- zC*tL}0Zh@oj`bErHjI0-Re-9X!I^fiy zEtWLh)ckxH{b2XPi!RDNA4-YoRzb%zJPH3Jkd4IgN zClNWK7u&>m6jQgJPPQ?8E`hDB?Z9{*M?pn0RnlO|>gbQvWY?27jCHjReq@*8f30u? z*NrX5vPR8RMLIi{gXPr|O$k|vl1mPoC{x%0@jgo#%A(2WcJ{j8dBLUsb>N*h{TIxB zRcpP2=PL_b&QDO5ydv_HL%VUsKba+pdVU$JNz}6Gr;;oB6IK(zFq|OzDSP2F`MQVE zxumShr>M$Ix_gcXO)Wg+){Eb4B$2>_#u0SC)iRnbBPKkMWtA@_|F+l^`?cTGao+gz zJ;cPXiFYOSc^dT@_D;kS%mr*T7D`{M*010MMn$2y(@X===)AR(ZUJDjt`5lX2qt7L zLFr@*#bWMqE$-%gjOVTsuFSf8*HD>3&l>U?#%aR;&;~X!K!jgKNbd(tlnL_*7E!V9 z+G%JKl;e{XD^f{GGq7I!{qZ1gyLp9Bt8YyfGobr$d+7HBd@=L3wBg|1ZM53F2Vc9q zTx2u!ytWW;dbrth5?l#a9S9n&W|g+<0IAHI+uNNnoTRZW79G|`c$9@6h@i5j)n54& zE0=3^)K+dIi2TQ5Pmqdk6~BB-fuVAst3W0^o@q920p|_Y6m_mbszNE?_D#=1J2u>f zUf|F5_SO0ATDT_(o@(9-~O*YfA5UXaBD?n=3-y2rCR@HGhw)3YD$Iu%J7B&@5e z`(Ec@<;=wBRnLxNCKRb4Dx_>slfknwxsg^%gAtG<4p^Ir+ftF-{!@p;5>`0-j&QhB+`+H)HC z*4izj1fDTTq;BahYHekqjZl^rw4_8f55U4N5%6Ds>i-bmsWt!R`98m9tite7Ee)@N z2U?UU7R;3IZ}DZUE>ZfxYod3059gWLUNYrf-dR{=u?ajNC*MA6M9gYrqiWu()9}&h ze9!2S6h!dkS<`yBlnoGBX9y~O-!p5^{5Lt`;#XY#RFCLjTn^GEF)$nk9CUxXbK8qg z4a9ARru}_h*7kaF|NW}#<_%mtpy1AxGDXPJeB&hUpnIZIwDIG3`?kekX zzJN|Cm;#Y`Y7_mjikY>URlUYwh$vQTQX0Y2`3+VZ(Q{c)(Ur@tKv2K87WH{WGv{5w z_Kn-ArF=lpFUR8>vU&NL=~EYYjaiP*{ke{A?K(+<$O$uuG-$zFcNN6~&P$o@=iBe+ z4S{N9Qo_x0?7y3EJl1qzeWcGJQX4nmQ!OBALCW1WneVL0wKlbo6K|mFOVfP@_4wYd z`HW5`$yV>>e^wynCA;qaXZ$rb-P5padX3e7b5?MeAdHTX4h?64@BRL317TN14=pPo zuoK5S?D!0O#P$ju$8jO+-W~IDMZv%nHevqWdn|11Y`mOP3iiebhxr1BQ@-r?vZobB z4^Vf;?s)N*WUBjZIl6%D$MQWXULD}(7~U$YDlc}EV*=s-&-L}`Art{T-+Ail>*^*Z z7CZC&e$u5WPR`8qf;o8id$3OB%;+BXa93f<9UT8Hl)f`%rDkN5=x9x-h=TeY6=*1C zYu3Q!_a9$Ag$0HFza_7vq%vJTpgmU36qv{t52{uP3kVRJDrGB|mel5*At5KxA|oUF z5*aBA&;x>KPX%e|Kn0jQ5-(ih{L+j#G5R^0*YEfJ#DA%8o=UV{CU925U<8d-<4w@@ zxGZ{*kgX|CuK6#mB%3fD63Io+Ki3~Sd}OvlnQEOY649_^7+XL_9yn*xdUi5gY1j}_ z5-AHBl!XSYWMk*@#gkX~CWy;tBhp-ie$*j_JX}tTAHYNeprGDVw_W&JIvfAxo3Fw7 zHk3B3x$~XjtIL1pRWIfvfdlO?*ty1^U0;kDnhfkOc{*RCuU$2iB95n;m=sK`1hEo! z(LUBG@cm$2bNW-)c3r*8-+s*jz#BAfo;jluQRK>?LjbmzyW66kOW@YEvzEbWI0PkP zt6^o>Jm5`i&~A^g$;Pu`g2?oq8q8L|mvakVy^rpt8EhYjMZG<@VYKC^Dm; zW{rlAf5<9fp{H^wYoL!A--u2njzs`Vm#M<1_QDBL42^_9_4@`)ENSu#;q~-*$1wG~ zgiuHg>do_;u^e8zSvs!;m*<9txp5Bv$sy_;ZAoo)Jr{lG0_MaC7y>eJF}jo5MXreZ z;;H)6GCp*&RsZnaxp0_IV1J*Mtv*_maO|J2J~}FL^0%8kXw$~^m&oYoXqK(oEOOufjuvU=+r zvDA^67f7!MT+-7s=GOLQrJ$wi&S)4f&83pePjs{yM%{C2PzjY$b>gpXKSq63>7SQy zfpgap^gcZelTc5OVst;LxWK;*d;na(j5P%R8j)vUKMI@PP z`s2)-t-tH@2bDe#6poEIBgqf%9%=04yof<7pRb=?C>y-Cpfa&9ClFJ&xh3kOM%R0Z z9BI%-xSW+0lhO5V9Z7TN5E0w<&W;2E`?U(%T28X6P+DP4K|*)+&FgZl&}?N=x+!@j zH$&v}_%rQeBfP$&gaW0{gfd17Qg4v7Wd5ydd?J&rki{Q_Y+!3|z?#ydFCi`hI60REu3a^`mMMKY|~u z&f4Kn?sQ+a>jMl~s;XGlOofiy0L}B$?V?2IY4v{4uUzPzy zQ?fiNFMb6_F6%JR4mI15(ihDbakHEtVNbnHJnyR&V(+soD}ae@_wThc6LZOu_NKDA z$YR&P*DNb+=SgQ1qb3l^^k7fpYc`tAYqeiLUl|`37WU8e243u`Rqy%77eum^IGbFV zTF2ox`G_b-IA_xt0XWJG&dt`i8Tmi-HoS;I2DBgykokXd)cy!&ZO4g8L|GA06hEg~ zG%I}MR=%oRRyM`1A=A_ElI?=+HtMy1h~MFljDNH}8_m+%c}KUodIz>%;B|IMwuqoU z^Vy$}`zgLY9??J*wD0m%CTT3DddH8smUhuTg+AOb`D-HDJ)X2~v~CL$+MOiVS&a$L z4R+yN@YR}fxA`w0tKoLA>U^AQ_Lye~xDS|1h=s72WMCr0r2?d$0k{!6S%W>* z+_kOt#^i=2AL15`K97LDM5=yc&!o;y3Gj|8c9lUhwm|9TDXUVLQqz%>3J?Vk2z@FG zRyTDPp{htE4Z%b*JwBWHuk~8J*|tY9HXXP*IOqw~uMKl&Ftav<7s%pWmBFrR>Pyl? zI+5~xHnWn&E+4L0vC!pi7o2mt%3r;`TwzWWQ{X!2I2=!2nPQ52P&NK#h=O~!gESlT zH7@{XE(%x;LglFZ;)<2hzuL~gQZKXlk5r+}r%yz&p4I*$zkhbm3?165uKu?l6XfOP z6}j$t(FiA#F+}fHtYms^A+Y*M_02|7>UbFUV6!?f>7?*X4?yZpQvU5{mmYrKzNgOclG-p#_6_~qW4F@e*4&)=FaEsFQTlx%k5kQ;FG8ZwX9;vV)+0*Oyc8;L#ywPcAeK+3xR6U(|Lgtr zWs?3y49t$pu~Pa(xkn9a4J}9DC!-_G|Ec(-R>VV4`u83OEdhVf3w#=vi7EM>K>;~X zzDc9)`bGX#j|HyC-{7U$SqVEkOwc8{TYfISTszFUret(8DNl8is1>liX}g%`=L+s} zpk^$X!&zbG)Fz?+Jv%G@CT*x6ryI zir?u=A@hh@#zLPsEmA!l6b#9fHz9`#kM3l$(y>Z>wG2p5pJ~S zY4CF7Hq4Z`LS_*lV5JMdc{tUYwyqBNk25#KU7KUF!|>g>h+#>I!s=O8uKZ;9zu}|F zE^g4(GY?)5cXxN^hti*0EsqaJ2MtSY;yNE6mBU=fGr-RdoIVFF zztIz*QwHp-=Y44V1hqImQF;ZTgPW>Y>@V8>H$PPV=*pI0SkP3C^hQ(FEuadIM$Qe! zMbOx9ot~>Hjikqbg&eCm#pCOHqYjB^zWL4kRWI`G6Jo$v(W)sQ{en!-qyG#?uQ4*4 zed$smONh4|SO2U@?pA#{U_;Y$F@tk60 zu=G<`jZy~qg0zG@cl^cRw2`cZuJ_tm{WTVPJT<}37VGTr!U5!v(5-7AJft3$j|^G$ zk)KF~?qTqo7yuuVN=`$q_n@g3#AK}`-Yd`bB*sbfdRnvH&gp2*kQ0n;SAf|%Fgjld|I9wmEY{P1c9a1ch{J5_B?Yrfmq zdpz;@DRxT^AS(YXFiCHMPQkIM)q0|E-I?DQ4;cvgFi;ArNk=vZHfjlDLyatiCA)V8 zaOyXVg^9ovk4M|H2kwgA^oJI1JD` z+xxwj^FsXkRyyYEGP74PXLt0&d+nTGujvF*qMARHEJq z2m?3lUen{Fo2L;b14C(JuG_Ruz9|F!H>92w||HN{(T0e-kw_IBN2nfii z3JBsTHpQQJ$pSRsSWwNiGV+he(qx)!E6Sk`{++E)-v3gcTSg)S>q{JYFa7pJgv5BT zC?dAQlQ!ZUh?yTu*Or3L~y7LwF9m-dfIpQluHQ(*?~!j z9nC~dQ5aw{QSjqHlFM~p)>CwnJLJg7QNpkh zdSw2j*2hVl48finSFM&?0wgy3{@!hsuATMv^5Ye8s~30Z)VdQ{YanJgFdv8Nj#RUHwh|=d#C#sCNWevT*gei{#+f7>GzQG|RdM zNs2UEADaU;s^-7$f_6GANpsN70bl8p;a9m{%Sg{J;Ck)pv9B7F{0{Fahz*>@R7H*j zz@sTL8TCMCNCh1aygx^LEBcmN|C2&FhdV3bB7uWKScox^O5DW6!2ugo3OCm^-xZfP zWgV~eP0US4n+cy?K+(tw@M(pfOYTQ|veA_YV7_EG{(0DT zVx>#U=i!<-)G9CFBKd`?P~a_KzPatceGC>6;OfX|KauhOC7tq_FW2(Eo?_&a5WY(4 z@%>lZrS$(of0n}r3NT`rti^3|MZ=et8$J#A_7q(Wm7A?$eUI7(4c zg_P~1BLsVeYwOYNnw_m3WgRb&ZK%`vk+8OJl(e^rN^QfmS;%CHxX43N`2WBoJ=>)gI$B6rL`U% zAv1H$Um0^!ME+L1aa+3$jHgr zosPD@cuX^Ei?pYlW*ELTGou54Gv9DVHOWr*V=^4~2U+t`n|QJ^!{2*d!awbdxkDot z_fH^1H&LA-NV|J`gPX2cSXf;37VO~CzOx0v_d$MpYCtUh7jVDW;alT>{-|&#)91ch zYvu&7ZD7l|)C8=-qa&b<`5@pCdMSEA;0g`)D1@%{Li)goVAEp?P&NOq|Tu zRkl%!JPOq6I5X%nUa7IBqoH#ZPPj=KQpBsMOe1De2BVWy3pxqllHFWI-tkWm9_3o> z%`Gk9F~t7hyMqEAICLp(wv-zdJ)9*BhHXv1|27g{K6X4&`^DRP(>@(kdn|YE;x#97 zwVV%f6)Ij{OyCzu4Zs2XU{y(fx_Qw1oA)Rn0PHm$v*qc(vgiE#>FK$@ZNimNtjnqi zpWENIFRl2NYrq#vuQamYfb-32w8z7ceO@v>ylsd}MY((V7fABfA+(QIV_$vVlVm2B zGrZ0V+q?dBw&TQo-_bkQMA;Wd8D?KHK>uRkI3A~fjWNLor+Zf)rAJDcnZ@1n(73Dd zrN64RdD8#Ube2(7ZfzG<0cq(5>F(|Z>1NZ2q;!WMAt~LBfV6D7OS(a&OH#VK^Ie?r zeLv3d$2sHZmS?Z$Uh|&wn)$o8F*=nZrMe~YwOz4fLAAxEyM*T2rGBsEEGl)#^Fkt_ za%|}7Dn>t59@KbSC&fzB9VL`waxtgT3f=RRf)qWK<6g6S2TrS)9B zyzxFf7*L>$g+nMBDl1Ia~rkv>J6vv`cRw9BOo8X>DtWO zbLX*!Dk}SvYQogVNqK`N;pcum#K>5_BMR*gUD$~iK?om|rEVEc*fA``nJaLa=)tB%*!1;^iPKqF}Ad+tqtRxZ8FeM zIUGiW<8XAh%h7f9BxAyIDQ8eJJLz(l%Z#Ew^8FlinYH2lCTh zN`d-~#sxjh7flJugvsOk?}XV{+Qhl^a+uA9GFWs3h7)YAf#OQkDZkYik||0Yr6L>b zgjl^?Zv8*KLJqR%U{lnDL}ZQQOipV7+E?B??i%L}r0G&0Ki2+wBQ1#=OkMRuTMO(@ z=-V%$`Iy0!`_QLckwc|PKS;{~Pf8TnS%Wg*=iH9VAO2y!-5+p+@T3O5SN1hq-{|Bp zlbnMuqu+q<1OC7UT~g2b98@!xuMFwo;o-VXrAkx$6^&Brmo2ZjdG7B9ER@4YG9*n1 z(pmt$`Sb2j@YU*%0WyCm^+^QW$0&z#PWpNwliUkIcD*%n+sK)AD~Ji`n97c1R5FNmm$q( z!3#iElt;67iajrdak~3FfSW++Bl}eD_6vv>)6;!j!Cy~$5>!C1BA)Ye7N9S!$mlE~ z`~F(yD~Wp}7jcd1hW3W@m|t!ah!ZE~4b-OUZ_LKMpQ_K@vw(el@r|yp53fTxWM`EM z5s^QfC?Sr*CC-XQ6`~Y7lXtuUSdtWJ*t5agFL~nt59eKwt}1lz=k;Dc`Y8E=1bW%4 zhg~fP%TsJE@`e*@{^>i2e~w@kZm5ZEsRxh!U+>FFD~)CSc3+aMEEg7!r$c)lhlQR- zr?uH?r!`s9%NPhyVB||Ld*0}&6%0lnXlQFIFeK%h=$>C({JRr5sxXXz6u&TGEtle2 z%ZWCy#0Z!bu}js#i8!#cQ~bt;G2>R!94y~!a=xtwJRZ{(ppKQXyczm&%BI3t`|)wF z;|aQ&VdLSzYeVWAGo#how^z~n2Q;krWqK@GRp{O=1>YStJW-Y(ks302W#CAkpe{C2 zA>0$F!(v4S*OBKms$yXdVS-j-a(s{{&x0a0L)qE*zU(z)NA%LA_v8M{jaKq86!vAH zmk^?4PBu>6ZVt(XQf*L$=T?KX+L)@5ipB)p`_B*DoGHH-F&G|=y>wf~RbD4!4t>f& zmIaN0w3UW7Gq5(=4^PvikB+Pktrs*TB=exeNl%6ooJx&{^c_A-A16I^_Ju8 zYANMeR`+|l^5fmx+x5K(9`QQ~Xx%z$#TxH96Y8u8XGew`Gr)27WYD5g_ptr;=>gA> zlDQ;c?-S&&*Uwjxo~Dvm^8D#K#dOdB2IQ!uf!C8DD4vQ~g{0Us0S!vkp~l3Zkl_W! zDSm;XAW!Ze9Hjvt8adgr)ZritD&HtxLBb^k4aU$oWEw`%aj9<)$|KR1RkNt~Lpi00i zH>e5#xA0Ii3OO4aModf)(51{~9i3bVvZBewpplJNpF%)IQ-0I+LJ6`1UW?`B%EvYV z-@^%Hsj<$l(2noV7)eLD4vIaNeZc6~x%oRonvzH2;^D|A+kj`}AJF0(+8^w)^xD34 zqX~Wk!=bt0(Qx&BWuX--L-^@w*4gIL*u(_q5?Vl$(_w<9&xEWj28_)9Rxh7kT<~iJ z2sf7!?J>-W>!!eLawT?4xx&gFWZdCrVd!GB^JFD`cqG)yjDx$jHj*6p>4!H4w$46# zR{I4oDX_vD&oU3j4;Y`ry*JrC-%(5xN@Lb{x2kfV`s3DnqkX)m@2BM8z&f1l6JC@o zDkqTiFIMu+CJ2ADU5`ql`GDPXJ%Q9)1DTKTi^8oaD4PR#NQuML;h+K3Buhd>MI^hs zo+*G0d+(U7<4kDR#s+NPf)50y$m4R0!Lkvh`@?kP4%pqEE`2@%_~sG}{_5OVMXK$C z9h&|3Bm2Sq3Cx19T5&;E=s_#+0B#|_Z&4o7DDyP19mNpT?|XrkZ_P@L`c%o_FPu}7 zuSg;)HacTYAc{c1q)U|)8-_~n#lRumZQk$xo z;|JC4lGpHqZ!Dw}qadA7DGkOFOl~b6_nvCZSXCm2Pc%lgAy^t@^y8I7U#Rz>KcnWi=& z*li{LwdC`X#Ev7Q$o#RWkbNkY%bSe!u@p8o6;r-a8+)s?e`pDk%1o~&XYk> zg?9+VPymU)BQeIW_FeRPBVzgTs7zOZ#prueRh&tcm^+&SDCssdT&zF%ghp4rz)H>x zNzC!_v`v$am-=B#=e{KsEddA~sAYs=drd6Sdn-+Elfsz|0;^`7u6gnI#LYZu$Gkbx z%+9yR05}bp(C`P|L|+;>q)}B#jzvyU(9rcvUNG>2IN6Tv-}CnNkVVK->P3msL%4(Y z84+>IxsJsV&$F`v@XYk66fyMcz5T#{yUebn@fx4_*ZA0+xQYrXSkwU4DL8tAf0BK~ zJM#q9+Xc=T!_}+QB=u`6pWhZ*aTs@f(u8!^XKvqOAvAuhk}ag^KDU|xHeM7)EhPVP za1e+Yg4CPka&5E|;@4*SGsjvkci-3`tI!IZ3r*+Rc+%!7wAPIDcib8p%U?)^fAvH` zk`hS5<$}Td3kpoNDqCNOg3P4T!x!7R!p<*FQC7{2iC)MXYp#pl>WEAX&he3E7_uBl zj)S?nls=(Pn{J)bcqgYN6{o?h-u^}p{S|z7r8VGY(GE5etO6T%%TJv!w3)8sJ;}*A z_lImKKw`P^e$S;j$JFGVY``KzkJK2W{l$rr`mqFIx0%vl*J+^o$TI*+>Mz#4Tc;-E z%>WJ0A$pFC;m1WYV3zeOLDac4i)$U>2%DoV@af{>D58}jr1yMRkUPD|4qZ&Rx3%YN zO-M-e5x=66Y>n#|e!NtSKG`sZ*SgjGfU#=o|y?{*6;Y9p% z@O7Ce0Ap0@SvTopD7fjQ0s~&mxea`eeV4u`n7Ez`uFKa{%QdB<6QBUfFbH61YLz5= zb(#zhfJ}@mVF^9_W9sFi!(B#3o+GtpC9O5aO#;z~GlvUMg^dzWhIH)6jPmP(`x?3t zOKCY{;A?{4Snr3r&^ge9ci$3AB_~Tt#S9js6G(i@$)aEN7 zAh>gIVE*C57w;;mV%2=rfv{o-ImmhyYO<`poBq`AriK$th7w#V26@iqo4$+5HJSgE zg;!M>l)z|2r#hoL@@=jqPL>J?8(Zv3oJ0SxZ>0sl{3#bz8-Ru;?T$x(duGBE!fpZC~tf*(;`eFF#eDq#2C8yZH`CssY z^Sqt+t_I%mu+d{YtKZ4+^6mbX$kiF}8KmvFHs4lN)w84whv8?~Cfh0pv8D`B`)gHZ zB8(XuOV53&2YrzzP3zJV3@4RuGjLYBX?S3vxw%mJr0Q}aiy&=un|4=uF5NW6cU)S7 z*qdyzHJD9EVIlDB>f|UA_r^aNa!!yaW)F^E`=%~AY&YZ{sX+x^e&sc)rqU=+%${pD z?;dAoUR(MLtXBM6S;Gy$Bn0+X>>v;3tX1xv<>0+W^lVz0zR1Za0cuwSK&^+%_x7C` z+76FX>*{ehRNVYZ=MOXxQCaz%8X^Zy5@4adZi}H9<|~)%g{m?nfv@U@bC^V1$K}Di z=hdRe^ZBc477YGJm@_VjtJt1mNf7yhas8{stN!fvCNFLuA0H~k1dzZq%{OYXUUck6 zT>#|h1&|*7?^jS2_g|eyS;Laa=NqHxMn1( zbk#C)+V@$1&a{)<4D)q0RX{q9E>yWgNL2ZItfM#Su=}7TTOp4)z2;6$mwur4Oj?+x z-RJFjd~0SHUlMcAS1EKhd>=a#<3xJ=CIr?ZIX@k>UNwRk_NNtpQJ3FaBEweMLP>k= zPChlc1AaR0kJZRm;6%)11K}k#CfsLH3RuG}dMBZ=r1I525{GrPsD}`0t4cYdsR#~rj(3G zQ-kK;5b?w7@<_{`-2b3NPKQ)=$9xy~6k4QaVhMT3+!oizPZ8tF>XkU@2kUm)KP}g* z3eJInt&>wxtJ~5tCwHQY!!Peh2iW_GYZ#aINxzHKUhG5*9+GKjC$iHz9c(nAH9vZKp0{b973 zJtzHs0iFK-P-&jRw2v-L*-B|bH=H9vci>ZmONfjB4@GaB?}3Qs18AlZi$_t^$TMJ3 z*U0FsxBL57FqO}K0mm2p5kZb)HS?!sP!Ew@d{3`_yjiS-_e?iw^6gvNwwC(9QaV5| z-`(A_w6-oRu8M1J){7s^7voM1`A~_E$fX1W``B4+=R7AqUG9^O!>E1yct^T2>n@jE zz)0R`sOCyVF9vZty&(n^rDUD89s_)D|k+bvHj)s+` z?aD9Ck#!K6wgA5gg&^dceN^kDQ2dn*r#T6U?AU zdxGDmMMf4EnNRN|qdMPx=1MWR;_i#G&b8H*7!&)ZO&9jX5_XonSS}wGM|*sm@$N{! z{vpYA;u=2CfVS|TX$ym~DmhNH31dkU@a)LkvOWDS$;pWWwt`TAKx^?nO(=4{0F*`Z z6hrq>aD?CJ#~4<--litA3;O(Ab;!^77QuMDLL&Yq{-kDU*Dj7A9PK8^Pnwqp^ zU`S^W#rFDn{S)Wr3r1jNxZW3XvEtPDzCfssAdcuuZOOE}Iv0EgDk_2*7ly#Vxrn~H z=)1+}auVD5`Y4bl99>?P7BG}ynHeldISjA5ktu%mkFWT{H?9OAJK1J{?}PDGBWV3tv-M<@fzF|%xn1SrSZGO{6xV? zjP^0h2{%~crIH3%e@cf19aKvds6W1Ii(Q_apO6I0YS7ds1O|4>hrd2QZr4bk2Bx%) zI@M%I#Qcn+C8`E`POwyQ;QHN+X51bIJFa44she`F2T{LfS%jPx^bjd(nQ2N(Yj7Fg zL9heJI^6deCVHK0tMrmW+%HdvNLM2w4W^8Dn&l)-DVg(R0;$GCM=SK}U2>U9u(*}H zFtIDt>8qVLkbxjx2?V+4f?Qxrrq?Rf@i)eQ)zeTS;_L=O5+@fGeo??08wbdz$-qPy zj-||(MW0YaH=La5akW0EA%exbSH1^K$kH+&X@!Ny7}&Clz>k;-mkt*xF&wTmJXLG1 zK5(yPEWtD}QD=rrQz?)wzbYp#q>zSVhbwwZjYV5EPZk3V#l(2S&X)GpW+$uE z3*Z)wjZ7UsD0T7LVq4(o=M@XEtBIl#Bs_Anu5PuA?&^>2_Jv;QZ0De_!oNjQ)zpYg zuP1UdrBUb7OBHtEXf|GHlE5RBQf3YQlE{)UZpKk4|6|vTq^WEr*l78BDItX`I;&Z$ zs)j2KuG$?_(p_x&m@0zxZT*Za>1MkXiQ8n{Ky??Or2GM&{m)51=?KuCdOw1f`UU`D zrTFoH_X_>UBBTYj8;TnVrO_5LyUS{5%gcMX21~i@?S-+yvk}n|u$3hs z-lxs{LpDq}oNNfzfxgO&S(0D2IVi?2y~up6y%^2`P?Mq~X78T;o5eov_@q+ybdDod$c7khB*d z;IY=cbkk=-3u7u$lQIxNp(%u=H8n5=B|sLCM5m|=`FQeX!jzn)rG%K^er z3${j4!6$6tg@96oy{g>r)`TFl5ou*bo+%#(%*|UapKsnfM&<^wPEB!N);D-my6xfG z&cBN{BP1jQ8XEY1a&(=-wy^1vrrn-pKPiG>$gfm(CcWCwB*yHIW4Y462bK5vaaWsH z7#zW=lxsv$cJuqQRe_g(NI>v|jg5_L`b+PtU=wydnB*RTejFyjWjrV46E77BomGgm zxJIuOd7M1?FeW0WxP~dE1&6o*ec@KtmgbFPIP`@I(s^cbxcdE=pPs@Ha-2iCL28DqNo~j%Zt`gfA(f z5m$h&;h&!q&(Uj^x9T4w^~c0>uDGAY*xZ=7G>;f2wn$;e3M2FyiZ8%GI zU6fvXR%v#H6>8v=1OUJTj$pVnCLLk_MUbPg$-_-IVS1xg9JManlO_&if{lw3NuNiS z29xSH_)aK;405oea3-$ClN7K9s^!A#>L!=$wdv?n*BW*&hDs8b>>@ehCtDBLAxSdh zP8~sHB?ERHlI06T0X9aT7KAL_6o4`X;4k?TR&Ce4tksVHjG6S^Mf~p9NM&v-kD%?) zCoPwYeo)&-^tfSUb!58+Tny`=q27EUD2&l%t~3|A+XXITZC9;FRjYGbIzL?zF=Kyk z(xnUo8tDW_eUj6f-rVO$5vKRmLB0J<7Sq3U*O5KNR^z^sZl<)~Q^UZ(>^B^V1c{?x zqOPmVF4ecT6t!fKA%MP4#w7V*9LC3+(FczuPg?M}a}{O#3fS4r?;IW$|@8@F4G~V)f0;s9dL@X7-$QfMmtXr-k^H(zTIHGDM^`$_B z&`@k7$1F^4owy9gU#Yl+gu4KNj)L+gnuPdQR?A`FMev%6&iK^WSe;CP$#3uds{VSz z&j)qJEEy4PGEvO}3C^C{pH4(S8+t50ALArImUjYcpc?BbB3VpgN8rr~j zDJ@=C5SQ9it?rPD^V2sb(f$5UqZ8zSuzL<-6W5noKq%uh_RPkyKG6jf0iS*)!bH>T8y*D z<%>&~X=kuBiaF1D%t)k?gZNB6Kj=PJi!vhFTL5gbHLk##c>+#=`?#7B{yQuei=#+g zN8uQg99bUPS_sI;+1kf?i?GsYoG?^Uy!uJPIIhEwYmYs!FW}Dok^9)^CmoGq^17u7 zbsmF64d@|jw)l|#de98Bn@f&XgGybFgJ4XtV8V(cjjNDeN2}TR`wx>#PvG2(b zKjM&t+HcR;P)gn$@>y8XRtZSjh@Pymwdvu!5vT>-pQpUvKCOmnUtC0{3kD(ww*fgc_xC>e4*6q#@3UeZB^@F3& zoy^7^wlilZx%sZ0lUTplbfd}gswwywjK2U9S2*=+_!{6L&}1<0BBP4qDlRF@Yx2a7 z`W?l^%@wOy$c{x579`iDXp#=rY2<@QZLBPMAVc~)gZJd`UPYDh;_GB4!>*s6pTYC& zaSXoX$A5rl%Vhqtm#h`fhz&3bz+4UT(jwVJ|BdKqyX7s1tF;r#rT{h{2{1f$HZvR! zOG4mS@9c}p@MW_%*xNGo!4YH0E~?2(_*2gE?BH5QUXPHV1?}d=i3)1hjS*XjW6ej+ zvN@4d$dUH=>`SYv3#puDG>YK2OH)K`HdalL70 zk}N8km=Us#*KNPUG?P}G$w!An8!QGrp^5~{r;pz@d*)P<^t6eprTZL%D)Ye!_FPoFBDZYvg?hnb&8sQsD|k>?~qNqKWTV|nB0HLLGQM7wV7_V$>Y zTb-a!G?>kif)S7y_&)Y}`muybe0sx@8ab3E^J;%DtFM$a3AO5e1Hv!&dFip zs)L3w$&jx&F_57sd`2+M%t0?zsE*ugUJUj=T&Oao6{^dtiSk(19bORjpv@TOFusS4 z7TE*~{r#5Rr=myw1jaARPmfoM>3l$J9*9ii+=&_32hrB|oW5O+%lbGa#^_gB-PJhJjXIr&y*FHD1=N8lX7N3T zG5Y-B--hlr12kly(Ct9pi!}+p6gJxoL5~p+z|94G%8r-tqZ1Q>cJuk_#Tam{hfp-5 z6a!~O-eqUb5#c-HFtY$44#k59`Ppsj1itzWiWxiyIVWrV*#%aTId5PBb%DFc(&h+o zoWDxskl80T{Y(`}9L9(l=!-Gv@TXlm8(4jZrJ}@bC^@BxX@O$s@zXiOuasnWD`HU-ZteS7{SVFVVxTh?-nq83WLh?#|QGS zq)tObdxG_fij6|=kUAgBBL8GT@`D6>IWc zBx+pWu=;ia$H{N-93!`#WgguRe*|vjjA*@Dx=eXg>6@N==qJ?F;jJJI{*(%iQKsQ8 zs7@k-Ig>uZEb}~6{;kkV#A^F0WI=Vino5qYiU$ILs(mOl{*eA0RZhaqy|@;_0}51D%E(A+8mtkeJXL8!c?q7L(RS ztA}Rly#7efnu>}Hr3}#zAfZs@zIZp8Z-dzNVTSNH`}<>mj4H@Bya02<-@kgc^MyG% z7!zFdNsJ&Y0pmS#r#V;tt&mRM4qwUWi}9j2)p#`K00h$O{tY!ecd53X*26R^q2e6n zoYUctLA{478?-n~e(oQ@%@gm;>^tZIZySC{j#@DvAaUi`faHjgUvOdHdXdlaT@Gn( zGBf-#8kiejwKpq|xsphSAsn=QXx7n^j+_Mt^X6+OCU{*f*&+=tZr+K71u4LPsH@}d zA~2<4SIiM*LxIta1L#A!cuNNd+Dv6m5C}eOy?W2mw2rAbAr(&rT0wgPN&e7d=<=HzWO+WgztB}HdBgl~2{kV))Dfg9kiUHozFM%q| z*nacdfp6st43Ipr8i9>^7oeYSpZG4ofSL^)fy&vOJr$S

CEdk!-xq;Q~x|=^n2n zMx1Z>>}#PRLr%R->&^DAZ(w2Bn@wkzF;t-IvJFMWdO`Z5y=Dw)0QMA@CGS}JODe#O zBFq>+z!0aGsn^NQ1c`fc;GncD{6_2587OrM(nrW`u|X*|DXLpWcVR4jPYI|P)dxn) z&ch_xO)CK|`vyD;c81JN2FXep_3XahjPnf+%e_SRw8c+FH|O9bqEMyNcV!3)|9&Sk zXMnH?EeiEJUY?q|mR9}*MOHGDHxM(=ta2iafDT>>Rcg6YYN~m+OuOj4Hk#qxQ;#Ks zhptEDOV*3a^9hHf;wjYTTQ6BcM1jBcKKUw8uyjY)P0qCygX>3h6ecx<;C>Q!{7M?6 zVK<*=A_&{|l_C&3WUN<8d}4~OU+w1&bBRQ;W^TKmSdeIn0<6CZLt1Wqc@}$~%-F&L zhye)ixME8YcAkJ&^q^*V6cO+0XA!^)`wH-}(HbiJNmAfamRShsIXe?Y;74G~W54hV z;GKh6P%^YFJIR&G)51&oV`lv zz~Z-@N-ZSAK79eG#nQ4(IvTWc1@Zaua@Kp+y_)0!yflh1N)wd-nn&k?jL8Z$Z-fBb z3u4^DG#n)UWzCC=YZ8E>B*3#|4+8EG(DXts1_eBcLKjK68n!r%!uQRX#CtI(R z9}Db@DY=MAp!l-SO_(7Gsh*kRRmoO7Esa)?acy*7`YE}z8rZJX=2d-JRK!m$+V6zj37bFTKyfnQ(hvG5j|_w5vTG)U6yh19bY$ z{g!Ay*kTLglDJWkSK2?kzMS(A$rLu+hQ8-<^T{L*QP~Y!C(#ECma;w1hKuuy<$cY4 zBR5y~2eXBqllDuJEqX{Y?-Vb0bFWESVS-BjU2n?vAZqRaN3U~Oh2KR9<%8aX;a`vIS3u8ddVZz{DEOYP9FXh-GakUSM<*x?AnGPR*QT|UM1T(! z14N(fXKrGe*i7w7H3jS5{`N1wJHch2gR%xK&=Qu$ZNm$i9dcqz2<%&SNprwYQy`gH zzmLeFZE(Cm!E?2$|GJ01h|O&Xd*dGYPrKDnBK=Gsp&WX2$K|Daz5U`JU~k?g-KHg- z+eB7-|DnJDm$#eFo(f_0i*8&BeZaE0rc(YJssu!E27zrYIZgSXs?oBTQlYY<7N-?v zVOZhLKzKkTYhphLCtd4|@qT6=2Nav`{p18V!I`(5iUfYTb9fv){h#TdIHc z@^@ZerF%Cnjbc{czVH>nPWPQhaY^|j6G*y7NAs|>uR8w`T2lny8y1%K{c-b|_jglw zDQ{a`_Z@$|`U2uzr_w;9o-<5Er*gYrH0_)sjc^a%#i+J!DQ^b)aDaR`pl<@l(2k~8@Oi0a0*~SrXTm*N< zuCXGl$r6p(MttkatT25l+DreGdM#=WkCbVA58rlVx4*N;-{fYy2Qy!9pHors_4f9) zSF<}HIE( zgu+(_{Zml5M2aaVx1mC@I=L$Mf+FE!HUGbX?svD`w?<{4*E2Eu@%$aAwPvKl4hL&A zV+fPL=N1A%>&cJZu}6B*6&u62^>$ddZ=u+^P^9YI4=6-7{b_m|&S?@=vVMM|bGEp{ z^=f9piZn{5k}!GiVl04rqc)O2>ABB_addwEcbv>y(22D91JLX1eTWihl=5Br-)tVT zrvTSxdaw-p|Ho+m(sqk6vTrOD#}mF~xtENJJZfAK&qDyeCXCT_|`hMlc#A zVtTI;v2tZGJ3DrF4lM@bsrOq)+Q3CT_lGo*WfjH8Zp9&7L4SJJ+EJCwza6N7i$+<+w&aUhTy z-dq9SKsnrEj*J`Z96ag*d#{Qigx5V9Y#|>POO3dER!Nc}(KgT_*8ZYt6G>KG_8CY} z6-Td82xvx@Hp~82yNX#tX{OO4A)tdU2w2~GC+R0Zc*L};=fry_!swkEcX)vb?2A%W zrbK-F?V`NAz=QdQiKV41aLQhLRq5Q{Ocqaof75>^4B#GTLVeLz=KB3w2A@+_9{g&2 zZzqhZui8EzU+N!KKRw=6Ijz03_>j9VL6P#hOqUAUaHKW=%jRTb8>l~+-`?Lh zb5yn5F*#|5V63i%Q@^MeUxBER#={zmL9l-Ou!g`S$Rnm$bC3u1fVDiw4ob1B08*b4 zLP!!5VKvz%TrZlXv0^vwEyIjc6#zeqpnb`)8M{JPL43yj1LY-|#W285aB^x|+hI~X zNRw}G-vtcKxta{QdjidcY8o2D`GX1jpmy4*%4FlL0klN6fvTf)FhsGJ*ClzLZJq%1 zDu>76LY&A?zm#;4QUlejG|vMs@3J>%|J%>RfFR70eZRhg<#$_?z2ww&LQ5=QHJ+a- zLW}S!ynq56#uD%GiKR3kxjIaU(>ah%2JK2>_!bI6#(tM7W(CI*Z}zfNA<^4(UsoY% znEWBk_)<;(fpq&=Hk8O9{~X}Yr!WSK62O+ijOzml1XoCmiES=IhAb`4yB#t}gAuya zmr>)~i-8yG@ZyP*1n7N=a8^2wNJ~-x*F%JONSc3O{sAY=%3=?kF=K2KQT5h z4j3A!7g68N*jt}`GN5jlJe6NMiZkfA3<@0opAZfPwxr z0f;4^eLc{?+9bENEQ)mD+Em1^mpdq4N{@3-{{4o<2%0jzra|=$N0Kvv5~8Yk70+0n zaBI0uTnDCs_UHwCjV?fJ5fBpt)2y{M2VJ$qXKhxcDAd%D&VOH-*Fh84X0pD$`D(r# zAWm7^SYO|7iO47k$dU7Yp$W@~-|_-w=H}XTxZx=4;pZREzzYF1@O<1@Sy@S$*qLMm zXDCH(*O`==)XKl+mLGXf`fmS8hMP?F4$I)H%K7PZhn8=Dw0qWW+TM1q`X&STmnw+L zE5OG(JbYVkw+sk~crbwvxy3`9^jdQe-143nXbAg0NNFH8+Ny- zDpP%Wyqf!4ZC+4I{sL2T2=0&Q9ZI26n#A`4_Pq?X1UE|yOeJ0@yHJ7uTb?q*-^ePW zgO^HsVh}{Csk6Xi?fSLHjJ;Xm@~zdTH_i61UM7VLkF#FLG>d@XxHD*wJ-N<{aXDW# z)d8&lLbuy%`+gn1_v?M6Ge*8+8x0MSR{XxS9eI1empKT$Pdng!$(B(j&=TH@nWT=L zwbx8RHFH%G1@U%KTSwRYpuJPbf-nn_`EFS`Zj}?k{#%N>(CqrRZKEJ#q!x!$ zAdX74L4W6!bl#DtuiGy5;Ftgn0$^O~wjA_bwO<+f0;4Zb3t_8p)y+^AL4pY=-UF+> z5x`FI-EDvN4v$6X{1h-geingp?T5?7|F|gpE}NrMQ^8Ebzkn||AMIrMXWKj(S$izE$|hjm^&CO*|ME}x>28au%*Cu|_-n>gbr zl`@q`6sYH7_s;PF8VW{_@5n_ZGxEq)uQh+@xmTQ{VLa>$T?!uNP*+65DYn%@035@T zQ#7Q-31&uiPa=3Jj)mW>L)5oPYOELP|NXHNA;U5p2XS-FLO;MVTwqeM_lfnBmegLi zrLDf<#|Xsay=Dh@5BE$#>;2Ta0*Sb44Js>(?SnaSB_-kXLMK4Ii8}wc4Dk#6J7w^I zHQDVUs`zzD+=UH^wi1MO;~pRFndWJd*wEf|A2;C4XO9{EV2fp3(G1^K|5DDlon9GD zi`j*N1^Y5GB)agZh;TQqKkVjVQ*^&{l z`}9swPD~;FK=r#OgLe=J(=g#q${nRPs4y0^nJ)eJyzJYIO#9igY4}FZ5gkCn&tKl{ z3qD=mHs2C-i?$gQgS-uH0m8ZJ0N%jnYtSy2C@;-4jFD?PAHo(HiSd%WtBqyYk zzn9vLcK-X_y5!0ST*Q8ZkWAC|DzfKJFJ3B#CzzWD+x$U{M z-uvQjMPd6*nZrXrXbyM&Q`&A#*Ugr1z@k0lcQOgpVF80Mo5lRw%!cBy2y9ov4Y(K7^Vk|*o5>$2crLyPk?EdXM@K_kE zb{Xlq5E>6r`*^p+YADKABdVSA`TG|L0~!3A5c0editm~;b+Y&LYo09C6chEWQ6IDQ z{h`)W>Q)FsTEH|GY=ZG+n!bkbAe^=4JfCxb%C%HJEV^8z`L+hU4`<6`4jQo)q=6YB zYY$wKQibf0YAlZaY>&|pE&0YQKb#Ae-VYzeevzU$$=&;GG^)9Qvy4`02d|`YLK&5{ z_=t&>Y4IHVd2fJDFyWd=c-9u4x?KCC!(ggqRycTiuH+7b&%J2Nc?Wd@Nhp z9&hXS#{d46=ZO0-G)YhFd`$iTXlO+q=k7wn1#U>3AAg%IHoHBqxtEt!z}0!8P>JZj zYcU&&m6a6;d7%A^@w=u3_HhcM$02RLhscSo_fM>VZ(%kVFDw)Dwsm6bQ=3YYCKPD~ z87`-eAt^jj!TcpmSt4bTbAFlgK0@8f%3om7e7Cpw0Wdy=Y;WlrE#=p_rl7eOpGZ>W z3uFsHttUquR9OP9U0zyk^_@ON=tu<{ZYunBR%jh!u3J7|QJx&6v^cy;Q+=WGt6W)~o=GR9E|B7yE;)yT!ogK()j@}kU?uzdyoUxN#^zReLqzA7EX4Nvoa0vFb5 zZoUnE2)*TONT<}HcV)&R4Xg?nJh?e|P84Cg`3#wVR5cRFlZIktY1mL3iCTn4^o z{%FuQeKmHZI zt34{;JSLQQ%Sb^-VFDrTIOMR<&4BSaIiirvl(SKRuS}ZMyfVb-`8fA+uF?WEp6dUj zjx}b3t15tiQRJZ4cs$yy$p9X+#&T_LUhGpi3{xz4H|?HUr~$o998a|6pFD(&OcPu0 z3V8{%fbWEOlycRhGJ{Cf6k)_umV|^Ya#)3O0+d=`03%sz(2T?D`y^o6a9K{BeUL4| z3wfDC%2^WH_BAIAhfR?cM^a+#N|CsY_(@fg=V))xhshsfuC)y=GnpQFI|6q{?W_lO^PfPixRq^Y*Nm?h zQBk%t0ttz^R@vga^3``3f~$zC8bJy&klYWNke)cp^bn#T6kH}AhocV@@HSP9)E2*% z0wrUF@GIgs^i#eKW{e0cQy62y{$sAUGx}jg*mjfy6%Z!_dztsHu0OfJI3{WinqE17 z-fS|w5&1+8I8vm~Kb!B`l=>ZHESc!1_=>KVi|C+@b8sT+bWHcg z_+Z`pDeKd!lYoGSwz@C7byWHefrWKby-gXV>!N^keo? zdn5P{60+C7iayYP1nh02)=Ry%V-S%!1LoL9`^WoMa4(yzW;z8KHSa6~amNy*UWx(} z@z80;q)IGG0t@-3G$#20=+F#{08Iut zfiwx;o^;h2Akm7)CGOs6{60p85gMsDtquwqk-2vsV5+M5ApHIj!uhVpj1j@(4qjE&LM_)={#2Y3mzgPt+y{3mzR1z%ynMCFwNwd+$A!9jo(nO zH)P^PN{J@>T)ssf9IL#|#XYGZ+6g{$uXzo!(8@cn$17ycpdILME538Kk zW^=SlHguQ#i!mL_8+Y`ON7?qtCr!6`y9TGC%Aq-SxkQPYDrO}YIvtv$6C)~BR9yELA4n*!oaZ=G3MD#I451r;&NrXB& zV3;@DwBhw`qhQpS%XLsuBc8Nc61Hs#Gs=y#63^chKp9kC5_Pd{Uj~vX;9G}S?Y3>v zgO$h-HxHNZp^WJ5Kj4RO`vb%d&%?BjX)XN*JPXbK%Iyh(Xo8>e(Ti(@Rr15?=qUm&qQ9mO+!`E+G_oI*XpKttv+*;!J;H3|0+sxo=%+8vuv&^b= zuu)2!)6|QlnhbK(%MpB&OigtI8V{vsa_~X?+20q(nhDJa25Pcu|IVhvj6;qg?FS*H z3EhuWoiGc=H!tzFr1qz=X6To%DD6^SEQAEbk(*ks5==~)zPcN&wf?BHtz4milAY91 ze?WQMl zF{=PQH`zRnO^JA>V6~CTZDaSvO@C8vneF0O|4Ij$7Q2F}VR*VLrsT|Ay^r7ocz}yU zZ(o`hgpAxDzX40vxyHIE?_TO8bejx5^Y;=$Npcv2eA7~?A<9Esvgw5B(C;NC-lSxl zI!?2V#*{=$elcdv$=%WKdlKa?ymt~5JU?$F0LQ*ndxQV!;H$)JBsGgQm?Me|VN>Rm*m{`N8O26oFee(DA{x?uCAXeL-tp z;Nv6tU$0^&`|u5Qf)SS!ZzF_WpNgSN465@`R_vw&F2IDwRLs%jkmE?ouP-b_f>SDp zPYuygiExo4eCv5lZg(ZT$>W9jTggpnG2<`qWuzT`w^~HB$+H#dt#CS6 z_X=cMj0j&5|KB)9FhAZ^#L^t<;B%G%c5VCypZ-aEUo=;+{M<~pvDbB-RMXhqeMG8R zxl0TWh9a{W;Zu~QD5#m5>jLJM%&MD$n0T+=T$olf`^!Zoz>cJo3;kk(K za&w3vQ4oqa^neS5hFICud`t>P)ftGBuUxJZX}Ub>$(RY26rbXZc9hl|I0a_+hv4zi z-3oygq^FUJ0!J8uVD(~eV;`SIQsiI?5)u-{R5pKG9t9;O)Fy*N(_x4E#;NknT}oBI zn_(k588hpCH(8qa#_~Y(yGe`jubx?F8Sxv6HhY6rP6|Y8>Epx=*9f<_cXOaM#joi} zMd;?f#QX81pH!JueoKkI&K8!%Ic)L%q|VDJWW{|H${{{QT15^y7>F918_vWi{Vh^> z*7^hYQPsZ(57{D{RDKT?LJk2V;Tv>k!+ADLIotkLO|`C!F1EKnUN;`H3~WCc34_L* z=X&p8Ag3L7zu5|-&Hiw7^Vwyr0FT!9axHraZ1t}vO8QZqD7SZaP4=ekTn}f({fvyb zWgB!D)L2rgm=qLCUin%2P>g?!i;FcQfIvpMs{T%JLDn^BP^>BNE$!?`K#v!|f-_)X zRB_jNHDIEuzkm(pilv)OV;g_3X7~LbVPCfP4|($qeOFc}A>0Lp%QBJ8%zKWHyS3sY zCkTj+#Bs9dumPJS739=%5((zm5J?TxbQ{8L=1WeG!?&P>5EJ%g&BqbIw7ui402}!X zaLQ)n;gSB1H;w-Hyw-##aU~OdJW*-9UX3Uhxmqw675LEk5?XEz=!I(nV73BH%G@f| z&!cYcZFYi-*?JU7g0 z#8LpbX`l?%fYpA*H>!ys*<1TXHUr(LvMaQZI9Gad{U^z3&*>Ihbw(QZM-QR74`(4) z1pA~PjspKj(piQ@*|lBxK@p{-8>CaD92!Boo1wd;8>B&`C8Qgqh6ZVAq!Gy>q>+Y^ z?*2CKcO3r5fqV9S?RBknE-aXr9Xh+P3uQAbkdAV@c`3(S=T&({MSlaRb*LVCcNtL9 zPw5qWvE-kjE^;Lc2tY=L{#O=+Z2Dkt`Fhj9eQGK;%Em$1<&t!)fdX6r&DLO`HPQ`` zot4>gDo}PK31UL_ejxh?9(c!f@}+CYxwsjI|N9l3)(LToFTqc9O9yDT$C9P``pM}@ z!2739lQB+bh|EKKgDIh#lG-ecZ;huhj()Gyb*gRkPwP{js2g7LICph?ogHEbortX! zmO89+Wg0Ozhw%C0W30HWNh?c{~ln(E}2L8?jS(raJ zEB}LNu}trQh3LEb!a@sMVG$YE6JooTu4Z?{W5Wno7p<0-dGJ3GQ7Vi%<^5iE&r?4t zOv7{zvRTH!dH0yW!?|R`{d$q~X=C)A_q7RnjJNe|aWmz=+L>&dYVFmeAo2PN}`A*m=Zg^!_#IPri0y`qoHN>I8v;g{s!-v~!~S z-}`X-xpH9`xu<{ug+2a>&XUde#sV_ zt?To~j$xnx4S`DaLDZtm-=#B#&t+FTpJJ_7G%gDqgww`eV!=5Qx9h^b?^kCVJgrt zbD*a)^lWsS+L=m2TX9Q6H>5T5eF3yjQu~%5QvP)@51kPN#!$e*@ zn7acl>tr2I*#&5dM~_Z?uq1OGrTADo+J5u<#|GG5=(TzteG1qM#_0YEh9E#*G8#}F zkcO8&2I0U=6y*jDGJsb9`jbpS&+{iQ_xR~8AW8Io*1~?t&0UkHkzoi`MLyJ?;lMO7 zS0+V4h4(1Xg@z*r>3|_JIPLuxiGAm{#4Tcy`ika3#7o-H(OQ`wuQ1KKFMH6$ade6M z^4v@J)lhZbOPbL=rIJ_EW+CWk-rD!M^})Ub)-rHHfn(o1$InuoHCY?{PXS`sfcr_k z?VC%SaV6UOaVY^EeAgo+0^muA$a&6PKw|aPG>F^~jfBoRJ+aq5;Y6%$P z^H6EriX-=%R`+KAsolm<=_~_!i68%3kSzxD10D=?c2Wgvbum z2KBw@s?}rd8dqXC_z;ZzDTQ_1GNr;$=@^NhLqURc)UvC6yvz;X1E1v$ zyd1tGJR`8(3TQhV3&~F?nN-SI^Lo{5s#^Yl_RQsq>AaYU2~nsP2V5ES>6){Z;)VJ+ zDk?KLsvlG{6``Z}qTFU#nfN3)<~m(tZW@Zlgc#k}wws=NDIB!#t+-sCr*B`6J^l9L zJmw+B^A}0g(>s&7ci|*9Q_sU>4j83LD{P(;tdVu8gs(n53M5&E81&nJ)ZbE%j*eEw z1lTwZJ{bf1H_7&J6{At$h|zAaoBiK&B3574bR9k&Jgw<}RGVXhjKsgZl~9zUq^yjU z5A1SNOXE%Fb7c2z&U?cfHv|N7rdw+UHV zzaRG|HV;o<8V|1aF5HBPIBk-AIAk|^5HPwvCVBuCi0u3NE1!oCz^guw|3&rCMU)R| zsL+L5y+(}<9WGu_RkJ5Yr+?u@PBw}+n`;<6RLnD)o2n@rj-m0hN^Q*TnK)5%NofpA z9QI~7uurnccHwt07XK57ghlqTGz<5_p1(&Hd2TpmPkJqWTSt7)Ul;i@FYHCBI`dys zg01}DBgh^)$3q z!bBBDJ#?bUR8hxELNn3C5V6dEUfF@~<>by>%{yxh1UybTY_GLJ9YFZjk9B#%^iq}O zKT(y|b@sZkaiu2vKflc0F0q*FNKGa7O0gV?m#M@&3H%hxpY-?Vb4nnGemChx848D%fuZM9l7PEAcIzq;p7wt!DJWPz&~U?lbeV(XP}oUia}QyCV( z`2Fer%zE)6p8}ODo^_g9uC6rBoJ4(wQy~GAhNN*kGkKSVBVx%#<3VR4Wh<_ukVeB% z{KHFL&;nVLmsM1IYNcntB6l$9vau(p${LLtxnWJe8dOx>dS4wEIoXAAn(1k`ocqCs z(?ej^tU5L31z58p5@3xm#9n3kGsq8cE+8oeF3dCfCuy6_b8`vHdjs?=DB$!?bljfz8&0~jR4(8R%k=dABWTQegKF^dSat5&FSeDpp)Wk!Q1$ret? z1bcdf>}BwB+CI>#I9|V0Bc>Yq6{Qy7QEo$=1)aL>Z)H$OeGe1>zz*CREXrQJER;{< zcV&2FSl_;KJ--BzU_n1$P=E{~@Bk(+r8V;s)E-=k8J4@S1if4L60Y3B7}~{45Hm3h zcUgd7Lg8cFitk0$nQ>vFELpJ1h8P6~@kfiNj0wZ<7ffYRG^+#u0<}rBG8(OHB#B)s zZmojoG0n6hL=r%b|C8UC8^PC^O_wW+Gk5p0C2xeHcZ-jem7V$g=9^5fX`M&jMN4pZ z_{DuH=NsS6w>f`71c2m2win?eahb@_?Wi5(st+7v`LDO%?UH%)u_Bu=ooa-%Y9kTK z1&tW7sIsImgKG}~QgU<=G{&k@Xte)ApA!kQOQxA_x;-9QZc5|7(mV+~nWs?oGK?~b z2|AM(c>!F%UMQq8gfeS}l$PfGLW}3Z|3?x0Y2XlDGU3(MQ#3yUab4m6OpkBA4v5BN zzv#Xsixzw%tG^t?fgNYkZp2I|pAt>ia$cnJOFf~oP-Os=(gDQ4Eccs5=+s<2 z;q8klr_ROXVLeboi!S}j9a*oz&ZPHOQl`%czw1HkN#$}wedAuOAHvdd&j(-8hhhYs zy~=WmHh?Pe$xD$FQyW`^(?7Y>0wUBn+Q=FjbZTd&2#$z>_n)`GwuQ<(3|D6S&$}17 z?F^Fg;+VN~CSKIZWUGI8vIGTG3j&uuk=I%(Y=se#BejRb{=-KP`K$={G>A73q5|y1 z*wZ0FnzPH#u_t4G0e_>EvwDA`V_9Cohd^?2DaziSd#1`LVC_$GvNC2-ML*`*bjAGk zwpCGMW9(1;WK&_~672$wk`*7}275{BB~@*Eh;w3r3}~*2NP_KHr4ugxi-%g7F(gnY zjJ(kErBQ7=lC5E7_;1RNhnc4I3)!60syA`PtppyW#Q7z)i6C~Cr8exQTkv3 zFh&=)xuPd9D&_0r65|G%#qe8#Vmt3N#M%d|2l!P#%i4Nc3WCx z9pp<}R@8}ncZr@;)KQgSei42mTFowb6-eXR^qv!_D{}OryH(mC?f~t-3JM2{{@i{{$@g40N(*EVy2|9_x@Hk!7|v(t_ms_ zci|1M@+nqPcQ}f^;b$=4+mupn5%qmlMdjbEGCi~+HWOTWjgOWB@=G1~(zlb7(<{wv z>A4AH1N*C5d!<=6GwZvwY5|HbJ^WH=V+Dc~$#{?E^&I}@$+HRHfP4SqXrtYt?y|^N z`i$YX7Q5z#2DOBeTKq@9*n{#`X9*jiF+G{9d22pF+=V5jsSu1pHyooX4N07YitzjW zFr;{lOQdAl_lc`d2N3F| zc43z$U$+ES6R2Hva|DB=Xsa+NZZV-{rt#E?DEWh8*;U?LZ^Km&e8juEHsH`InAiyy zF{c_r6Zb%2o>1>SKmX=!hE9vk#JR>Y(G!0Ao^v+7z>|_fbLSui;cFk;L)9zcRQWz zfT~1tC8~4{5J)V!K%I3OUBb=)CQ~|#IPVySBFFE%B!luSw4iTtnpia5;^li^RMF#q zb0}Itoe8pR^PFR~Ce==biGQK}_tnXM3+ri{UkXoS)QDy6=YNe4NI=<#dN=zJ^E!|} zZfyWkyZdq6Jj2p_d~v+TbS(GwZq^3l9!L>-K6;_r&eMzZJ;#gMPe6lfz|m){>4f1; z5Mu!3SjbyN=?jlml{^@X&|v299eXp+FR_jl?}5lMnI1P&ok%gaeD`>Of)vGGMm`dv zc4KTF7l;YlyP|ucYT;asNk?r*;BQSSk_gsJiVpo!3hZYt=u5WqUNj3j3y8c z^#Wbl{HMkF+Gi8;0Gtr?8EZWn>X_+!`1AP#PnyCs=0m1hNzeJ7z1@6!QsoF6wLUw3 z-q=RG_Od5US07dn8b?%}ir5g@__RBw&J(zdacXlozAUI=Pna~fk(qfh@|ENnS6MnC zw9VXt zqN<=q{yGvAUv4R0BVjo4UYBdEz9j`VM?eAFQQ1nWTn0_)qfj_-2X6l z;S}+(0=neZ8s-Crf}Rp7Jbu&z{npFW&w6_OcT>yw;N4z^2^D6a?kiLaF;%4^0@Z>g z8n^{#k>9EWW61cQyu(S~^Ma0hV=D*b^+}diB2DdH(ZisoQz;x6@jLja>ezScs;>%7 zh>2nUO|q0)Eue-iz(lvDD<_`E2Zq`{5aA2IR`=6_MBO8^Ybk_qz_N!Ncf1lKGe z-YEW+j#DglMm93(LZ~jc$H1cY!GF5qCa|)SE%}XLY}+}h%OM2-4ASY4 zCifFLf#2}o8#a^eK=Ycz$u)k@4!^5m#SXD2?Kf=)&b=Ecly_i&zT5oXjg|3Lw&>&a zjqfs1G*nnQ7eK9swThsxycS)*dfICbKWo>a}(u%z(tMqdx1V+qIF&ZiC{H<;C~ z|1tAA{TtSFIw3E8T{jDT==}dD2AH9N(aN+pk^oHHr-y*Detr%*`BpB|=LEccZh*=B zPlI@q21B^@u1RXdFJl z8{|>y?r@U4c^N?kkM4YOc~>+1Epg15{iun_;!`Hr}NX)KZ8yQPS9Bmx5hf|*R!cw`b|4W2d;`z&C zT&0TXaLrHLyV0TH)e-3@mhi4>15n0%wuqdQ!@kOVCix?77O!qpaJKR};G0G%*ai=^ES<4EdJn!K z1i&SPVN|$fXHw6h=_;e5;>}P|fFitsWc#3~r6}X)Cs8SBX+ZLrL`2I3FLYuFf%`mZ zsi!-x6oQmF5*-IYDh_VWPvHs)L$E>fx9hdfYWR^*q8ZWCVYy6kn8N9Dp`!nIF!JiZ z@?{}ML3HnX;lVvzlx6W|6w&y~%tHO{OHFn=oF6aSrSnb3mzI9M9kpA(JsI7)=yWO&5$7@9{b7S=%rW*|#{(bMhpU<(@ znXa?zL`$-Xma0&qjjSq}L3An3;p3HgcXzqIvzsRbw62|nlU8d}XOi*Ga2aZ(80Z*2 zAji=BZKe)JfUawT=)d1~+@!{)^OH=(cueDP7M<5TJ2t0~sk$B42Y@DFRT=nY@A0?TKzcF$>%0K*TN&M1ItfeSct ze2N`a0F#o+|*6ZsvVq+jPyjAqUZqlU!l*fO_xEv?4$&A)vhZBmEe0_Uad08Ufx4 zPGO*bEcy=lI9wI5zMeDqxb*XUPq2%>c57~LkKznO7&`(E+9{rz5WftjZb9vSN}W4x zHz$8^`?qm~{~^=W(536Bf9DGkyZ=%S0SeNY6z$;Ca?MhW*GUC9RlGK;W`;z?A(nXa zgsbi|F;83D!jqNPf6;P@Q~k!qrHNPCef6BZ=(iPSaW1$J zsYz3>!9OQ`elPR~_2e^qQ2ZUUmUX;3|1+sCBel$T#lc^BE=>aQ`$$r#Yf7=N+im&J z1uZ|iEp4!)GNrt(tFKpKQ+DYk&^iX_{@|g?Or*~vlMjBw5H0r3bT;Fh)KnQ$I{leK z+YxetfpVSNbz*+tZR2H|#19hC0S{4LLwx3`62f}s&gG+xE*90TJY^Y+RSgD0aj{b`Q z6*P0Hf6nOS2}c+gIiHJ|&p&s#Hn!-m+$&JuA+kRmJ_vYt4j|}49tTU^URzm1AOy&` zbQn4VpXHa|Lm+M@YAl8-wWhW@B>VgOw}tMb{Cysl~$Xf*zr$DZZ0?^Q)fLYiAx*s0Zi3_ZYmxJEtr z`TP|`P(VPzfOoE&N}EioU!9LVLf;Vpa5ij0K)Yjeb2ErZBa32JAUz}2crk+r8gt|Z zY&A{!Cn;pf1Qkg3)hKQu#)}u9Uku_3B1!HSBaiP2i+K`1SQ$OKr>>lk=wDL;7OLtxI7H(Wz|A zRI+^8fk#&+;Rj8rHKUQ;DS6uhC4C%kz9i#rTiev{w#8#)?NJbi4hHi&7aN^-c)z<{ z>9$*JjaD3WSlu>@wd@X!E;ndN262kZaMP00oF=>Tf}LBI(GwC<(r+y-VPFL%B^An? zEH}9e-K}qSa^!y*gOKEG_QaNtRhVP!BBz;p5Sr2J~n3qH@P+X6^FLAthy>&E%lD zt9GqM6&N$oQg$Qd#_cz*7bhT{8z z{7z$zU+ww09gnrWy(Ap+^Lwdg3AEHy4*DhE&IZ-FZ5&&D)Ur0hjMw>H0BPH@yrz?A z@BsD}L2)SqObj%HSwkqgIXD&H*;EEsvVco!I`gLsnL^yT=DhHTV(mBmx}`F30t=PC zI(Lz@E~z;1`wzqyC#3n=Opf$5e+x;LMi;Ly6g{`GhGOgEu-b`YTEp+}P)Db2po; znPt6KWv%Q+1GCZD$YW`!5xO9!?X?jE5OUx1rPL zJTb!Fm_FzK+AdSgrtiwXj#Bbx8BJM1Knb*4`Ika&wB6=9ZlOmiqHEAUV}Pq z$x&Ph8Dt$C;7>m@O<&zi9uBwb^c7Z?mq!PvEiqAu7WjhURt^osqmB2(IsLk4Yrnyd zQdJ;^SsNOY{^0zD5;aPxBO1SvzUAdOvQ?8a4**8>y3uY7pDlC%I>c+sU>N*9Ka2Yf z+_Sjv*&24AztLlYmXQbCI{Q8>9h}@>bmVBY9YX;GNF4krBFpx(cpaBay1T_OFflnf z`K#rV*O!d$cZrU-w~O6|-ZUadvV`gJIKCv%c{!Yz){6D46&gn;+r@zai~-;T+iq4O z4%+*pQO1okZGh)AW>YU!p_{K+HEsp@UJlbn<*6vHK1Ob!HOae**rAsT7EP8^r|bNN zWB8K;X7LmjLdKCH+tn)RrY476gAmX~&W=u?FlEriZu+l?i?K*^UUu8%);ZH1F9qUf zL%^*GH{A-cRq1nIR9?EdJ7~2ScJ9}B%KLr_V#t8ya@j-oyrtQ*_t{$RcV{M z&(utaA4zO$&yYf4aYN=-0xtpQ7ZBkj03UX+$U^qs4jVa?btn}E;?H{9`};5rmM3Cm z@aZKsh(?2Wn_7YE?D)D%h*eFl$gtei zGN>eVhHP$+Oc+&<^Sk6an{_pm8#0t8U3OP@^izysn4jKF`FTHR0tJDM>|r92n_ls| z10ghv$7&;Q{ODY$$8YXz5VCsYEOZ6D(tj2=RwGB6482+^?*wnItT>& zuk;Zb0wKAmZ!%$}pps?FTa7K}!*uyb2{#*c_Q6|ze%U4seDyM21%pPbNrbj0UVnA< z9z!KrE}@W!wOcS)Ua78rw~!>j;SsBIFeUcRD+BZf^IB`9jA3(N&Ci>SB-YfeLyL-| z_zPLm;n>URdZ5A}sebA%uuAK}q{Q1M1D_7Wtrq9GcB~0LxG_t%XyeHl4cHi<)e0Hb z#T!iQyr^bmD6X$_+Ed`!P`C@>t|jzE(jX3viit5zH+_;gVri{Q*rXq0TFrNmc`|yX zjJlIKXd0KD?EsE=omNjkvu;Zk`JK_fz5OEEo1))&8-cLcnXo8uc~+h)jN&08Z9606 zHYoa5At=0@sP}@Q$%%$pVc|W24vOTrC!hZVD>u#HuLM+yV!lTDV-uFaYT@F_6tU%O zZ##^?yZ`=KpYc24i@B~~F(ea{EPMX;OkIgDrs-r$m04?h$IDrv{87$m_ZfW`Merrl ze_975BlG_k>N=&R9PZdkzVLPZ8RVs<955GSX1D6w88?o@z{psfTsBGSZdXQvq}SH- z^I2Rwb2`SLYH~(tsd`L>m1IJ+gD0@<*s)3TB=kbgwqZr6m{U~~Dbk!v2Z-c#;Qc65pBV)8 z4x(jm4Vk_=iL+378s^qV1syPhfl)_AT#W!M94nw!n(}!i8gAxqqiu*M?NjtR4i$y3 z*&SD71P@lG=N&d0^c*u<{BF)4{{8zWG;{GZ2Gr{;`kZS6Qy^Apsemv)|E!KJ)g#X{1+WY*D?hfqPPE{^JyP~3XNkm3mtw(qYJ`NZ6X*0UCn7?&M7ILIG#;_X z7eP1#Q9xmV?nVp5tT8z02u^E)F=CCOTH@zvQfBaO3;CFD{E9EMf1+voFPVl%K7uB?}r1x9cLeNnJnUd@K z{@n3)O1m1;X#{-dblRoqHyAN3?l&lSS7-dp)nVLkb6l&0E>v>--=5JFg9DH9$0OeL zcw-1$Ffqw^IBcg`kFSIx^Ne9?e;WKW_4MXv0=oen2XwpG`S0@s$hUUmzP6Ikk;F@* zhQ#qWoR|NWrLmEtVx!}RHd3d!pSL7`FdoYPZRCervA0K@{kgP^Z}7#tSNh0etpbWI zv_on%Zcr#xNJeT^ow+&9asq|ffJki0s(Ir|c<4h>$)8uxU*m=i(Yg^R*tDx%EbI!h z^KG#fjeq}2hiWimcvy}5*j8y+1(?lEd)<_qfDa?4j;|zg=a%j5-5t@m{#MYJPc(CY#{3>c3ohElYc`hOTBmIP% z%ep#y(7blNCdeddXam5-QeodJUgM|=z7UVYVpg1;>OQ=J7Y8%r_t=u`T)if@-rZ#Q zLgr#Dxc_{_(0iog-L6O!w9(3%nF9jpY}~&`actgi?m)Brxh+8MW6mBzt7JB~yT<3z z%c2WMYiY1AqE5pHIsE*#tcK|)6(Qt0>it+I<)-6S0_N%{k*xV8XhVdfYurU_qGofY zB?wloe)8_j2BkSYU70O-0URazr!dRs8|uWPI*1&CwI)R9u0bKdnz8@(w&?cc?BRES z|5gi8+nzn|LYmSCLQsEPF7;G4nQ;UpZNfUv>#MlW_h;eRgO*b^6@)ybXJf8y#z(8Y z_n?95pKbbP#~Q`Kp}A!80l-o5C&>*qSIWzLl3-$vq%o7mQgz+*80WUF=0gq!{t&L& zX(`Z%Q2F`=B4*84(7`;&2`^NmH7|q51OJ*uhfv)LDmmq*CPm&_F0B&?S4Ah8s3udH z8K;@^{+)&vp@36OVw$dM8o5Isf&bi8J@iLRFpjQ7#J9d9j@L1*5xgPP)bXsEQ!!=% zW!h|ulM@rV4fYveHq11-T_rljI?qQ4)VkF2T^y(N*}(1v&Q?)gv~|9A{vp9z?cK)4 zrj{Ox;5(RbyHgL;WFY_&1-l?9a$NrO)a~PiN?D@U)N4Z|T;H=8!P#0LaD5d24^;im z<;RN7V21i!RBx{j@vZ(YlPRN~)qiD<*&qAOyC!qpNwy{k@n?{4`9eqoDhukl^+{z& z1ezX^gbApT8`r-FS;)st4pm|m(Nf^Y`N)wY+nz^LJ8ru-8)}^XT?N{#M=;*DBNfWf z2lqucxZ>lqzNQ7Rj%Auvo9#FIYd{J60Bq;~ma5l=zof9;)R>TNo>rAi?Vg@pjL*yu z0cnvo-z=!X&{3so1`J1$_0g#siq`1`OfGcUrQ45T2F~B$LK5T4CeM>VoiUU!WI=QH zh1pb!#vdwkC{$!ZEcTvi-`SbZ0a7SOT5kO>mrjoj8~-xgi2IKn&vK$%q5txCR=H@J zidi1gdI8|(-ds;mzW-u$@a%&@|5QrWDCH~f%p_@6i`l%Uy1I1`9RHmm5<3*56JAhd zGDuHUV>c+a`P=4$$A{-{te;B4iP@$~ba*I2%C${=gllzOJ;j6=GQTU3<@Xp*st~{I z+U7%U?@W>T6wA&G4wRFL?g@SOpRF)#K819Lze{zU33r z((aMc{PDoBscPm`4F`Wv!5KZQ{+1iB?#IC<2R5jcbzZ4~_dzTC#|CRptRwU9q@*%@X zOzE#+_{i|Ut-#bpZw{5>JA7PT{hBDc5K(x8qfVXE_|~=e4em_t!3}xSD(JRb>H=-E}3_4ySN1EJ>WPzJB*djPcN%cFW z^CTolw%ZlDdSiG5MS!XAIGQE9o@}?x z3xnX&zad?FDKetslsbfzU-$$_MzK_r!nX8WWTao z{UN+HQW-a08wDkG%;Noce-RdX2 z1a2ICuZ^VNS%O-W#Kf14g<+H)`R}0$Q$0P%@7^t*o}u!t^z{62LZ0p+{cg>B$OMk^B`{H@h?O>IL zgYQ~dor`$%kYp`*PcVq^oW|5^emcyg~ssC8qF$SKJ zFNY+eT<%efqSYws$#jXJa5Kyu(agpKbnZklnztEf<4 zVaC*FJ6Dru92jxtA>q%`tuA3Zf+WG?9#GM=^{7&>lW-vK6|wq}B_aG3r4K+W&> z51k5T-0A@dK;ypuWaDiHWl7SmwZwe-^iDhZ87RIiLl5cVC6MHQW$bAc4qO@4_BS4& zvx1nCtO#6Ucr&(}`wj9`N;i>SYNV32^KJ7CBYXiv{?)P0-;`qgGla*Xqp$Oo#~gJliq~WDNrx{;zK`J|6b*wsRC| ziacD6J_o8wOMk6DGW>ph;aPx3B zj;#!tEynE{r7u#l_aMNi+N#=!LKc1f4`#8W2}eVmg%*^ufOQbp4v@tXrKF__6c}i4 z+FxI_SAkB}-Wt{oScXF)CR}Cd@Ooyb6gCKQ7_=Ef5q&JWs6#bTi*Cf^q;zB!Vk|Yk z|d#m4iC`@qE( zkBHyzm$%l{mCeTU=%dakCG69N7vPoDGjlPy!KpCf9a_mJ6aTd`F{;4vn=Rdsx1Yw= z9L3%6?*)C~+fT%+&KMpjhG7TOtl4TxS*U&)Id_hQu{$pX1@gmATKqn5T(~t5HDE?X zt6`OH`$y6b#ah6xpL@*?8G00B^*{Uo?^pj#_u>42?>QSoDJOBU%Ofq0?IB68wT>71 zqCdPbX!xghC1x^yT2*bIaewdc?c+^CPHOJv7CdMgVN)-cZ&+l_edJ3y`VsXr$EVM~ zYJw!NXa9!K8$!7i#QPNrITb$Z^Q3H-*31r6C&`*wJ^@G19ekG0^j#)YkKHLB`t(Nmcm8O-(dPS*W^LoD0TqW&c#6u@JE)dVrj<{p zG0iY*+6>@EY1;J-x$7S5oFDAK46wFS;eFcGbe%u4!|{&ue^5RVi9Cw{sEWe(Q1d4` zg$q_Lb2U6mZsSL8ZX>3x+J!hF)_Td%swo7X2V4yi9csy4{v9+Ga+AhS)rrF)sjN!J zfSbbDj);>hqMLCp;E<3Kdqqi^qNl4n+0uT_y^)^Mq3?ft)SuMeZpfT7D(`IUGSMmj z-SfzlkWD+BPJYtX{Utfy0N9`iW-opJMD=2v`wfX!gcS?3=$q|kW~bgv_&a6jmLh1|l`@_Hxb z2m=P!wZl;mu8Z$(mK&XZs%c>_K4a)FJZ1r9zh_?--@ytydh*jEBH?M$)I|`0!$LBt209T!$rQbih1oe2}Yqjov%7pCpS_y%eoqpBVYi zFaxtVEu23`t-G5!mb1?59mSWI-A5GoGNdT<6V<(zpZHGoR zz;Oa)e(@?Xda^#%a}%bdA&Vwkj}+gF#pOh{_H7!kyX!NxYHhkKCFvbhu4WisC{3W> z->wi4R9v|c22Bf!89dI*eizk_%l_cZ)=b>WCp3R18OMQvx5&YPiPt@u@ZF-DgVrC4 z0>}4#Z7`GHD#twWUb5%RYJ-W?-6(wGGjoCjv7!?Fx>Zm*`QL56=W)63<)$O^3d}>^ z3~_y;)F7W}%KbX(SEX46a6X}NUG4@z_dw3}16@{f?B>Hi722q5HZg9V7X$qtSfujv z!6*C9T0LDhWmEe$?e~lZv<<(<+;(duOQ_Kc{rSs(AAIeifZ*Mop6-M!8i*e%8}3p& zTL370z`~T6-HsHa+ZH((!6|(C6Dz_qGf|c;W9_)iD3s=PVt*JaeaPvtx(vHMEnB)= zfw{`MOa|VV8q=7_Y{A9gvWtTJ=b})tiJ_RSU^C6UU}1Y^f^LDzWI;;j5kUNTF-yYSnl8M8yIE0{cv6e6Bq5q?vs+<*+UdoRi(tm0r8K4Ir-Nl znR|LNy{EV#hAKupxrl5!E)n|2oFE6Q?Q|u9EQYM%uhIISnp&+Y!Hc!Ee226&kAC{h zlM5T!zb-i~UE`VPe`>@Lf6SrP5ONbF=#RJ?H{uX=upL9|0g^1&^yXY7*ht~+6}oB@{_ zm%4q+WM1(fOz{^)+hektFLz`+xxZxJFWy~CUwZ0HC2#7(icjFclq&_Ji=DvbryPm@ z&M=fGlHu@_XU zoy7p~Kxc~dVawEEOMcHozL56Ft6L{{wvVA#-ze-{Z?nAH-Wty!s+(2O0Mu3 z{$y00?~aC0y_|`Z6qzJ}5v5ePj*0J4{!}$PEL${{PeGint5ZHN5f-ZEtWJMO=|bL2 zuGnPiqlsLrJ5hT^!Rc*tkiOIYy zX)`ELLMJEB?m2xkHo=tJjf4InpM-&1uwbb;|Jksj0qit+ zYq#V>EFzHGo{fLj@`7kt0zuZH^l-?>NdA#E!1tdsSV%{T`)S`x*E=iNCrn-=DPeu!wsz-&NQH4mpu*vrXZQ3U{AgTS;n%?OD%?k2x6^tZF)H_4uT)7 zBa*nHuEY^@g_p~c<+)Tf-ThoCKS-XMPD*WGEmeTBoRNM?Z(!tQl;CwEpO@paB6`5o zQdG~_w~OSLZxPzZNb*{=SB7+5gu`IC^vr&ZL1yy4ZE0oY{%K~bjc|_F z1(|lUIga=m{cgQL!(zdbRgZevcSA>+m_-HHu;M(-3TW(F;^@>)mDoX@(FgdG%Ef*?7EGF=CW~nsj6GRn){SuZus5 zH(5Ih&BQ<0N>zKSYmuoz9oPB6@~GbO^|ZL(U~0)jm<_B+Kmy82$caHa4s;_)fh?&R zce{D7vPxT{cskjqkKW$3KE;1aZ5g?Lslj5S1d4!=x|8=S{TJ^XQQaB^D+3J<<~jfg z<8;(ZG`3OngdQB_oywthPN$Dwx0 z)=OfyZMJqq&D9FA{8pXQBxgV6ZugN$C5Vn7T6Ywywi-LyVhLWytj~1Z(*w*c3FwmM z1KkK69zaO^mt`*cBEKp#HW|*?c8jk?lD$B4X z-ZI$qU`nEN{g?LNvio5=p;9f*JI_gHJM{U|zk+NacUzq+y5!$2a#Tg>DHxeI&I=KP z*W@h-a8H}B z#FkxF$n+i~s=?|#T3_kB=DbyWv*}Fj91H*ghjPBVRdWzCI~t zf}u$p0%sEs3Na%IweYhjnrwmmjH)y)nW700Fjp(V|3dg?^$|T%f;nnjpitR*%hi6` z%YJ%7MI;nh0s0;M;XXf z)@B#0m6K8M0w_Twa$7vH{ArqZx_Yg6Y58&2)@eZ=sEXRr%#)p zbTk`qgFmzE^v(>AUP`(jY_Eqc6QsnEX};VFqnFKg+GuNQs{6()_EcvTHyt|}JYT+$ zY{)sllfWdDNiD%g%sfQgxBE}*{DwRchGZyqajZ`av8{=8oV~&5Hr}etA`VS^?@O;E zCI;$yb#-;O|7~}IM&B<9%+2dzP zTZPCyiawdIu!Uk5lXz1Ut9?$I)4aRn@FvSZNTXLqfV6 zH(dhKB`J+`cS+PQSQSM5xoZzn4o9)28=I3_J>=SEs}(6wf8JkMZ$n@Z-5(iL<$rQ8O)%A z5o!=8X~*i|;83KL3|j}Kf%qS_;#K=w;$nU5#{t-gh{0>V$Jo{YD2d(O9S;=FQK=QL zC|=2=5fr(<7DS^uLGzFQG4i}`hH=b^u)$J`F?n*1*Vpqg2s!%Ux=i-*>d4se98tSj zM?~MKciE7dvEw(bebH9kgM7F01+>H z`(OItC)-yxMnw5C4JMd?5{Ze8#UsMgceNyt>Z-Mi$Vb)^7k%XOHe&x8$>cMeJnl0! z+*#Jz486tBAA=Bit2%R`&Zl9xUdcR*tFbdQsIZ|0B@dDq%aW z?UMfdiXL2iU-s8v#iu+J+iB5Y5So}k|>dAUcla(nx7Qw=x?%B0b`3(_@I%!j`;RmN0*MOGjrDEWOJnVy-z zg}JWWlnFzfA(XCour|>mh-&wHZ*ZkfYm`&KnWKu(>ARbo8|HMyB~Scu+o8|z4Hm)E zmhW(8wp7l=+)}LwZ>r4#952GS0lC6m)Ph=!;Ahj9r-*rG@w&2|3=xkY-(;HxF5>Ll zM{5GE6*q3XE>BZA12aMBjhkyG-h{+-n*OCmg>Hn_5{)*@Ep-T<~#pi6!^Kd)VHv zO=-D`kVDe=o{bG|en(Z6gSngFTp0nhJVC*NDOEwF-Gx@RMik0x7r&iX)13?YK6#S) z$crA{d#uKjbNy*tVnVN#hay7Cfp?EVg;z^$By#BIg9l^w-8Wgvj^pnI#fq(0ebKFt z&EorCEp)?t#`topitOf5tER8Ls2#p&D>A9hy zVRqmHxK3~G-us3f5CP~rwV%%1tT>E1uChWU$CC~>H=7(#P*8vc%f#6^;j|VVtRDc} zhHC~Vxc>a*c$ z`>Oug0u4b248+1ngS$}zHzCYaX4%hW|LT4B$@SW~3w1E2IN;oA6^mlQzj|F>zAf;Q z*!V8}tm47xXRWeu%VTZH^@y;MYT0b|yKnm8<1b+xYHW+%j+@W2F0i=;jC$=-Y~s$< ze=f_L6;M_{!jz~A93h135H-k~(aPijV}fDaBRzChq4AmsU z5$YZH6jv4in-%3nyyP!*@&LtIZsYeI@p!+V@{a2s@gDr9AclER1l(}15GiLyP5B( z@RDK^gaX3n6V&QV^zd?Kf8&f6Wa_)VA*)>fWA3AG%i8ebVk(U)WRcqmlsG`8B+mA9 zgBfLm)7^cn-3`lE6Mnf@%)NO$0}7L89r}dQty)QR$N+y8uRQHwdc4v3G?!x|VkV4+ zK#Agh)A7qn>=4Dh*3wWT)HmmE`)c zob7XdKdoG=J>6nP;|WCb_sdCJ9oQ}ufS0dEB1N5w~_83jgQ!LS}d914Tu%*#JqX0 zg|+Cxg&E70;#~Nvs|S0j{qmXFPQP5z02cpRk9g;KRi$Bl*q=XtvcPctlKJ01w3h=#F~<_QC@0HNze~ytcneM{AKlN zhir3XDo5Cb992sTCZI0y`S%h?m3FkcsSzNr5_NN?D?U|J)LSL>?Vi6$mEm_+T94Vd zG{quOu`9i!@kkI*XZ^H-XKT(28ysuz^4jr22}8!H!%B3x(Ov+csX< z^W73^Y1JURxUJV)VS}fysH7ykc9t6~Qkr(WP;LChXwr(e@6@Q|0VO$K`gu7_o)5Tb zre{~?6!PEyS6rN`#6VGNH6YF1#IBg+EhO^w@!2i*ul=>NDcY>5laSn#7T2C z^UM!jH(KCwJ3aC=vWPoc(wiGIIBsg{rXci%)6FiU`1LuNQ%7PdtM*r~%>W_c{lCAD zyYg0@{6Bv>dvH;y2ZGF4{*Emyk$Mxvl58KAGQZrF0VG;8GmykRWrjnDb6v+G&$oIb zM~y{KvW9$}eE4I1a;VS}EFz_&iOz~S10s(eufvupuSb4UX7N^>wUNZ)EG}IM_=|Re zyvQ3Np}v7Dy1_ZRMxPuXb}~SSrk!N%F}Vs>QjXaHmg< z``!N_D5&A3nk+hv7>$4Finr5_jcvs+mGYMqJI+(fkNDWn7Nr zj1ZUW(M7X-0AZ|PWadC%rx;_>@(ucYoSBX5vWWk^zy0!^!8Of(X?%6MwL*BbejY4AG%ni_fj7C+Q|rR7NJzeevI_MH;#0rojevk0UzW5QZ*|*W z3?fcl$ub?h3{)+8;18~-H`|XQtk`&}V%8Y@&)cd9Ja`9yK%`qAIwP86oQ*3$4uZKv z;(Tu~>Qjz2cwK73P$c~R_7c84`#dU$W&8-#dCmr(MD9mm^T4pODtsflNtT`<>$kZ| zi6r4wZ4{soKDR#LXZ`5z9upbKJyy)q=wm3* zPmanDH4VYtpb8+vU{8LgVOt)S{{pYc25MgSsxFfaq@WB`S`gr6kTA!BSGGLLI2z9i zQeoC#5ybVzamOO#X_yt+1ac8nHK5On&;>wxjwaCdcI-3FrTGT^%L0Q*qq zy+sa!u9+mSfnF}lb=}grPNn~VYJnSDRhiZXCCahD7A2}Y(vq40{=?gmu;!p>M)suv z=BVr`lxcx_cZj4h(j@G*O>jwk;^c}hfNnRA)`Dl5yxr@MIf#T?LmxUu<46AcCwN=T zxo79KE^TGS*zS2Oqd_1kc}F$iC2Fua+?3VO*fcjg3pOs`dTQgPK& zf$5to+i66b$N5oL8MFZe0sQ*$&;Ewe7PJ zLCe>v$Lr9!#Kfk+hG?nPj!{agpCB4I5-=KVd3)KezRZM&Q73*0p7|9O$@DB9FuBpcEPx8IlO@ca}WnuYBgg7gy%C(0m@+)?{SYs?kD}L zB5NI+%a$~;>%d=HXYz1&hW?IEX91p5ipH+}@d05r$D?i~r+tsB$1-4xX|{&5X03*#C5Ya4?c?Ir(!;6pTbWj_;2Pi)Vry zNzkjQBKnf{r!t2<77d5d8FNoMjyFLQ=Zkq8#Aq6Ew)5#h4HlI2g zOqx!uUrSLGIwqJ%smbzCwoxj1-p$Jz#gaGTl?%4OELUA|^@S3*_P)D}?BsFt^cMwm zpvj(y<4<409`+wnyMVi&A374RZ4*Bj`M-+FGy!v#*;?*eJts8LWUi1FfhNVy*&a7T z%jrX)ryY!m!K}Ahbi|-AtQ5IH(xe3wQ6xr+_9QzFVPb=q21VqnccfY?AT}Z$q+gBN%iws2By`zy5EnKDH}| zY`NBs->g`uR7eI=Het?V@ApGDEDUwlT{KfcG3i~s4I;Hu=Yx;f+2QniHkG-}&G_;| zq%KA%;4``z*e{xBTa|Ei6={ILDlIEdr>H*&2)~>6{It?ak95gBDUP`#(nF;yd@C^^ z^P(h9_s%Px@(&$V3QR2S6yseW_OzFH-H*N(PMddGn|Mflf@C4jVfk=th}A!>H|N;; zW5y5cmKXz}I~S`?Pr*$#-LE8C3nPSXI$_d$ITn}I>w5aWt5zP$k12HWwj^Qy+%Hdd z;i|PBM?_)avKb_lB|6zLJ^xKI$4WxZ=Kz;#fs1BHi6cF~syMdkf)Bhgz=A=YH*E%G zhG@lep~C}Z@V-sBGsfp1H8c>M_{RgAI}oPzArl*nfF?CqAVYu>69g^P2tqB!U%p6Z z)BXF!uKLrpFo3WOtc($|dN2BJ^b2oX@V)lkMu%wa(Q|%62O9|4m*>>-V=m;+^j1L+ z!JIqUEIEUnVKCUDcqa9+!$LRD?_xQ2sP~T}5L99+?BN0KQ+@*HJ8d^YEe&)jE~Q}L zuf({P#Ea8sNfmHDp%Pt3Xyg(RnE>T?X)!aQoGvGf{|gBvrhmySS6OjxkMu*oq{ptt*J zuEDG%B@5SV7|Fm1!_|{YRHJ((rNPY`+EAS^Yf%RcVUV^HW{;f}i~rTP;QqQPt@s7e ze}aTVvZ%H8#!5x>8NyB+AVL6Pe<7VI=>!}L`>kLsom{G?bXmvB#U9f?v(VJxB$4``w#Wrg$}# zhaB(kFM>YKcm#jguPduLci4Z1{@sCZ!rw_YNG*{au9yny@M=$Du0Vr^S?`(8Tc0v7mF=EU43$hAzVOtY^pi-u0y zJR&msYh}~{o|d!*??lSTKU*6I(0Qi3Uyv1$jZNLBj?ZO25gi%uBZIkc zgh#nVzE-Et#a_G0Ae0hmEnwB*=`My)w)*4X7_IE$YyV&3;#WP#fj3}(F#aT5?DF@` z%yMDc0q*9T>As@@uz9uS7a36U1Kygo%Tr3N+o3d;5@NnmLVSa8fL=-zC{m+ zx0x9kA6@I@YITZ?Dol0xn&1O&B0)>&BxHCXhmb}yT+C8;1PM*a98!w>)ube(ES3lI zXvvdBzzM)DvA_$_l@ChVF(Vz0y5sMV#9^?5E~OIg*AC`SoHjhe+1{eM`m?ljAPfr9 z<0f(;?$1^)xG-~EKW!hg7(AW<+uf$fDS+C2Nw3tKyWq^b`WqtR^I7%oNY?vrSqa!5 znb!e^S++U&0Y$f!QWY)iS9_ISkq0c9WP7gI{90~KKlZgUyfy`HcaM*vxF01zA{Xmfgpk--TCR=v+>iDyJw5%E`^p<=)Q3u zjFM((%b?Z?TJn+_7V2RV998*0QGCP3TC{_!n-G5I!SMxrL*E_ryXSc0(T(zef78Z^Bpv(R3Rmj229@xOB%^)DzY9Kw+w&zRWbiw^ z28dRGjTC$a3RJFN+sRfP3r3>2K7~A2XWEj*wpMTWlXc@OV|PfUq&-K&V8cR96+mIS zpd~W-!tarJ^Th@M&YuJe5Es9G=H$P#jDDpJZ;;|)&ne5i$(vUK+8ph*(vC-|_D{#{ z`(~sV+HjhjsgEQ=%EMy%iw#aANgYW4X|jODS{ul>8QjT|gJuk?G`~`W_gvD>e-VHL z4YB_^Z>wf3_>q=Iw4$d!+DrfvOGOi!=Dq3oRefi)Dt+%#C|)Sh%d0r{)zM_zg8Lj{ zzNQ89jiBp;wkdFf$4b8X=`QEkZ(qOrs+jYaj@K_CBe3~B15N!Hd{E6oM1AQz^vddP zq5u7K`_D%5Put78mYjWZB?6Td$h;?|ybk7C^zV8-MWJymf+0yt5i?Fmv!NRRxv5{b z=B@DMs|9!RAWij=(aa|Q$wE`yH~Mz)$bagR=!aM@M35KHi*sq5$Hrin_|s`(M^OswZCNOFuT6f z|3K)z{tm9C4seR8@&iAY0fd`Rkt3@=rr`s$oSN0OVJ!OWd1hTRxF(k~M%K6rJ@`S_ zvN(H+?YDgj8*%JEyZ_$bYVbqj{HgQ?#Oa@57S8J{;z*}Lm{N|nb6y!tY1dhu>C>g-$}5+ zeccD=l~-0z!`Kwy>XX^f%pjpKcXNtFci;^7Ut&nCi3`d3{+je+%r@y3!OzbW*J%u3d04DxUfF zMf7X5Rlo%=Uv(f!jELJl`$uc*&y0)WU#f>S>}D(9;R+f67WWE^N8nA zb2JsW;h-g{e3S>9G;qP3W2-+sk!LripS}=v429C|gEziY%q!v^--~mJ8z4{0o>R zRY9PHa`(rzi+tpQOxrdfV}~gByR7SDDnGW+$qV%WjRqON=y>&d`>R*4E$Wy)CY{S5 zt`gm#QDq86Y9&Thzwp=M%c9QXj2J4fiZu{ZVSFc! zRgXN8npP(Vi#|8)<5n4N8FY%&z&XRIN%kw*wwRP zayJn~M8rT|37f6bXlAE-teVb47E@ulDQTv{tAn;LnLNnNEXjs7UU@25Fq4Fj+oBos ze41AJp=YCry^*4?^dkQHud+a*MCPScHhWDO-R5cG*IB3`-pzJ z@9$CVYv0kyIy5M!%EoX?qZ7=`RY+ocPo0ROiF+YGeD*7=zvs#|-$J|Sl^svu6wePL zPuK0p5-=SMytg0AgqC${J)JEjTC1H;c}e*~CDUZqCHcXW#a59o>#?BPrUv!x6=aeS?aAC;oV-J zXM6D|SJ-R+1f~DwEMd12b3U}&H0?UdIi9gq)~)xGsuE6fw0vR9M5ZuV=RW;H6aIcT zQbFTps{g2ehp5rIf{6T{v+KAUrd~F)F)Q)?_G!+TyU#5qCc%zTeLv70kllLr!*$sr zJyNG2QEeh6lHiLdqIk~?78sOA(=j7;4bR=EH#u%7J@yE+RY%L~xu4;3sMdNW)0zd9 z+XA+hiFJ_%O&vq>WYW0h=>8d4P;leyprufTK4>u$K9`F*dXo3rTU7L~+&$PZhz>VD z)3xq)qy!rW(NR`7RCzxZmVbGpoL+rh|B8Y%-+&`orKEK?N%7_R>hJD_sJ-#GX@?KL zwTf-w_hwbvVs8?!-_>|v9vigUBA@-3+&Sq_t2Z6Q09>o-daq5fuKS$hq|sgA#zv*G zD9x~Z>xKK8a+=F`!+uV0BuN*!O=x9FkZZIFu@mAzET0%Uqn|cQQwl3DEsctSjiCGS z&pJhW>Cf#ljO)siQ!*ndCyo?p*st>{O;yxB^loyOQoK{so5hNagiiL^za6Vlt6^pn z-S=qV)Ezwj(~^@P>?>gVn>$5;{^r(a^oQ%SNW>X8L*T9t+@UYY8M7(L89F)n`Ygtl zH124o0UGpDb!6#^Nmcxw&T{Pg2yGl4zJ(4SDVCr37&0d8@AEw-UBSp!T;jB{?hXPP z#ce&>16x;fXaZWWbMsNF(}Kqt?zG3@F9-=){pg+>CMM=r@6l^u8~iEd-!?g~bRYke z5~+uZ#on9(N2gQZrG6W>C;TfL=K5RsJl(L}cpCc?K%hunC~bi*M_#Q$*Uq)|4%BaS zQTwEuo_0L;8oVG%1hk}A5ma292aS>7B?A!UyA;zsF%ijc2@ z;Wki`uvdvKJ9(npWb_7^2d4sP5^4Bpc<=}Dm@e%!I<{f|BK3+c?!0LVcYDgk%U5Kt z%$7~Yb=p0#0O;)n$et29`L3?E?C1LGH2$plijp1ju*~&1e$vMI;c8>L9LZz^ya0%D zN$%5^0RqM!h$|^7mP6ydDarAQ{HRUb9wXa0tL=NgppafAvtqjvc7$xx&Etqd?L*+r z&JR^C^RiAN<1`!&EvbCzKb;yTE1OA@2kJMvwXXD+n~%?=q=Jzom@>>~C$|tOubxrl z{Lc3Lc}Onc{MoiK%7k=wm-(9j@&t5U`g`;N6dVj@7x~}z*M&r5C-g0qF-y}qV@aza zr_9dC7fV~}^U*SBf$Y~nocUZv7&Aj;5<%;g90O9Vq`-p!+MTrmVHBZ;h*pH7xl68o zL*?_{O6fGopwH9FD!+VH?N)gzbFCOd~|Hjq?Qb;e5kiM4DB2*6> ztF(_R@nN|$af;Pa+~;op__fn11}p25+e!s>4;Ef+qcKe1mt6{t!j*nGcpP;|_g5f{ z$z+0lF%vBomp3#3NAjTFTjhoS@9|G<#+H37E?4Ec4SPyImBWJ(3mb^*%-=9)&v9jj zR(LOmcMsir1%&i=>I+^2zSehaUfTuILnXaCW)nGmeKHV5=r}UuKLa96*C#0lh`5rh z;$}wX9-%*^n}H+<5J!q!9GF>0G06QXgFvhCAz8EKSxgzr#BqRv#+p#z-6Llfac4zC zkjSy+v*ARleczUnNO~bkED!zY-hi)#p@iiF@X;tSMgzg$MEv&yY9M?B zaKxnwkVu>ltr^cm30ufEl?tO?)0mZfxYPNKD%N!r_(|3HksVZiY{JA!ZLo&xW;J8M z48+dv#o7L}mA7{WZM;a*;q|9LwPot9tnTQ4?eI*I_a(gDNy6P{(Q)-EdgozH)ys=w z9VIQhy|K3|qV1z)6~t;~{2*kGJX=jB`Wxi4&gn-q<7Au_J&=ZBf>!*n1 zA}r851Bgz_bQDU@ZZCfCR2bh!{Z}u{5y#q-1d^|nMx9XMKOMmuDq^V=!k*u61Kzd9 zOONt^`)bfCo-18kzFV^la6Y~S#cKXA8;pJJ`55$xprC3pHF!22{IgP;5+AMHQ7h(h z!-zB7oqg^D^Jp70pWw5|YPL8cbaeC%D&0rq(E%2QnsC4o%uPag8NzQ3^=jU+zUm4t zu%3Q_^dPH;_|U8|>@vfPHC`u|`QwAEtn6bexS_5+MGp%@0cUaZ-XLVaH=A2t?p3Q; zJo)#A>}tYFY%<4dO`b2^%G{e|5j#OL{#(OXeD1HUQ$%_d!^Vh8j{4T-ks?;Nk8lPC znJ|HyqMgI+1?HfN=UR(g5G?6jA(`zpIf(sel$g=*@GCzA4_wL;Z)Mi^uN2eSJ`O*a zfU}^i;>KHk^B?Y>2|QTPreM19hQ?iM&fNju*%5G}#@_H?rETXcFxR{O?Gz9SL$5?l zROCjJ1c6fT)zyuubWr#PZjQd=<3~i8B^wh%V%d4O)V<;3By1mnM9pLnm(vF1o>Nu+7&;=W!r!smTnr-Sbah9aK_dN8qUt zo#oh(Xtr2|pJugrTUuU9NwoO_a7~vR4s|{4H%CuOTgnz$BoBW1Y|Q(-d?lYat0i3- z;k0MGD(X{i9ywbN=Hdfy#XZ!rp(eu=lnroNQ=6z;JdF; zr<&89qL^{Zs;wTCB9bz(E)k#8Dz^9XILBjF#}9DV>#G^toL2td$PBck-RgVF@|mT- z#+wP+fU|!_f39~thZv67I1Z4O$PXwGHtGKvM)ZYhDNAc$K@2+rl2cJ!zq`R%r?>vr z$CnsYaS4b>)@l|A=mPt+jNLK@EOVQ<`wAJvvn0CS_jrU_Y}Pt}>^h*w@_B81Vg%nr zv+3MUYv|`@g}Q8k^tLw3!g35y8C<(uy}jD236SqJVoc>xqxqIWs!Ze2Pi67${Y>@< z;>7;nUDr=@HpwZOGVn&EI~GL^{sS(QAR5Pa0bHreMD^i#+d^E((K&5pjDTshv}V8J z#I5WmMWTSl5;`4}+cN z2E`-+wEO@+`?Bj&)abnY!|6C!QNXV@%w32blid@48232Xr%D9}g}l*+_vl-dlp3#X zV|j$*-#a>%NC8LrC>@*GPmGE@@(*=%u;$!jRe|cu=~ja+*;tuS9CUVtg!cr}&Rh1k z32kamG1xg!BZj5Q)i%qQz#(kW{n+|Ls)2vuisC0**c4SPKQlts%y`L)XA`%!0O95G zN4>6vz3H}qZkm&p*16xaVVC7rJJe~hGd8gJMSuGoWJqZI74LH{W>k4T3k#G3Mhe=u z_8d}*`ENlepsF#)Kung!qTon|E>0Oi318xHzMLsYiXmgBEb8~aS*xwvt#2}&52|JE zKjo+KR|vG=r~Y}G9I_s+f1P~3ypTd&On#e)W|-I0lxDNMW@dK&aSA4Szjk}ecu+Hn zdAv6DOB2y-%GBAAXBiV_lcZvGl1Ouz6SC9deu-6gaT4lxqMSaHJDW*DY36OtW?MRz z5+xl~jJKc=s!*%|ueIUJTDuLV1eq!86bb8r%RZwU5gH{15zrpn%iFf=`qFpyn6s2WbU8)+?YOM*1c=4GNq z9#@LsDX&Wg&Q!(~mY zk}=r=otcMKpi5P6@zCChK6MU#9sYa!Y4(XkP!o@mp9+{Ubq+k0gK{FqZ;3U_g zJLM@f`je@o?&@K3;F`(AOgHz?wbM;YeR@^I!!z z7m&epWME(@)nogWR7S@Qu|1P+n??Cxtj zCtVJ}rSG{s^`OvL6j!&sapU{*>f`={k?lE(V*3wQ&0#$u9%_@WXqolCGXs_dp;(_# zm<5RMCFA3}Q;LjOl+^5eTg;JClqqg*Rz)&SA1EpZ4ol|rGR<<(_OxvzZS=uXUI3I< zEKnFBIdm5?39^C49qX^%_WJ_A4m!A{khQiu{!f!FpIK4^XmhbDz8Eb4n=PABM@D+b zE`18Cg^%w|0-c~O6cBTmf%^$?&HOlI8Pe&~M@?byAY(#gm*I;$s(j<{kN|=tGS$iq zj1H_vwq|y*Z*a3Xny`d@1WZ)R zqb&0thAYA=%)2iD;|^S>FWaa29^XHQmb-wb*hCj=t3ZQb#fq?H|5E>IFAT9`pLgGF z=@-Jf8E?SVO#M75kyY0&L7dmr|p>7(9rv{gwj+swaqEqt-WU#dV zeNKMYBZqs)OduE-K(c*HoeOBtcu>%f1U&m-Nrb%^n#%!SVYG<-jW!ziSBJ16h67tC z`sB2e1cAfGW2^i1W|v znng~>Y zgRtyHq)>O0nHy=@=4+iYst_xf^Se@aZZHVhtqhe#6x<}o#DK_*Qkj5!BShZ9K0;JK z*TQ+)t>gISgWGC*wN#?iOV3LXV(7iP%J}R{#K@ek0G`b91&jsTR3GI^O4|h%aGB#; zJOOgx<>d^?RPsqDBJqapUb73lS%6m~A+p?VMDrRw7-!tJ;HV8vU8T6dtt{e5$o$PK zYVB!DfTW6Qo>8YFmR=!g`$B|#JH|b6HZ7G#dp|a>#|8e>SNV@t8j8%LJ+XuTLbj|) z!fFyN_Q-Y?l4kBA8o9#q;j6;EgT#;bXU`v#Zcf6Tq!TUtHl@_&70VaKTtM$2Ey%hO zBNQPgCkKQn-Vl>AFnkdku^j7OCH^oM}9}iqMZf~LmESK%uWGnoRx=PCC zf8stc>RK`2l)786b-cn<~a*=biF2a=>;EVn;C%RTy! z%tvx(de8OOa(y^hGmQc!dCliu0Uj#ltR|K?L1uKRX zYz=|msBw$gG{1Du{WksMDX)$dZOUN8DAq|qM>my*ZU|CR{su0Cn=(FJ8gD#Ge@ZtK z-Ib``6Xyl2(yyJ?Gqzl%q_Sl#et}hZQ)~WwiJyvs&l}xai-$kRVpVN8QCE!+W-|w0 z?Jo$8Hu`1_>AC^WzdIkPhtX-&2iN_@uAw-J)zN)DG(<{qTWjqay;0B=NHCAA(r@|- z#C9mCD9j(mbz)KCX!|tG2(2*V33|t&Bd8F}zpWzd4(ts?de$}$^u)_2$e8cZN_P$k zA{O2&iRHdF!{^R4Gy90ZO~A(bYSl$Xbg{K-X6|pjZE?_!07;wt_iMSj3BnKe{+!NT z`&7Jk2^>_o*`Y-bCT_;k6r5@DWEh?O$s(=yRH!$y&Z5}OM!mV@1MKl1KQMk}kX>pt zd*Rk*c^X@@J}RAV2;NTZpOUq;<%#8V5rQMIG8#rrQxNJ`&j~8e5 zgjF&VehC$#|K%x)-Iq}Kt#U7}CLk3s+e346H%goFZt$ir6X+rZ>#e|Q791RGzi~$n z-g<~99A>9Y+!{nxweR`~{OMpe;1$5>9H)!x;mWT>MS30?#)1iRbT=I%c}`j=BXr^q z3pN<+{1C)tK#4R(rp4PSoXjn7y{iGvV1cYKthxzl&Y8$BI|5+b4)QCISm7{~@Mi&)Zon#33p3LnbGtO7@aCPZDzF_6HJQ`jfSUQ#- za3L`0nrblib{2y0U&3_#$6h~hUuINOh$FMY82K!LhUUTDQ^yq(Eg4!HmX2SFQXIc|uU89x4<%{~4Bbm)&^yTB4Wc%jsc zH%mj+Z+7MFKz2mU0-)S;$yvP#vLmpm0BxiZ%Qr;@BxJg{dNh)mIF#a;_*K$LN2vz? zA)_VPz$-{v{u{xlJ`$NNo!>~Bvhvg%Cp4IrSo8>*8OAc0v%EPDoRQ3YKPl5$l7udi z1J50-`?+@cPlfN#pZ>BBUx$5cFn`mR#_sTrSx1G~t^Na<1&ef}i5#zuQ7{NUCA0W7 zCjhm|M}8Sbo-jw(*AVv0mZ|#7uI+pUefa`QH7gDVKvl}Xx&F_x4sgWJ-KYP>MGrjz zY3EGUht-m+ZDO(MpieJAFG50%U_geWXtn`_`OT-Ym%&cbbpc(2<>I}{b#|4EC@3Ys_++kY365AwDnx>h zK`)Xn3-WEK?AClPrv-LeXj}iL^k6x(J%Wk^6DDFeqaTHG^= zXKEf%sV*cPhA&xcp2|3y*pijN^-s+_l?$_!pPfLLA%_Q9kRFW|m1~qcu0%7^J^<>e zo)S`B260F~HI3Az`0c&tVp%1SsBp|NCrT!GPS3fO7*1)bZDoZ}z>68I#L%w{PO@Nh z`M0ULJBLEpiwh#6B=#YqFH<_1lNF?NlM!z(-hl3~rN;yfri2=T$ld;4##j)lSND$h zq77*$3&xoc(Twm)tZiv2wRip-xX$E!bdwQeQj5dv?>cs87!14Saisacew=!tBBo4m ztdXH`kOc&Q@rz0E_ejAKr|Wiw0IiOvldtdN>KM1x`|!j%wO?sTeE1T;Cw@tucel&< zX%f(pK_C$SZ`=PfwIm@iF>$6OLIET^d_qYlA=`vGq=Mt~BUq(}LNMyO=VzaA0jppX zzA`5xgvWaX<;ZitHg@*tG zg#6V>DR=IVTSKt}|KVTtOa%v%lV^V{HC6LM5D}-NlOlm7q&%zgc@QJhN+3(lnsw|VIrc?k8R5dWL8|S-BP1#KPmB>{OqTe6!hhWvfpPS%QV_^=+ zA8@onbcX81L}4Z(TIzWL(*yA1zt|G~Gi{F0;|na1}&i9t;RfGPV!!RA74vp&!! za)D{|&T!F#t_Pw~1m8B<0`a0Pj~f3RZ^7Vax@l^>v6NyBk?Q?>Zx(aEAl$j$dtRK! zs*fDt98weN%4lfSWkRB8qGudnFwMvf7NU2`WW=h6REXwp)d^0oXZsV%Bj}!2*c2X- zw!xG`DWaWeQX*_Q+|y166tZbu=hs51B?AflbE`)+kN99}g$dIpsf;?_L*vUAojKVJ zf2;wRLGY^+C+PDbtm7ep(c>)87V87{TBUJ!u2;uB2$^*r12C1Qa&Po@*4w-DFqyC? z7e-?vZ<62$lL=%p`tU0Ekup{9RJ7GTnpkx+Ofk6QUq`+7UsYANKcV}tf5NR`mOq{J zIHP{BV1fs9_!EC%Y<$NxLbc#NlGxpiTM?`0`INC(vxBsijDABAYdS^E6c5T!luX&| zyk`IV+?8du&kg>C41?*xa;62fj z{){G7#AG9;_d;57{;CYT(<9p=7H34U3z|(Iaju%y?KkFE=3It@`t!A`X2iOK|9T?} zvKK;9yR*7}c2m@I6&+reMoAWL&8BIe`7)5dUSAoe?Y|g^X{g^{4P&co`Tetn+ornn?>Kb@QNKi`WHknlBIxq1g>2vh(tYU`e`<%0>K z&1zz!kuwZ16_E&q*&WAZDH@?EHgn=L@#STs(;JF9)|AyRG3nlS_V_< znFP;-z5XD5zrv3r=4?cQ!qlpD{f?Sd&t}Q0X&C#%5Y0sXt{KgRWn7e%a~O0$WyT=y zY1X9H?4zAz`jX8^2?H=Zsl~L-BcHu0P?D8TlSr~|; z6gpC4Zc~07N7hdAf*hq_I5|O0D}!xu1f~R`A2?P1k?X@79C#&^Zsdv%2nqaUi*^97 z97NS~Ch}u4XLu-f8Z6D5J&WBJ9@Q;>F@W0YwdEv~7a0{R)N{G{1izii#9@Z$3NBQhnrFJjxM2N_KOZW}575eql#Vanl~bJddp zd{vyV=jD}=jH75MHY6x88wSU>+_kpUdE>Gf$Q06QC9gULlzBbB48p(CjiEe`NC{ci zjab}!2dFwexAqmM+S2gXELsd-bMV5J70PNtHgOaFsJJcba|#y?Phj;R8QttLF8|Ag zb3E(}t@}MH=9!b>AB*mbxGK?ftHr zm6R}(Z4P(8?y-71?x1k5YtYhUvcatG{ry3TZqo$(jmX`8)!J`%(b`sT|F`?Ox0m|I zM5eOJlqm_yc)UOm6(%!LbPzwo`0O<=uLmYghzv>Z$DKyk?BvURi8b|xCOTJh>HXnj zkzIbWHnCkHzI-w~TWWQxt#48s9Vf-%|1utV6{8rG3aBGt%27cu4CWrr!1D^aCdQaJ z%AOAaH-Nz6LBh!PyXa@H)3@WEI{P{s!(DL}o+yx+0S9)xfvs;YeG)>_M-}8nih5U0n<=h8m``sfy>^4->tq^VY$zI2F9?9udndt)eXPE?|HcQd4=(0 z{j^wr^}4UMlbz!0B|2S6xF!hPAN)SdZ!D(I90+}mDl+U(IHG#}h4bC51ZI0E*T2@Q zI^r}NQ?MKd>T_Z=fB)UQ8AqyCA1~_nC&^5k&0k$(k1)`CTX&~o^R}_UW%V^csbH;I z8c$P&Dn-S2pDS<(eL}vy_+@_7l;eKs>GtvQIp8H_W@qpAd_hDX0?yhu0$e?x_Vb3f z2cw-0WCiXaSn>$#T-HubjA$lDY3!goYC|g7P#q0pNgq$-+_gEjE-5Sw{?^3z9A&Zy zZ|laLPtET+vCiiMh8O6uWD(gGeVMef{PyVRt4)E1RcSRU7IpgOA3y#F`oppA3Vp+S zd+A+Cly^6%;ddFYqLdmBPp00aW&b;fdkF0QeSf^u$Z6Q`!kGKE%<{<|&}p!nkvcAL zSWHYy>B;c3&rGM@Rra>-C>CMq6gSfFO0YF)oT!?6+W$ z|B|cgJLD8hRT7$9x_YT*WGJ8yD+r*AU-Tc}ujm`%5`yoJ`DbnDxpR`p(HH68rWKOVa65d{1ZIm$257ly zh73<+%uAM}0t{kj$eud5$Fv0w3LKZh2vUDo00V9!WWkTMPO0!PVUD+sIk*i!!6t9` z`w*&bgE=!4R_}kSJ$I<-t`LeF)VmiS=oj*WvnvC{LchpTenMJp;>LU$qK?fNf; z9s9edZW2Zz{!UBv@Sasp4{}MBnaT%L|NCI_WRpm%08Ix?Ok0oP{hHpbI0}o{vV6y0avgG$GHJI|5LC zF?hN^-^^lgrH{{j18(jQ#5oi>pl6gcy)UhuUM{V=nJB<_Elh1{lf)eMb!#|q@v49_ zkUW@%V)%aIH)ZGjUjq*DgB3mnmchI07m4pr{BkO)efILj44%0#z3_V2H5nq?ngv1< ze(!#1Mz`7GbhTJNwDAr=!JuYPa=Rzc6#n?4DK z{)PWy(@0nsNjSBbzmcYtW3llAL}hkW_Z5f4rOZ%nXMCbUuz$bBjf~zR=j8ghRbVxdOK)=U zPVkvL!%1kDLZWm_{f>`LlQN6Ne@8zxcgSV7&*j!Qx@7Qfgyj1m;KG~2e`7w6a+qpx zD0NAKv?j|!{{8f@f|fgS!+(+AY7^3m?MM!m$IC#og!My}sjDl`OTm_3JWQos|A=c0d`g8*Y9HhsD z{7ukF2t4xX<^KR6kVJ3AHuX1)4ns?`nIGdnY98*n5v-c1TDFA$uGnTV(G|$ok#BfBamRza8g# zzwi4sp3lc~IlEr*qW@~)fl90#l>rJ+L}q~2@9O;CXq9*Lv1GyKSB9{2?pqAy+J?J7 zPZq(td>?od-r15Toauftx2tDGIwB4I`WOJwB9R(xoR@ZT*g;6xnya!X32e~aE+3Vc z%3iY`)v;!qNe*ty5pVv$#kjEz+qY4F7^#Ylr~d?X!bl$5J)krmfZA(Vp!{X`N>i(= zN)tmQuCl6Wn`)a@r%tBxxRE0$2^DlhiI~7{ynX5X*5{Laqo&!+ycc`pKP?BGRIYWh zd7myJ6=T7?Md#@O{-AR<)q`Ec?B^nk^l9{}e0x?~DY`Vik(BtqscbWodb@j+h_-2q zg^o)fYQH3cD^oWV7!3)WJjBOx3U0V>Qx5pmZ)3i!q2 zWPs{-@o%baIJd=LFknVK07ar5jOuZJ9N-FM13;(A$;XE-4=hKV9!9)FT&4ZEi9{ZF zue4ham>zAU_fn~HB>gc_=s3SAHR=(6rqINn1Um^2z7kQ#J05s)P>Oi-=eV-kk1}_u zOY^8-Au2*3oVQ;J;nk_+VY z8>r19yKrAgS6*=zF7PNvFg%Bu{eGb+G4{X!M7*4FKKoBbTUwx&H~a;jkU~L0wBSa^ zXZ-wf*31&qS9|o5Rzh{WWP#!BC-~T%oUhd^*yai}ks6#@ke&j^HCymq!ODLU=@SjEugXe6jf+WB_#X>)vhCdrwQNpUgVg$51KFPwtrw`)9Y96-n^_`2K zIEncVcmntCVQ=1Kt^WZffH=vis^Us@O5GFZklHqUj=<}9DVYmS;d=OgQsQ4RDT&6zSN;g5UxI(1q zm5BdQEXLh!F_^7SPtc7BmGT*MVz}El5!d;@mZuv(DN8*p`(44c`tzPxo7m9_R_l>o09z_Je z=&UQsE|dr>cef}kT?%6g9@M*LI`tk^`;l-oUz+IEx;6fw4htDsmB)_)Y?M+Tx0}3+ zZvK776j-grk=ar5!R)sxiknLskk@ig%LiTn?hI^j-0Gzsc2etMMtu-Uw`($c$E;Bm zv`k^YOqkNT*Sqigh1D7B=AAuz(}zXz<0rX#Z6TLAwHFiBL7ru}CyRCOA3&_P&s}kC z^@x=#??>~w=a+4PX2No88J+LHV)K2z`SBn{U+RJ3nvETTRYAZT-;ELh#iNSgBu?(x zthg{=+DyT#`pJo5JI(inHc25vJ~51{C3sC&k71xNQYE`>`Ht4$Y0w`KUlB$Fpn^ie zi3@fW&TulH8re9DSW)AOg1-DG%E^CafYYNuMDYD5=6lP)MQ+5NKw-OdfKkCn2T9xE zW6FR-3E^MKp>l&+-C){t>E7<=v94!7cS9M+w$%>Yl z%2}`Mr|u7Wus-DG-ooC4LJ3RwwJYA^uQ_(10l7LPto1c}m;`Shz8{6{za$=d@i_Cj zML@R}M{%lWwe$v-GLv_iJ=fBj`RYiaV-k2)Af|bTlpRo>4H+L6Bk3A+GVr>1ZVEOL z64tq=?`PUrC1KxJT=4ee*?Ebx>bNI99r7bF^6v^Oq?@lAanM|Hx_f0_%_9 zLiO@^7(#~A-NNKtl&c(OvpXtCf-dPSNByX&D^@Iw+9Q>ly?*(Whb-RGG^M_>`RKK%hvFVnrk+s~Y*$ZHH@Aek&Ogo*bL{@Abpfj<7A=t+< zGCfH(G#V3)u2UW^eEOntfph2n*Z4Ptc*p^I$yE%t9bd6$108PwT$_Xx!c@NH!2wJMH$NhnCo*j+Bz5dR7~K$f5RcuR z{$3QlJQi*{rTWz%`lE}fdijOPKam_P9P^(2z?c*}fgpN`Gw61gE2CTlb1Dqf+*MS6 z{KZW1mi;KVJkS;JYj8OyMzFDQKvU_{XIpAIhx64@PM;#p4haCegBd&#fTN*aIW_7T zsw5Oz0=V&dJJP$f;^~jz0M*4SW^pV*iY&I!lT8JAQf^twJAqK>$s$3R7Y{~&dO07Y zG=#n!q{3T$ltY{RtUy_B|HNvjO=mfXJl6?2u7diE^e<~povwJlAi-BX!v=hDR z`?j4n#FzdG7h+)+z+KqNe;_bo4D418wnI~o>y^)Y)G=p9^k$wG64P;$ zoliPBzw=>t9v~j&=p(uTZM!$SYUY!W-K%Q<696<*4fZI*Jy=BCt95{HcE*8t5tm(! za82Odp0L-*=)!P+%8Mk_@881x&bhN)%2U}PwCx(r=ssoxl#=uwMzN$G9q$sk2W_3( z%74hRWN<4|%k0cvd<%OBJN2J)brp@%?8giEWa9|^;7UT@DvJ}k>8}E{XURxb=<{F$ zIe}5{C+fmpi(k%P_&>oE5fE%h64%LIgNCyqKE&Et*+S;SaHqd^M$yHAuJ;|_6N9)e z!WOg)j}L&C4$N!5ojZ#ccjgBzE4xko{s#y8&DmmFJVgn>_-mnczTnvS*4!cVp?QUr zd*Q6BzJH!8d*eY1 zzpLz*jmvkhzQnCV_Uf&xt#5KoXrd%@gKq`hF5lM__N@WnH4pd+R%0f#YQ5;v7`O_|Ir^`^{UaNrV~dh3xth;>yu6L5+MxZ4tSZre+BcHO(| zIofKwqZPk;5{%+G!@s-k#o1pZIhB$P+?R9>QY|DO?))qHza)&eNECBzmS!d1k z%vzR0&$D#gbmo{S`32F*dg{)boUD}>CXJB*R2q?+8x;vAy6*ap^<;VJfU;W)LPCax z&qZKe_>xgdQ90;)tUE>sd|}G|FOO2f&-bdQKXKcVe`1E8^JWcIMsS zlJ(6OWc==7H00-J$t>#u4+vz6*W*xQf|0Kc>|p(R_l^^NbVEH^LjARH=u@#je}&btBj#xQ1_jI10Q zc;Xn|XJS_wYt0h^?4vp;C4%)Rn?gTj&8_Rx#|?@75hhSEF+kfLyb^ zVn0TRKir^H1QD*^ zwzn%mnsJ@J@>Sqq#Jw~MtW>7%>-g?^=O7-S2`f>n&e~aP5*V`$H|1q2UR}7_M@^d7 z5bx9*%MrTOn>%DHiv4>Qv>wYeicJtUDN^elHOdg^;JadJP#oV@x7Oj_a$@35RPjBG ze41?!MCanoXrG|r5-xwBX+M2j~^HFS`~nS zj*^N}esYIvOog>uKdDS^(7!F9l&z>2QotwZ;Q~}z*&>M=-9MWtFCsfWHrkz8TIgz$ z)N>2EvQ)DM+LV~Tw#DBxTG@ok^mz**hwB>+_amt{KLe57>>i&f>B^OubHGa0#q1Q0 z^Qxr%5dVR1Ogk)O?LW(XKR1$r)KinwE0flZ!ph;9A4fadM@%NoQ+Tcek5^1qn+T76 zSrLzN&6P+zi3!XSpoCkk@8q*s67-0qBQg7whjeJph+qmU4<5;380L@e$1}?WH_Cff zwU0gPsj)iKr~I~NAEuVwH;qUJ+g1<*jaewL6!n7L`mIZRPtYML`NyPm&KOYnSrsWD z^?S~gz80%BV1^nGH&FDfJ7Q%xr3TlXQQ)>%A5M?jHL6=p^lJfP(>+u;R2|anH6+Oa z>;Zwh=2UbF_#lZ7=9y4A=hPBQpehs@5)!gof9EqGmF?Xx#0PoR>x1k(&+`fCv-@xH z>@a|25v9k`l)a>bnD53GgsmXhRAIKl=)BSw0`M&~n%0Aala{pbveI0gS;p$pigBlL ztDmI#k(z#=xeu_6i1H`NQCxf&3W?K4h!y~zM4$VFX&Y>fajXUz*I@^j>lqm9?3MD= zlkn^0k7LH18wXPvj=KH1HG;?C5aIKf zmuCS7s>mNJqs^7h*3u)=|Z3G-9((>S-Grl&2Z&>(sZY3|v$hz<^V zcX0dX(mT&>_lw5DWfRZEcovn#-6~t)8ZG=;BRk#+e(wM>nP zJd17Je-Py14aD|JXmLqoV4Q*BKgCSsgRuP4j=S=^|otTF>^1+120EcLeI7j2RNW%Bnge%Gj0)lM$D z%awO)=jBG8>dY)>-TU!C5>94MtWC(eve{tNq~B5@rYd z9?bLK-s0}=?*D%=bD6iBwXb#E5Evf9<$MEr=*Nb*cywA$=QSpO3x6p-_z$%QMcwT+ zP%a;|`HB;~?3&((66Ur>^5j5yOPSt`(O~>%weu23No$5*&9Z4hb|)-~qgUpY(3$OI zwx^)@QK`wwHGfN5KA+UI)95zZC;j>lmIHB;46;TwfqketS(x}A#lBy9N0j=48hYi734b_cmf39JU1e(OpEGrDlK`>|b%`GBuMH zWYc}MGVWOso9gN5?KoT{@d1%+l$-KMeOC^a{2)cz>k|_mzEBPht3p|F^fx%~a_C@m zOpHnRq!n+v<&$kTqXMEZ>6*fLe)wTkat2Eo?`ty2S@+L;CB-0~L&L@Q`E&KLombMvVW$-saKKzAj8&2LGJN=A0S0x<8k7wl>zW1jJN6?nyeHeI?N0?o`RgVV^zRz(VQ{(xMiR=b`UKO&-f%| z=l46{Ll_?)zy76qL%%|hWO!9#4`T7Gt^6k8L5|o_?;;~v*4HcOT`e$%Cxv?h&|7K4 z{Bq)#pC~|1W>7&N7O#WDxUVfMJZvUo z(V<)z>6w)TU0iV9otrY5eWKk)Yw=9o56sxSPj9m>F5QKTZON#WqAB1OCh@ zF^>*a#m`t;Pjc=#-~_;Qp`?n!s}o*dqG!MrxuC`sKW2v0^{oXK$CHV_$e7~9FwOoQ z9xsokMjGVn-itq%;{L4PEVb~b^bQrg0zjh3UI11*?8hFxOUA* z*DN#LS@akTi#nY>-horDl{Du{GjQc@&_YP2PRf#_eBkDS>?eZ+8eV=v{o_xILy6hT z&@>(5(F|-q$+K^Ote{v~9*ygVMq>ig3935W&Pw`p>vo=Qxl*-4GW%sihW}Ej%*SUZ zl!gW^j+kLAALL{&mdwRhrKql{yVOJYjoqI`PJ)+lC9k+{$Vd^$C{gp@Xrh1L&LQJ& z525g^EJ}bsw6XbESsg@IL0&U%0(A~KtHu=F4`HLqjmMKA!!pC6uE%3Er z7JA$oanP8GYd6xM#A35Y_yZmj?kihN_^8J-9xhdCZnW)bSH{YwZm>F{8S04pJFa2R z;CgVT^E3tP*S4p0YfKtP!q1wUE3)@DySr>Jv_GxJ@C@f`SCXL(x#Ime?ByKi84p+w z4*JmEE^%LR?WtIwZ*Fo^`tNdqb&2F6PISF)gfjH`kXF2ncI@eM+x8ko|Ekx1cPIAV z;_dwV{)w%*_@Os}t609Uu16_mAxB4(s*$vvstaFq{xGXlnfB+o(RJVr_ zzDI~XhsI6G{;o$!;~HoZJz|`%!2T3>`rqj|GlGQ}>q1bx){OI6ir^4zidtJ@`Z6{^ z?5+xiu;x?1H-vZ?(OkWrSTn6gzgC-gllhVfX}Zx)W<2fw5p}bD7K42n@Tb3)-}R2i zf5z7((QLsb4QPkcQI@$1F7&g$O-P%_JqWO0-9Ek_YCG| zCyV#5PnyGwBp#ZyS~jv_)1Ik=IJ>Zd38hpm**@wx{?va7h}7yo-*3*~xcO>Vy>59#T0 z&+$DEk%<{0OY2J*4rr%V&+JUt@crgAW!LV~Kfame`*2P&f9p1;VfLXyHmOX(N+Nyt z45Ud!62S}5JsZA77mD~P1vXpf!}57Q*Al zAeSx0Y~e!@YqKlgk9cKF1Pz8= zGW^%vu^E^pCEYU~^G6QTbs4fq^m{i8(0u_A_?<1-=jgQFK1F*|If2pHduW3uax+-_ z{bJdxP=GNH1ysUF*iiATa20*zN+?qMWHzAn(0|Kk)Dy!L@PqMo5* zz-c&hzfe&>bVOEyHJrYtY$-tJ%IUVIP?r_p-%TC(R$>NHgl?0Z)Yoe%4)Vhq^>f@7 z5WmZoIEZ)be0`CkyQ)MN*50)IQ+k6QM)o{L<`>>O*x(IJ=SZJz zJ+g2bj*F}ndE@+5x7iHy1zbFYB-{LQ3W{m2p|y>C$N6x}=P#v>QEvLXd~-7d`|Ovl z07hiY6J2&y6B7=_RP3W(x;T)ElF0-DVAvN=d=J~72zu?!hPN^h+t=V^2{~j{daQh^ ze{`yG7i$o7Nc*GIx#^^4=_)rMGNE1UIGh&b)wq@0C}e;`T%IMe=p%E~t^_JxI^0wC zAoD-{0~W-HJ~cvW)H@>+$*p6*jFB$(Eskg5RE*Eq2vBy;e5{0L`MI zSN!my@oK;MG9&L&Ph@f9thz0mdJ}xW$d&2hS^FU@j_znc}z%yZ&7NGl&!GB-E; zcFNlUDW2dgP!U+755v=}1Pu6f(CaOO#ph2+j-fmE--jP~e4M68+iv5$UAnu8VsLQ3 zpVWEE^;w^*xVrekvk%De+w8w-!(Z@hY)(Ea%ga z4qf|Xm`ng_B`s)+#CJJDd^J|bWN3RrZrp*?vy{f78FaAQXXr^u1ZR!2yP@@du{RN3 zJbZjZ9M>Hj8tmt6r(@96H4F)rr)K^fVFgPZ^_j}EdtYV3@+WseF4F_|Gh#LTtbD7U zA;y7|n@=&%n*~oX&|D#O7E@al6da)vU)Z)+rwt_%8mFIrKG!DfsuO^qhNA z2O&t6CyD8kyM!ApCnTE`Vo@29Qa@b>cdEaQq32}|xq;yph;@s;{_7l^2vS}_?l;NU zR^3(@4U9zurTbuat}SnC%XVdZR|p&n5E<_wN=O@P9_m0_;eC8!X~{G`_vrR-^Pch!8>g<>aR9*ve#1 z$W^aKO||7V&dkJo&!)!|4HN|o_ys_VCwH)SN= zXgx)l>%abZSa9Q1=I3^>#+a*102L7v2DV!Y3P{$&GBU^#r(-@oiyJoV>1z~Ha|qg( zwu*awu9x4;SoL@G9k)}#x7@U~bU%2VtHAp~AEUQwJPGC6P`NQoy7!!gn!HxuV4l9I zj1^X`_-`zwxe;}-!wMtJVOnTUV=mg~2i8$SaEU;JJsew#O?ibPB2Iqcp2S>{fhYZ+ zjAm6;X(B?O{Iw24EMwC=KC{XJoR09NB~ua9y~YL1rQO>fZ?t*b%vH7RW|ZdL zi~)GJ;8K{mi%~mp?0g$(_z5mRQ;i5m_p=&z9d0fAq7akoO6Qv3rlTGH#Tx;^#RjWj z8CbZXw+9dE;fx5imKUv~w`3O8`Us|^CS?39bMTj*M@Ud?G7e5=Q*{5gWj#{H|51vr0kz>y zjb^@LJ~%v7Ku|=A{r-ZJ7Tht7jG#lLab zqL%WLpK}YS&z30ZqK#AQg-hbFpvC%i`Vh|WDb1-lZ6`ZA5xW%UPdY5gyLc)k?;tkH zJe45RoxT9CTV9&m{cBb8gR#vsDJiMl`TC^1o0+_VWDb|E9b@nhg2}XQN~Q$6QBTeo znD{md4f#a_uwwysyU`~qHFa8%DdvSAW#}ObxyBvT^ii}U&*6j~h3ruXO*842t#Spr zoMqgTvvi8hT=R@8JWLMw?I2|UN=e2FC>BpMww$0)&^JUEdd~RXX)qc+6%`L^kp`X}k z!NHfa^1y%{0|Jq=Um93}a$sEr<@40#)6usl&-pk<85r_=#XaEGe9H0r$`g+7L5r(w zEh*fsc||sBm$v;PoCnE^Yp;LmqfzkQSt68~Rvrw1q*r4r_BH(6+-yIx3F2@Q? zV-EG$WI}16hF%fCaj)e8w-{*J=i1JY&ik1e8H`H!LLp?f7p->{w4AuOr-u>Zfed@p z(zY$WotZ>kTe4Y^8LVSmZa!07RTmjqEu2}H#9d=!4{2Q9ph?&W@b0~1=DPkqE&C+p zg{XWFU%7VSJ}gwkv*RNtJkm^tkSTe9VZa&FxVwETlgmz6pI2Urv4|14 zR0=mT5YhuNaudk>hxcJw)v1hFoEwSHw7zt z^9^1+X+u*d84m4`uK9b-zqFY?%{WkP&=xYl-kdF4q%wjD{CP4D0P-5;zJqLVTiY=~ zv6SX2HIK{A97(dL^>~WDr+#baXLltYc-j5;_P-|?nVHMbsg~G=wwpae_n`y@!@Ki} z^mCs-U7_ZD{WNtG+Lzh}DzF5K{s9!e)H=&-fmpjJB2|6;_opq&;AQ z!-^2;%9dM@jUzl31NP+<8EPm=0fD~6>&o9>vx*zfI;9C-+&|bw26mCFT5jww?UtB;I$vmbRqe%6e`X8;WE$@7_Cb@}j6 z@n8SoBt@O@bBzgff}yYtZ_4G=tkw?i)?*^d?^l$WL$axl%RKm3R8ju5gc6DBiOl9} z`N@n=rHYd(M2Q}S6UGm$9g3nXOiD_Hk=U%P(9h>?g}iEsq_gkUr6U>PNrS=_x@;cd zHImb1kheinR(TPT+yNcD0ea&%mkAxmO~pTn$dNJ6LXSq=c(e+4H!QVGy01N=5#MU+$$V)=?JcAgJ*cF~^8voyUC%>QJ-3G%=d6wOE`&6)F1bO>sj zddCl`EXb5VV^6s#xcT5Ca0z#PSFPkzMsYE5dHmuE+Y^dZS5j7X0Z6|uYs=B)6ZT;e z@^?R|^opV}?0+D-l8mjgC!?Qx16p1YdSN@a%e}W1*=~eK>jtAPlkEGoZ zmCyKPF`0<`P;8i2EPtaLxHv9+x$TI{-Et%77bVsOi(^>n_jRT8!u}{-i8jTh2DRBl zChy5g%5pQxP^fR%nF_Gi>*vs`lqJImqaQ<94xtjm%02IJ!X@E;MG0%Yhzu7py%&~e zwlYi@LnR0z725|5Z)A7U{aWA~P2bO&cHXcSjBk+!#Z3C-q7oStF9sKHpm|pj!EevD zCq5bZv*o_(P{MyjEb~0??wW+zz;n**=E{;VNLQUtpGBr+^6goL`E-jrN$bvYG#WZl zU&f70G&LoLgHaqw^5(B&;#Z_};piwa5AkM`S-84F$%3+$H_H*sAeVr2wbxU0nZCe~ z6~DU#(+!%jrVHzFDZ;Nb-tXqhIH=x}=ZZ1!#7x=}wQdXr(IQVTvwc;gIc*W#o%5Q% zXu_z!5@R9EXs)umDJAEcwXNkVb_Bq_=U0VwK=tXth5(3@(O@G4>+p}}03gzLf)c+2 z!h?YA9jfa;5dt8T!FM$wLhvfv-Ika99;(hU;9~fxOP@_6!pJ=(_mB?>F}rHFeaB-w z&(Bv_-+dBz-0Dn;Lq75dF;NCnq{ehLeGDvn~|M|Seh0HLRl^e$~AlA&!EvgnJmdkm^oPP#22bdEO9 z52T+s8gk0!>LzPee(L*Bh0&4x2pJELmeuGb*+io;CG=im-=Sbo4>gGX&Pu_zfcXe7 z{v=R@#bNcCz+|Km%rxuRNt)mvW}eg>anWf2SpqVPq^y{>DApG>=I;S*;H%*L=G{a9$uZ6l0hzJ4^q7wGW+| zRV^bfK|7Mm5bgDnz?QDmpXNm7r+_5|;8HLIe$AQ*4Vr6VdBg0_8np-^(iahu1@F|O ztZHL-1d1*GB^PH4x!NNm@x#p*eSe4}SFwaUPC>0U-9N#Z!gNCiU z61i)K-r2o)The53OGz{2Jv+(Bf=FqO^3Nu)nf!2hd7K*{ObRCuZ5ID6fz zY@+v)?ADpt)Prs;8vXBy`JT$L1n7*})w>qc=M7jc8rbH%Qkz7NjS*%=Qy1VXp2u5* z?kr6@H9XhXU?+YU`o}(HR%R2sK26dpB;T!1f;>_NrYz?KQWIi5^Iis>srX z$!&}3Z39*F3S79tI>(Dx*!y7h{R#UY;I2h`yVh@s)pB}2%Jyu;x_KC+IRpmtTQ85U zt3n}}`tJW6kjho@o#J+(8=)L;}X)E&Tqjjj;ayI-Ge+gMIJKr@n>aCm?E%48z;Jm(mWS{O>Usz7S%ON+N8V$ADWQ%C*Hr_9Tmzsr} zENNgZK!`AwK^Ju?j-)A{*g5@sI-L+BYpVd}7YjCj!r5~-$b0s9{}l^MF{ znI9th(vHz3l#Al($QCoOl^j!|%eV2=)xxD$FfuSX12|$)HC4yuf?1bzshibDqECA8 zX9MN9y=_SJ&D}|%Zb9&cRx#~Qx;5uN2~;j-f-ffr}yKP)KGu6#+wJ2nx!?b232f*CS_-F{_+NUjX_W ze#qMvRb)r%Aygv@65uat2QrlE%EfHD*I1)8z{vFqyPh zW9Mrn2NJU|NZ@e`3->$*l1{;mT)D~#S`5kiSS>xFjt%iUU$I+zstrV%aiJmm_~K&l z++l^*;xI|Hh#%^=Pj1iR&F{sR_vgw44xQDu^6lmMU6vOllc3h1M>FvG>9cF7Gy%Ih7R*; z-=)}|*FX$h%gkIA4Ph4IS8GWj5>Z7VLN*(3GoJ4Ymlnvi{W1g&AE2pfoY4c5*l-{t z99Yl4Qa z$p77+82h??X94jXld%C;2 z0<~@Z3oq7$6cT%50yLUR4*XU{rr>8k2PmG$V#cW82G4xgvtVrKK9(S0a<#gPU+{-> zVrb%pp_$6lD}~w^9CN4;6|>TT6Cil*S1!k2~n%NCv_^!YCQpRCdeG?q}XD z8@~_4ymux`og4pdS6-%pDiTCsTMu*@03=j2d+SHAn|)r{rT^(JNr)}0(u+wlOT);r zWO5L*4pT2h#cJ7FR`!u*j5Z@$qi(MOniPId6m`tUWJwwu-fd}#*9i6Q1{fR55D?W= z;W1&F5~fGQ%Se2t)F&snfXFbiED({SPVg>ae3EZiY2b8tc(OD+h(R0MBBbU#ac8%fw;#0ZqF_IzQ?nw{d7}@v0h9QWm2&G{oIFbMp+?Xw= zijc&&ujBjh3G-3TPkH2*Y<|v5kF8#=n^K@mdlh7G<~J^2WiTW1y0IZ{AwHGBGsu#mZM#>VZaE6r`UrU&G`fq7Ug1)p0VL)!cm2xLCJCNY`4JyYap z2^-4dbGydualhJYU_Vud`Z8!*Q9{CLl9DulI;OjuiJ8O=BCKu-o{zdo@T|o1^$JIt zzaNRYt{*o@+&{ z>2k&_pN9Mz-wvzVX#573vI>gf>fxCW`&kz7=>ntFias!>9vY^ZH6}kgm9C+U zqB;^gKUMkFa`rZwwfG@;T2+ z2M3GC-TdLIn`DDhF8xeWeG0%br*VPH4dRy@Agvo4_oeAwNGKszH~+?je$@^+f!0R? zgmtOivt;#ELsKmi7OHQR*Jy(mGV*3Gs%JW|!!@^{l27_(g7-75gLr1%$n%y*zuCa7rPueAV9 zCo?{B7s2gE-1&j0J3aAt^Z93hXS)}6!cE#z$KlYm{f#^ehp+8wihe9a0d_<1p_tvw zUzrd^mzU=Xy~*a*-+Z;DX3r!PPhjCoR;#z9?V!9`l%YA4a#nN+*}Px4S0UX4o8s;3_AJa<%F@38MpVRRFVV# z#6?EizpS>)#DgnCpQUg>Xpx#fG#BrFx!4+>Fsh~^xRo4kybMkUx+3I&O=A9PFkgq%pC9pWC{;yQ|R&0k)jeVoE{=yxe{8p>PGU#rhM+Cl!Jkm zanvE~iNYv*WVUxFAF1X_@ma88$NL?X` zpUn>*E57?mQ9(yP#+7AWuDLv>$l-V?ct;X+NfLC#GnQa@2lxJi(GJfMHYrh33=JXK zS>#|r#3pfxmoo~hFJtr>7D*trnVw2|?TP>B>xp?Y*ep_Oov5g)KjdPP;rD`fD2~u3 zB|ll30Y8P_rl&8Apk!U}47C%S5~~MGB<*oke&e2sLsLs)pJiR1Ok1zaOAjlQ z8S1~kI-Q-^9r2vlEV{Qg5GK8o$sD0=rwfl%ZPOsBL6b%{5__)hLUV zzYtj{aNxggTFA@F^%Er!`7DtEY7e&-wKOx2nc7AJV>DQ}NMrVrrR`Sy&&VT2H)vSk zG!34Ig)DJFGho6z$qYUAX>ivGlPdG{?K7DRx$zSJdZ|b%nNghkw z6_9II^DgRH`?NqCMF*$)n2mmwp(+E#`9)RF?kb_we?*g?^t;DeMFdg&S+2iiv6!S5 z>iA}yx?{LhO@hUX22u}N*0=eMPp(hq#7?Y(FE_q##ZDd8R|m%4!>G6f69R|XXKQrt zf-TXn%D<~v$AY|9h>%D8LaTAE?_a^ET@VAl*yBGZ{-YRhBQXo3nXTcAU6emWj^5Rw zsD4nj^@9H(^Qh`mOGxBmWPFvq8g16Abo38%qlJ;HHTzqzqVczfyaOX*8|tV^?Nak^ z#o>?CF%mUjW)*xl5=;N8{mkgspe~zyR*^n4VR_sh0`*Mr_NRuk-_@D3@J@mpmH*-C zIOgV2a8$ zn)lr>nm=keP-9C0r7ndr(PhY8^RZEc{qTaBND%&|G=2{uR;!j(hP@r+OLKR0xgDpY zu3>@N7>#yR_J%qOQRH&ESC2)BOeEQkJTGm%D&8ZSf*FVBUP7mTQ~TBemg%|VL(ilL zgdQTxr^sy(n>%|oD`erX)vI*`ua=`pIhxz1G!@%8uk;Pt+E z9X{VN?Xm5|U{m^xj-l%O7reiJoEe6#6xRP>Xt#ye`ktxf-RGCK-263gMgn_L#`n`P z6&2wQu>|BzJ5;lfIE|7t{;x}KdDPQS z{VYxW5szsdW>f}5cLmvj8=+$P zgSrA*oPJB1{Jl$rC9n78s1h(?`ZF=+VlA(}32v0`f2O9*Vo6@kp7|=vh9VFifOk->7;meo+N_lLLcLx~D(rWg+NA8qsx!jTJ zUQ#@H1rrXVPW%@~xOdn(Z8uPm9{*q}<)`WEU)fRuPF4;8(^f+cg{}cC(DlvzK!0l9 z9VPk%EP4%xMNY5*M@Z?qu*W}mxrKwL((u#WN&ly(iD^_$5AahSBsSU+O?h6X88}&c zD1_He#<}$n%#{<0Oma|h->P=FmF+TXm;aQ-FL(Hv=EY$orM3$80MHO zPp(zNk=p9XV>gAR7!ZST06SdRQ&6 zTK`ipG?+XvI&1kodNA+40R@no6p_366Oa%tTQQ-hB69St>&gXmk>cgx;;%4d9X06Z znbwe|-b4}xZ8ldyNgjHQEA@y+PRepIL#_>RP$xVMtJ7j0#cu?v=wr;bV?Wf`Fi$7@ znQHRpcqM69DmNN-oCj7y#ssR0$EM^|ojF=JEK9X$7{ZjZ^lYd+w1Z+lgxm(Hh@NSJ z`{vupu&@Gt%2k^4btTD%=VyL7KxPtucPTD@lIfQoUQ$6?FRVw?uL73nB-c zw^8KGmgHL=Khy9(Y&d4CQ+RNXa!b{RdBnp*dB?z}iT_w)4?8@KK#o+U zHZoKAGC67Swjub$yY05+AP_{%OlSf75_oY{f_C_Wqm$x$ zHn=KWrj=Vt{j1G8ZqPKtdqb0x_IyzbVr}f$?`NCQ-N*Y+5<@8G9di^j@l%1Zj5I}? zT<=+R>MtK<O5kUB+Bmv8jfJ;u{J%MqxL{#oH}wQ70Os4Agl#%22N%kj{yHN+@vm(_F8mE-$w**j{X7HX??bF)5YKbZiBIIaeQ2 zR<-e_S0&=9X~DTyr4$}I*jDa5D|#~~e<_S)bj^Olo;KLYqA;Sb(d%oo<$iv?zmZXD zLa#Jf!cnjGx!fyBse=OzKN2r-)Uqhsb20;5fggK80wtQ-gm5Ztw^g7vh4d~jf|t&dY85jg_h@2KTOwn<;Ekt@hVN*;`94V z?-1!Gbj$-`N!QfD5tvpUa5^K{$Lbxf6$s7yB()VMijc_NYblKqdBuAn! zYbzH1WIPhCz-rGA9#@Qe`1c86%X8Ue1!60L&zvhlo5Tpo>EX z%6uuAB;H?F)F2zN#C=XpuQR(K|4mhWp4}`)-A{o}gM9n5wLgm$qE7Fn9i1|pF~8X5 zN@oztnA}tj^s~X}SZ`kqEh{3IrXUfiWriiy+9MuZ;Qj6EnH?t&b`9rB62#GrEUs^D zIC3FUUB86|>z+Je|I42c@!fp^5%IqeXW0V1T-m=e9x$J(YAXjw{BP|cczZjM8?k;3 zY6D|rDAU=LRYdLSbH%i336k?UZ#D!dUfJ)@>N~_)Di!K+S6eWNW_;@a60q{I>D67M)HCwC z7Y*qOmrtH3{%fJ{JKtrShRa4UdH74=$0>);w(gLuH+@f3kPUM~SX_+UwIO(Pa zqIUte?S1bN>GeOvue>$qDVx!iR0W&qS2FzRfhtB4Np{Lcb@uCO-rn?Ie!Sx=EpraQ zqg$9~L$G=X6O@@el)9eGa=-P3L3f9PkmcB0CDjwm%;3Gh^I`*6e!WxwPF46`7UA}y2j+oD3FL%32Vx6>$}#q%u5(*#M&h2is+p+#lGrm?cX z1}6mQLZ_x&5H!ImrfGcWw3M#@-R5~8E3XvuM~?s{YrCBEtgOQ2W0heX%h!mj4SP{~ zZEdk9LLAcN?;Zc%sXDh=c&fR7ue8NXrrr2mfq{vO`dOT?N6-|rDdjEf)ysvFNhd;u zgxKabZFw>(Nh3)@8mve!y|KFdk!f@+(b0?cYQEr~Q}Qv^o!&iiMhP?pCU;7lt*>Hf z<(?{vr!S7QdRr zBER@BH8*aV4VY!x((2JlnPFID<8r|}UatJ15+4~;6g#SCEsbQyvfQJTiUvEih}K2MVOlCYj#ywi7cS;#2o&Qccru+VT- zEVhuqSsxc2^6jrSB+i|3H;z`R^L=d{CBDyB`N9D(o06?Ds9b%Rsr38vD01b$0!S_A zYu#uUn7o1tr}3GDiD;Cv9pVJdfY_3RnBSGTbpb19HRhs;@=vy zn)CjjA(a7p2ZE3D8qQuOrKy8iA8D?724D(>K6YLS<_(x)(c4_CA-UXD^61hQ?jEt_=kO{s zUQ4<4eyK=x2Zy_ z! zYjWa4s^|V}fbn66m|$jA@;ONXr;0CGwuG!$0i#ZwB+#lAY)pQH<+xpoQ3nt7{U?gO zl5y>~c=V-3J^FHUcLWiiKTM=KQNu5#P$AW2d(Xmgt>eXU+r53@K#ti=qjeD}95Ri# zc$+$R@y6{FcV%ZrhK-8NtLT}<-+wzk+OGQSdc104`)&AI5t1R#I7g+rD``e^X)D3z zMd41=DK??YOkRb$)HTm&X;w{|&zq~`u-+VMXr@x-Rp1=IjWQ}T_8)v3nE&g%#VDj} z%FsEiE+Q14-tNn61E`NBEq2ZxRR#!o_EPE5EB#2;lGP6F{Huz(*b8RYIUos)eX90xE1{=2#mjD_NSROy;t$%#l^o-_BcgH zn)u`#AnDZFC8%98Y?xVvphx-&^Pu6qpMAhJcwJ{EtB#MKWOASaZm7sk^Ko~Ul|9X<^z9_sdRw7@l`H%*s2bFoW_|t-aZ#y~K|m+n2QHm6i+cvM zU#|iT3^G31Yhx)4XV01K!lmRJN1W0!xbfsR^_h2~hYnGh)S&Bn`Tv9?zw%OSC$(wO z8|#gi#*Md(VR>)B{Gro@?`D9>cl*MyXu`7E)DitFsWQ3I`5Gkw4|CqjN>e_F1am4! zV_e=)GG?fwY5BVXsuqId#DfMPLaOpO5k`9Kp1u}VIA34>T~pTC*@#W>+As8up7$qS zrbB-&$NSujR0&I{5P8i}ZFc7q*>Z^Z#9}y=nh28+nqP*;(1cr`JcX?!c1(U;vV|B+WTeqTD-BL-ev)(L~?JjrI@Hy=|IuL(!>M1CD8>&T7U zI&N7p*tETTOs*a=SA4I6DEH0uSNY*?wzIyipd1b&79|W@!3KYX+lg?>!VY`g)Zjmd zNQ{=@1zighy*Vd4142q2irT#P-FLUGf<8mfn*;#JZTvx`wNfOtrmxuE|vm64>Tx+e{GZ7+aH}Cb9ufwFSEpq2s=;WwGy=I zjpm?FijgY@24ih+(ocq^7sZWP!0&OAs0<~w*z)Moof6KS=GwX>(Q+8z{-T=Bdf}ac zdFb=tbC~(f#M(R5yrwfUnE{CRD3H3Ni{qQ3Y?zuXqeRiZ<4#XR)zl{UO}eMd^ToUn({F?){$2jCGtX8tBxKKc+fe z;J4%lf9>sXxJY_%=BpWVUa-GtwSUP-8KH)}$th<8N4-l9wf3#Rl%HGFQgk z&mpKVT)3uu4?B)GViukIZ6{NE@E~6!amdG&xH*~Z^G?%SJQQl} zgttz242q+5vg!#=r-Xp`9-@R1rN`D++!N-(unMil@u51csH+TEH?i<-O+Z6D#_7x(!>%*mr$a-M^5^}`5ACiC2~e6( z-(2(6)NPgHBK*X)onc-%I@8_Gl-sJg$OXquo=^)$%mPUYl|@q|joooa`koQ`F~0)` z&-HY>!=(W9TJxzsrD)_>)87a+xuu6b3JY7W5a|X4+6L*9$cJ!!m{MoagAv;fFhX~! z_>?Nz!i9 zjA32tPt$BH!q*h5X?oJ;O=GL9c%?Sn*~2l)DHv~0l&)l}g4JB9pwAQuD+l0&JEqMH zg#k<&*qfol($l4mda%`tFuN$BHnPtZl%$)XY7J^mzxTv}9%Eh|%SJz?BhO=atEkbt}MXg_X< zU!cgnuJmqPahaxojqH8VAe35Y{ZnYdUknFoZohMYOkm7YUxIAY{-w!9mI4xff#|PUj>YXCKGOU^X%kzK zYmePfE907P@#ngQ8XViyYB%~OCBIU#=tuK+><~CZlP{MuhpcoVU2(DyeKXxtiMW2g zguQK52X|3rBR{$Oe`N5w*NQcHV;g(=Cg1Uox3Wq2Rqjs-#@eh$RJQ7UkPIk;Rh|9&mQjDZQztd*0dx+z23FUDp`zq0^!L zg5SVTXkJ)jtf!)QU(7~jN}v{r>}qHuBMme8nS@wIqLH#IOn`@qHPF$9WvC_QCU|~`x9;_n5hBfIADi1A{3dGhfS|01FEj{Yl zJPJq+8P~3v%*GP0&wDHavIeVyIPYfJg@mG@3o;8+NeWU0u4j6w(lkXvLZf>O#-SH4 zmY|D$^SMq#&6C=T68m%9*&MWz^)Im8e;>`W)umY^Eyc|534a9XH~q{q=x_iEl z|L(HCZ_ws{f_6nT7UOsR-Q;eR_-JVLn6JxI$LeLVMWd_iy^jF7=r9E|bB?|ckS7B7 z<5-f=x5$dJZ-ssAZ{K?R$bVmOh4X7|l~h$Mo+4Am2=cTt8hPD}@pMVXe3bUbaZC?0*=4-snG~+@0tAFgqcrx-cd@{^>;|=l2Efm57KLdNd-b zR{jx_?0a~DlSh7UN3N0I=q_(OFcnXVzqypC%PXquerw!<^M6=&=q*D|V8CKGdB$S+ zpuh6byIEOgBHc_9r&nzcp6&hCe2=3Q8e)~7z5^IG8Gn^P^9yQz+D}biY>zsh%+G2? z`z=;cPeN4JaCS_$=|aPD2?t)1R`Y`&ByWq7?KLp(h(mWbLjJz+zrAhWCSkcDf(olV z{+Vs9n==g9j`SeOu=01$3tH{0&-6h41)qaY95k%>Mk>Rw7^`hZ?RbxBoSEZ|JNw@O z9@z1!wAmoLb24#PPRv1r?A}^K5t~{>HRVjw{gl+ea9U*QV3iNU`y*b|NhgDgVD}%p z#`w`T??gGC9BEObe|RiW{B8=s*=gG<)~ffW3Zte@x2vsoQ>?6E4`!4XYOT#6%A+l) zZx3_NH)`OflN8mwVJ<%kOmc=2{Isf;BX_PK9R-$Qi#H=AzA-;$BvW3?c6I#L#Li9X zip~nAh=*WRoG@`~JWIU~eU~hc788nS?yeuJCmgnO>j`zhw~D8iYd+(Q$XE?tP<1x; zt2&H27kb%a6ozwhhqN&!)Ri%`(mkGmX{kh%==y0N@(b{?>>Q@Kmqdtst zaLQL`Ny~rL93U%*ienb>*gAXLD){g8+T&k$zcF$m(+P+$YmAw#m7UQSXx+cMm;r zTQ`i(Lj(;PV{?|N&xHiX`q5qnvQo+=*ls5FIH^_g00Et(YQuQy^(Vt-_oMX{pOY;B zJ2wUch;p6szRT$(#J!X_hRwmSR|)f{1qBCdyu|jK2_ zw$7v>Mf%xWFqUWG?t>3zy$f?Hc-ji{84^k-W>&d9(J9Di*ELSv_~#)QMz|D2iE?yA zG#_8>D=w5Cz4$P!klK;)Mcg zOwgAf%VfK*VDtK~$i8sv;nJk5M_lQ?_ln%mxcu?GexSOO_)A-gvx_Pg+usMYw3h3o z0pF0{9cm9yBj;9$hFf;X2D;1(r!p}c_vpUO7mFY7BLv(8+eKjk!M?e{2N{BVAiQ_S zmvD|2iKt(Xo6K3G6MKUfuAfVugXL012UCiSJ|e;d6c2+SZn9LPj5Cu-&%=okHK$I!1n_KR$vHMfuKX|`sX#EK-dM#6Y>YWeMg z9aXxF?iB>)St-wi!t7#2dP-6HzjA(EO@Ei~%6_4e3<-1 z=>sZGH2a;#%%?A3XEOQrlZJM+tH5?sdlpvny#{AJ~d=4-jlCn%u7V`Y%4L`Xp@$HFEm$!DdSD*5)ZcUVUjam$mWbnTP@& z{@gzo4aAdq%3XcNHzDNyZIZbG@MA+{g`^O1!gvWeDU5zeh?CEU|0KhKRx%nP5cSAC zOu1Mhe*s9Z0N2rSIuod~)_DssgKf3yR~D*Fnvny)0JJ6tkMEHNVLzpuB9>H-6Jr;v z>ESr;QoX}YM{bb%&USbnZcIdnmB^#u>h0_ZkjZ2G)Vn9vu;Yzyd-6|U%^`aAU1$sW zwfPWd5e+TM-$Yj(kbu13OG4wc?Y1QVx9UWz@hgd5NS#3Gr^toG@k4RDvF}noFZ9Fu zHlPS>4pJfh<2FXHRU~zBuMh)0{7Reu-JK5@FUj;)2nir`OI@xdR{$Hbw6wJ6X1t76 zwQ0mgBlF|qfw=RF<)VJMCasqpVPbN`@tB{Wu`_JxATS44(+=OZn)w%4V+7f=;AowWY5 znvd@8PKLDkzBTyudc7z(px+5d7J8k(er*$mH$6zDM1-DTz9NDK+$jJ1kd9p#h``Ys z+}}_(*=pL*;^UX(^hT5`>s^#iR-2F_8(*}w?~32lOVwkJO&pTIsPXAn5PTkCx!AmZ zN`J{>+dH%~pc#GIF~h$!Fns6!$T1vh!^1x|hT&5?t0Ql<^%!*}pQ89FLp+XBN5)C9 z8Jt`2ypW)idn^U2;G`SARA0*sufin6!@fweTBo_WSzJz4L?@c3_&21PZ@#3UmRAKu z$3Aj=@IT2OO!d}kGpCSo5KjK{i9oB`ma11RJutHv#5tc59iTg`ClP95$h^DSXB2aR zWa*Op8LzO5KJrXi9upMvv&RVT7{l2!WDlPp-iu~PTk!}H|Eks)xO3YSVEIKYSGHMQ zXSYxr3~)#0-Yx4DCdcQ!h~ur0sM5+?=HC5E(ogv-w9?$!H<70(c{GD5jV4ApYub!o zIu7BFmNRF%X3Wn84|yx~gn4Xb3-*B3>odXFT0R&3i}A6ohmbbgw+8w$b}I6PgN~u~ z(sS_aSKlYa*S5|*{h_=_e6<%|s7JoUd%Vb%THR}t`C2|*c#OKu>AtYApgKZvevOri z@E}yDabtU1ma&I5vA*jTSwCNzBk3?_hltKC1}FWol@IhBcuKP2m@Z?q<%jTcq=nGb zzQhbse(mW&&|19@&Am$hXjyLhD=cZ2ao+J3`TYC#^Fy&a9eyx{EJnmZxZ>G;{w0Dw zOX=~6R0eW68RVtAtzR&aE{WKGuU0!*F4t0h=&n)Mz4;`F94U>kzD9;GG2ze96+~Li zl?CT^v24>OdGC_oaSDEG9C z1RHg1LUHhx9?8dqeQ`dkps;8Tu#}*8d8V%=ce4(|bfajeojJtSu+w!NA7Zpw{52&BSx$oXDAh4<;m8<_kyf?%* zCW8lcoO7e%s;EeaF-Q*b)A9)9Udfy3V=%x3Jjs|Cz+xy?E1&5BEIja;<~67~0}NRw7mrNY^;8s)6UPH#0Yd36;3r7I~F?2T=8UjgGzYA;;Rh*5j z(CkG;??+6;Ol)a5lH#`i-P14fCTfUXDC5=_P8EZt@S@sAikkO>(YAHsT9H8qUY@`$ktrdT ztMYkp9322|**OJ!5<00E4gHgzPbp%->RrBUX1yrWe*NyC(r}mR-}Y=|wk)p^Lk*+v zUGv|g8Jjtxval57T#S$t@8RL$aohUv4N8eiBD#3UFsU0E6@-;S^a6bd=*M@D4oq^| zv(*|E8`atSf-8bLaKl4YCCiqJbjsPe_y#vGv0}Wl#)ZEpQW|-C^P`w2d&^_~lvtUEzl^l9=pcHCHy>iiUEW?y}1%5iesbW*4%(4M4OD>AMwaFD$UuK zO)Ewf`b^DeF+|&<*b;MayXi~8yt}uTTVF2@+;Gl~;>_7YaGCmZZ2nq5Rc+k%iH|H)0cqR`7+CN@DiD%W@Bs&i}We2gFQJlMbb__JznLq&0k_C9Y7K zzHm8O_&FIFA0Hpm=K9tkMD1%qF0KK4G*%Y_Hd1W{lTJA`W+Gsue*eTeMi`Ai(8UFGh&?yRi$!hMG@|)PP%pJEMgq z18*eSJX54m$sr)neQ2Ak+$@FLdm;W6h26ZLvkf4u^xS~yitjpRr>m0j@{_;YY{2u$ z^GjBQtuq3ii|LvV*QjVH6#A*8$R!#!K4ashXZsq*sCU^JIQBq4Nbm z4TAI|-TysdN^|d4^@OeuUA}oQ!h(%t100?wC*li}mC;pr9pl`KM{aH?%gv_-$~JmV zNrQVXT8GtDYK_6O8S;&a%-Q+H_2Mvf>Ye)qn3|0eZYb#gI5QUZ3B}L> zjz^)~fC32^jme|ox@RUXi5$@wfv5cEgr%e9A^M!Y2a)0Z;vDuJ2D9wZd{vMh8Csjd zswl~1;-gS9abSmSbf^rE1a2tEu}a`2L!cP{rQ@jO;T!L)O*xsopw;IjNJxWX?moEX z+~XvR(Q8>KilkQWYnbUa_w!66#b-;l9|@0eJb@Pin;}TyBt#Eki-?rVOJj{xk#D|L zt7uoXJI!M857SZE0^Bk9f5FQ*ch2qm`gDT3m~O)uCfKvYiO)TC3_VT1sT`#UtuEouI}>zU^&u(1y8! zwu|#x|C^+w6Fd@_M(I^tw(n$}?6>}N{?@NJGo1Kd3*3en-n@D`90L-P)PIgnE^QfC zmrn#`6Y)f$p`p93{3ZT=;05x)%)|sv0gNw-n{2Hn96U{vr{Zk&;)Q^x?Vc|cHZ1P4tywJMe_c`2TWoD39OdO|@c z83}MTZME9Xb6Ng$mFt)Hu}Mg53T6Xvx5&BwUaG&5&}YPTst4cEZ@)}Ne(S~Plq(l6 z7h%>$V47itrjrkoB22oWFGhb1b{*Ino~O!YP+@+*w|69g%74k*iiPwF2=>5}=_>-* zptAi{kxXWBWu&6=VeZ8ed00p8ZwfI`V@Sv&j2FwXjVv=PQF>IvcbaI1KiOQj9t)*b znJg){Id5nJg=jnd!I47%k4(8%=gmB?MYfOX8Nsvf)Sgu~d2o&jV~(phy6eEs1$8nR z8;W1fUrH8O=OeueFOAIJgeJ4vTN2N=l1I`EREi|ZPsedRxzA2+md+va6h zIJk2GlyhXOtz*uOEqoo?ZAB)gLtnf?CFB1DxakmyPFZrIAZeCy2yrQuYXBt~dPwdk zm^+gtHBFIp`_olsY<5;w<1>?k&)a_;HIqZ5eN`j40CjTs^D-HByu#M;q`)M+wY4?a z$Q4gCkI5A(nt)rUSv*6oyna|vQp;_BD8AOzN4DT;+6dk^ps(+a1A^+@ak$z)yjtf$ z8X2reR&_c+PSRZyX_7}vDR0dGH`h+k8pw9U_(x|-6Mt*H49w|<5WV@oCviF8`4KRd zCqBZ)-Sz#CcZ7dTUi?m+dOqew1w<|M&>Oy3fcX4-xU7KD&zYf=M@kBz2zIqiT>A96 zu_DTq2-KU`dXa@lV#4A!HEh^#y#gWHhJ_djJz8||++#}f@%dsz6pLBhS&)VC#d7L? zl6pKcN;JV!^fsD3_^)*y<0*4A6_E9{N>n03nn-g0LqCzeo##InZ~X=h-RfNT5c{mXlr?jm=*W3MK4!j#GqIU586Al2g_K=vM-#Ql3l_N1G& zK&Ko?(9OT2hhUWlue#|G&TURnIR!@4ARgVzjYslEhGR;7!$qvq=)3vA;HKJG@8Csa zOYFJ5Aj5Z2s{pD7X4z%mi@BSa)f=Y2M@#*Y?-{~3ZrI5r%^8@2JFW;(iFv_xlaUCo z(@lt+0V_N)m^Ctd!+oxH#@pNril~t?+3BWllbr*5%g8=6;t@rjXt#R{vt1cf|64?d zW?3iTx=56yQ7d2QyWM`U=j$1a7GgP#|JJY3 z(Cunr%r9kS1u5XVK48er!G|Dgv=nXgBIJ3?O*&`I+-MElWKplsF$!3%S0z1|c=Bk) z3smLgcs7@uzVBp3M=wWmH|Djm0K?FaDKV{!&yv>awrvnh4sK@G^BX?Q%H-GW#RH#a zH^az|+@rknrOOs55#Xj=VZp4spbk<^p-9WK($KFqxtzT&)tJ9dOEbptq zzT42?T;z!fy9js+;@WDzy^+hUKlPU3_tUY-7)%s3 z5>YUV3JqNvxBXc%YYmuR_%Wdovp=lKFTQYW$n4<`wjJR2^j`ZB_M>kb{?(g`erGTJ3P`^JUqRad@TLE?ofvXFw=2-`{doTG{+dLTAN5Llgm?EXq7G&m z<;6?+iO>q1IH5t^`eRz8k%q#lT!S*ztV}a+@6fXwQ2siiORVf%nCq-A@dS+rJo6zH2#6zY^K6+iP8Gcx^_H8B#7`x#S>05Is zY$UxhKlX8HH+(4K(XRvaAjkWoRWis%Zy&h!Y`*S?+f@jTp-X@$AjL2CqtA$}sJrDF znXo-8>$;}19}$=W{OtKJtomPCaU1QAqDrG|@-stChDBZ4WJa&g9=^qYYL@mh_l=LX zU37wnrgmQlCQX8^k`HkO4;o!nXmEu53O5^{5wEeFVxgY)uEMRMK{7xTGKXz65b`>H zt~+Qd9$ke8Mhgq5S05=vuB)eqQU`CV@U=-MnZAT^eP&+VbD#DqzA!%LFU~RO0V&Z~ zMOH0^5l(+{Lq*k}ILMzraxW@OW|!Rbo!cDZ2ZBK_4D6O-!iKB_p62SNEj6Gab`x+v zT03&^c~d2CDRUIkwpp3sy?VdWKbc$D^1LI`Q52JTyCHIaVH4GBJQnM1N0>h0U%X7M z8VPy?>OPwJS}V*}urZs@$)KhaC6~f!RXo8fFLx@&`W&$RvEOy02uf~H^=CDNObmU} zavC;UsyL>|!3WxNZoFRc!OO`__byY5LSWsEu-Ql+UfP`HM_=shd*Lgo#L0mR-EwXKjTvF<9|!NYNO9zZ&^W+z z-^rtj(Ma?z6B`{lBWOP(ccYp2K7#Vt4sb!@t5 zsdwRnjU;PSEmqt7sB`eds?;eF_ifC zn8r74KD3HBS_?0OoOO3 z(z`XKarEsHWvJ0*QKm!NLK&C!Z#UqYba@tf+iLo6B{;}Wp2;xBgH{T#3jhlZ`r(G2 z_)*r5*<$E=ybQ58e}a2)j6A1&Az#p6f&$r>i`)H(wbO=?JuaiSlL7KyY`gHM($ISXC2;)J8ltF6wKJGGHySgFn7Gu z+sO_Pt~hYqw<=!jlh&J#p<=6ZJNO8cpC`9{C3RE3#J_#Y8%MHr%y0Y-6Exu8Ca{d+ zr_HhpCRKV#=~{%ITv1z1Tv|2G@3Ts}qsH37*6-<)DnM+0*Yn~Wl9st$2Jn$&@PC}AlDS?v;~9?^;_`nF zmt+!X^~OxBodc!w?FWzGl6wj$T{tW`+O0Vu=m?0vRst3!BXyGo72gzY%%7UZQ*jI) zif(CrRJBpId9q3Ius&uvs}2V~#Zg`WOTep0p#aZXL&Z>?LtBb+|7jKcGD#S31mqr; zeY@a=`6#$LPMQhGu?lKk(qZ3dcCSZ(~pdbir)oWJKB>tf(W!l?d$+x zuXOeIb^Fm$QmNQ#RkcXTLNtzGNdmPHFH7qfidI__WeWX5A_n=6Yr+kQsbj!*9V!~h z9KeaDT=HaExE}B8B8v_zBlcQj%NsYH9T}OyzDsyYod&)AJP5-qR7-b;4NqTQ{zw}A zbYb|hlE?FSVTTqwl2kG1x4j$k96f}ox@1CUO*TH=Geh=Wl!kVY3}&D0v|(43br%-d z59hmM+7g1$OlNI){hkS@Z->HgB|P|qb;hrTQdlUW$upfwMjrFIA|R_&U%<2Tt;hFj zTdMx=v*ohuloEhrtXx%iOw7%V0T06SN?ThS2^gnBs?#!c+#vgU@5inkgF%Gcl)bK` z0Aym(@iw8M3`?DV@EFFJ7s@Q2LAK0ox^R>4M&LK)xX^3~6<5)@P;psxNAtpyAZuMM zh&sUSnf4F@d?=_5`uyOaoCb*tGH916km2s%jQHfgQWa=&-?P(XL|QBMzD#;P2i{k?s>)3UP2kYBFzl1=DWyU2f@TNIo( zZOUC#S|a_3D$eg7ylGkz+5tge6wjML*vqNSS+HF5BF-Z1xEA96Zs_osMk+LlWTnWE zsO8YOd9J`iSC|gXD4N&X31DZ>FHQ@Yv4 z*4`Q7RsT^oK$bqqScUWUv|o>zWkmNOj&CmyfXWia`ci-3igdL-Jn3vbeKVuAA4nP z(HZdKWlYC(;+;y7Z?yq3<`8kl7LF#%mAu!NxG-8uBGi))RXkF!c&edAqtfZH>54Y1 zg<7vAmBmmwSIgAXGgy*AzIRgh`N)Pi;9O2{wH_t8(Ofm@^#OhWo6-9WbEV;Jiw3nW z#~)bw_WF6UJgol}sD{fMWo!;F3rVoq)kxFN@t|z@n)S=^v?q)GL-%@?`L4>1U&_-WsEYkv3oj`!eujaHTME5p`3 zhT^NsOTz1XgR(n=ZmSc$*~}m3YPeJ^^$~xVcsN0#lZF3C%=j3(ev% zN{S`|hG6)Zn2G8)EPH9&dZc!VTlmUY`n3!~(`EyWoU{#!{eh5MXhns^9dgJ#yz8vBKx!mOnFwheyxbu3KZ# z{C9)i`gs{n{Mxx_fI8LrpP$iq6V36tw8=Z(|2;Zftcy~svdp9nqvdYX=!>osNS#X2 z`_6@z5xmPiwn(ly>7+E3SW)BX$id@oYm)42&=j76wbrLV&t3aq}+Gy z=D(rxTQUrG8@yzZ*tX>}j5O{cMnXYI?a0($k(BJvkXTq-4uX9IKWg^{$qQ zoLV@f3n3~P`;2o{Ep?`{Ko{})4|DdhJcvi6g*HNpL_S=3KQe7#-t&2`{a3e7xMbk@IXCs6!JF%ojJk^(FqXW2^9H6) z4}7LY)HHKV6+Va^cJ<2;*Jx8>JHnrdywq}Pll*w!S%Qc0nc|&DM6HrvpPEZqKu>gOkc`dmZmrm$P$=iLL9B}m73`5to5?)%ELBhH|bj5 z1tVe9X3z|h1Xlf;&DIczc+i&L{td(L=6;*DE~1>H%c<*0r~{vN#`Q)iL1 z*jjPPa^Zw5nC-8tZK!D|w|siJ&#!)Yx&HAhQ3XCdxFszGimBK%PCyNNqV+bKNp4W&_^|X?tGJb7YF0-(YKC^mL_eSBK7QcJx4d1k+zg! z$|va+xNwSJ8pMW)C?R$^O*$K#!{fg>U{oc;D^qU6MqrVo&6%iL&^0{FX#sVk?xvuC z&-!_`E04jM!HQhbu=_9+8<7`>1N95lX#T}9CRj5*)bM|@ZHm&yb3utiLK2dHOK@6j zmQ=N0L;~*T05dQ#w`Ah7!l|?Cr5Bt!bj2RPFo6DDk)i#fwb2BhNq&?|u=9jjqvsfuaqu@qzh!RtlD?pAGx%9r zOpIpUaVpiG-^koM^yK#w5jAxmjyE1;;I1pR?F)KfqOxFwTJC_zs_z9s*z45G$C5ef z2y$c!y}7O1oqE->8OLDCNTu#%B#JIlaWZz{?01x|-7U##+@Cr@t|Tv-T5QYlA6sZK z?c|xG{+KVW(V{y|Yc}O_e66hE>U%ZWd*OnvOwLao+&9#si~crb2>e8mAs9G@zKC@? z%Y7{AB4tUXha^iLe=dhP9sG8D!Z*GEL$Lt>2jU!59KvFcJjhu?n^I6MDaAG0DJpU@{jt= zp-Bm_bSq|`WwU=ZDsbp3!!^YiV9BJep8oOJ+Mq1Lbd}9B&1E@ZP&2&g!r?t`*Z@w5 zLUnql=f~?Eztwi*CmUkVQ!;+Be)Rstf!7=afsK>DqCLuuEVz*h%DVR5)kD91ua*8P zv__uRv{tZy(q)Y+Nlo~z#c4OK#Lu)X|q8otvz>11NBWX zu7XE!H5MG0Txm8aTX4$#aUBAar1}{#d67YKI6wB_!2$iLLE=qZ_}QR_x{xg|c~WfN zLSEj{Lk(Ww>eCQZ${3mptL;2zuHZD#gbJNn#SjU}7ZnvZ?4xM1v9gLbFT+uaXUZ1w zBKWW0uRaTJn3#ZhL?VGhOFWD3pSN#Yzx}&~BKVCn%4o75P-m>)k8u=tf%kQ#hrY)J zm{t6vo$VbE{GiUIW+z90ld$|C$C*xq}=ia-Z()$}fo@@%kv)w3Tq(@5WbcD5>N*(u|HM)B4U z_B?eEN?;Evl+%Zce_1@*_4dnFYQIdTo`nSjhCb@nPfjf6!Q^l-`u11UP`4G{co&g1GA4>Y4@}eOf-;Ho(5PV`S?eL2zBaY?`%;`lq zp6V=Xl-ZwByr|RWXt~g&>h^IZXdK1xokBPhx{#~js)GV=Glp9@P5hAhf44(=E(8fR z@#}KryhZaZxihg8q$(P>@wd%)1~SC=#;xl|Z)OZ1=eJ=nI&g;z-2Ooe7?8rzuN@z1 z{C5PFP!u)l{5(Vk+wTv8XYhq;5fc*=^)HX@>Q|w!s*7w*L%Lj+qwkI5Xv|*fnx#g) zTzJW}QG#Ul$#j-RE^63{XgA{x+^sJJpyu|ksG$do(Uo3orLukf{d|B*z;`vB2=?`L zqhm$yWY>dPkyg2d*+zHTPrbm;r^Vi|`Fz|(_~HuuSwTE`p&H%e70U2ilz`noVX(P< zaA`)dM1Gj=i#ye^Vrp^fUoZ&Nf@MEjV#Hb`}!~YB?;B0fDQ5!#oA9})a=}f44 zHB;%I-1#Kd=58it``l9U&IdnHjOGtyn(A|QzHR@em(rrcw&l6c7re((TYt*_0iL%IIG zrtW|HpB~Yx>!$kLP41`=sTCF?+;Y-t zKC2PDYKW|&ckCEpWoexIYtw7}%9+@Lf-;;py0J)l9F75{shp+E-OZZREUYGkQPgnK zr{`o@ZS|`gyG_c+#Kvco0`hGi0aLCYb^~KH*&l~00LVJve5F`7{g@B)03ds?rcw~Y!CC(DPOK}>o-T`j4q)8F9J74yXEu_vTo z$ADr;qFugQ$@&J``^M?8GuLNHu90XKv+Ky3dm5jMXL~bbT-=up-uQ(srBP6+q7U$o zrVtn@4WCXeF8r8v08$6e~3m_cwDR{%%V78@F)`Qxg+;N|cyppa zwoI9AT;utkFwSnl zxd(ix;p5jQ1yefoQI-N|%4+^oKg9^-&CF=Eh;7y1=*LzbTCmIiXhUnmX%S&w8yZig%Cb~SsBCwgYjj;!vC{UrN6|<%B_F4~ zg5Ny(O!cH4Axf}3Yju$)p;2Kw1%WbsI>4aW>c=r|u*TBSnNH0<#7EhP47_=6ye{cZ zrMdL)JeC+!>uW z(0VwWM`agNX6vXV`*Xf0);jJ@qGpa1{TpulV z4AC&aT&TjkOHD*W9dN$jWWwj2wE+C2U*z7Yp}bM=GR+0ZpYE*UB|dQnoJKGF{@qh1 zaarMQ@JVEJk74>1k}(dNNtgwoWrL%_4Ek~Zbbq3VufR?cDQG-iueQu#U4&rXmRYhB{7-d|Zu)p!Z2SwHN@C*n;{DU?{hH^Z3s0B%gkn`=Sdn79>Aq8- zmYvv(qS^iRK>`x`?*u|8>|_21w9f>O0eD9qRNe@y7_ibbwtXVQC?8~umm1r3eOCybp=F}W@UzQ=X`c4-FtMOpUwZ-L37Nf%R8VZJdd}xKSxC?> zwRi4;MrmQs2eN1Bz=;2xr;s>dT`2aM{qf?LfA33(Z+@OUO8A668Nb#E14!}zrVlFt?(l2HBtz`n8aT5z7aKOb)X1By0Xt@82-p)AF?MPomu%Dx&evK zVWw#{NnIa|5w}K53m?N`FA)1Os;eA69Yaj0?Lt!-TrRg+JUEumWGqjo^>!{=o85F3 z3-smVz_AKCSxzZNv1a0;*l>eT15$J{VRcPjH}{WQGM59#W(&Bl&h{EM>-Y9m(dU17 z&*rxychKXulkwAko*n#n!#rgoChvUYgQ{j{kt3*hGe=*7uCT@dB2lA;#3_>=w-M(S zrZRoPF2&0vwnU~rFM;lYSGWZ$PL*9gK1AVfd}S^bjOEO^^}D7@%(5h+8NM8hEec2R zQpCFKj8K#;ZSAkxXR_B6iYaC?4~B1Y&GvJ;-i=T^93Gg(H+LL4E-Wn}HE^aAZ+2BA zm96nmHBsMA=!v{aOx>MaU-ikvE$o15dUejaZ z*-n;~l~poSJAc%^)p38^yXJT6+~pmI7kJZ~=3{4iHDf2>vi!B#V(rQQrmFMqV4jjBb8I?=-MZgd)K%N6F6dbT66o71)Nv~XHE*D-LZ^BG4K#&Re2OJ5Km#m8nI6uyPJ_Sc#Ha7+25V(`x{)9AP|SR zvYfOoKyG`Vf_U>Klx7{(F#_A1<)lcrQm*vK2?7(f#YZ8JS1^#QkDK%gJAD`9)Eq6K zURzrmIU1`@-MSB9Wi8~91FF(#)1s5-60@FAJc+P9wu+ng$FJ}i@bv=_S{feU;6qx-(X zsaD1|#UYdqA@}KN2pf-3NMfU2>M5k4}#LfdFumLaB*0bZRH0~Bo9AWh0KL*f-2GDMm zFat4?5_j_88m#m)7UEhTtXCh-r0xoI6gNWwZ|RPI;gX8fuj#-J4h}zdxjQdP#!Wnr z8kI_Q#7<|3(tNyj1oh$) zW&bzC`$!)f}8wM}H`r1e?D#c@P2_*v~ny zn7%&d7zIY)pD~BSk$<^i%0O1H=9)LhC7x~9MbM|;V55=~PFOB5P8! zP#QO1akV6j{vwRhUvgBh_+7Xr?9e!6wm%383FWptKhvps+w;W9%}s_} zzcb|@mz>UhOG``RsKLIiDv2n7(fojQRhmWHd|&?jK>rS!LNCF~q*~l~DPRS-p3Shi zHMb4c5$}$D-P&EfcwhjuMfxMFYN?M)G* z4G`$6kB!8==07-pube-)bP8NK@|qW2y_ESrikjfJeaP3eob8reh4i*opx z_Cu}9|HyrQ(^KM%fP<6sm2yPWviBC%TG){j*{+b_x7ON7qOvzd^UM8SVhX9H<}tt| zNTsf%bP%IHZTHaG5NGq_#ZlmGTjzb77l3zO5KRo_a!A!q|K>SCl0tihFq zw`Hb4!Xukgib;)g1K~99?&#zM9Ker*b=Yf9SH0}HDakj0jCj0rz&RMjB52YjA|Nn` zW0*i5tf!|(@QFTb-N4k)sex>{#*)hI5vcR}?pL2XurlS~nbX<(lfy5J!CfoQ+fKjF zbeh*UKGSwQj)|UxB_Oq%;tj;p4s69ghiugQk zOGn!5S_{gWG6jxH1e!D}MlSdeO$LI`V1RrJP$fyBG!09fa#|5|kZ&#DBC2X6Lg*l> zR(oQ@yy`E>FVM+j73h-p1~=Iy7i7v}-$CVbcR|EL)cpj|uY#$mX|8|v87JQfyst(e zmb!*kfA2f#arr{YH0$gY@hYw8dN?!q4lbqu^WazE_-F1lZT`cy|kEClN}z_Ey2Fs|4gTOVeXm z7M50JY9zY^)FWvBy>uN-!$AxZlmw5oX32yEVGL9J2oaJ zf`kwmsUU*V?Ojn5z2beOpbeKWpi%Y)5G$wo>+UP;zC$c58KE%K)jtRDW4eHdQ$H(H zwTNVa9el-u9SU+~>`(cOw{?~>Z0g?ReN`}B7QgXD@u^~`0a$fAZuA#2U9+ab+ViEx zRi-Lz$G0cf3GvSZ@zF^v8XmbmcWfyg463y&D|%9B#9uwov*B_U)xQy_1DibzVOQij z)H}FjZxwV(Q8*x7c0s~%6A>~3TWE#CGDVY`pDzAec35@-mOv>NglZiX$@elY&WNOs z_vN%)S#<_AAmFp8kWhSAMg?klU?4b051nCGyWC4W?3_VRW0A$>qFHqa zr3Gv_OFkpgG<-PMlBODN(BHPUw3H~c<|lBwG~b~zH#bL4hNPZD^)ZuOw2>(zwZB89 zZm^47nmQcX^IDpmEp(M*Sj+2zq(UKz^*)FaS%xhnhyk0tFepR|Lxrg)fguV>fQlD- zL<&H2q-3PPOf!BMeF(!7#pLN{$mA4voYE)ukA8!b?;CkusN`p} zd!wna6|yRjqXOpY!1Eq1H`7w>j!%2Eg)TdH(tOp6jv2686Fvs87xR&leRrDr6UA7c z!;jc)_N2ni(%+rAlm~c0U4X1N%i6<^5Q|yc^M^l&t#GA8lvlt()w~?Ru)UpTP4UUf z8mnw(&|kR^_PcZz*!r5=DzIir*sY z6)v)1a!KRo)b^QdSyQLvhNV4fJVyZKpZ-h%IR+J~{X_GEE2A8`ck|eez7Fji0lXewVqfdGU8Bvq73PyBZTWXy-=bVn~fQW&V$=&X1SU@e|C2C z_G({KV-xi8>T#R(^;n|YCst&K*hj_eu6vile2KH+eE}cZ*oTs#6%mDMY+6Aqalj-t zfsmzC<)|Mt1C*dthgL|3f)zrTPr`L$m}&u4=gD}(OA-G?jm10$uqCAf?7rqqP*`zn zF_@RW8U?AwIg4H3J9S>_X{vm&&Zv){wJK49Tg;Y_J&1ds0BW+P{WKYk| z&KA$UPt1l-om}b?+vo7Rh-py)G+`tzM!VNp25(K}64kzxvQ5c_x2zk}jZbO69zHiN znd1EMBWw(vEmEZkD+rY!Bnap(1Jv&ZBThLB6eSXC6PGx#;RN7L-Hrzs^avs_YYPUN z7m81A{d}-_!)2n3EeIXNGKHJzvCgNQzj${jnksx3s1A+&v-+R z0E8)VIYWa!0(nMU0!4b@RDpgaT{!`uo`g?7oUN?kagI(F0<$<-4kGQ;e$@2G`T5ux!|FZ3rZH81X!(zT z?9fJX%29}6zjQGQwyZ8@N?_dH!$%oH9+ieP@>wv54T&^aJ4Qg2_b*;T3B@L>_CPPF z)PnO%P*4;rqGd#`&u$3r@->kVs?st;PeI%zQ=wO!m@@TxOvF#w{zFXoV^-m6sTz-O zy$9I(Jaade2EM?J>umRN1!cZ+8NIp(?t#_om&$hGpsX` zu?v4)R|!e5rbygFQBJf^(fC63Mh0`cJ>3--f=kJRk6`G5lT^@%jDJxh;^_}Vo9J>1 zvbe52@vlN|G46`;LDbZ>)gKgjNu(p~f2HXBjbY|{!Ael5^hr&++($z< zw~N?5(;}1ANSF;Ewg4v=cIl2*D4*>Z2>hNVE?Ms^xP)!ups(lrp7F z!`Z;3C!U3wpJg3ok^QEO9QQMM>;MST!_(8VNtij>r1IDoewJu0CvVH5vZ+vx`)!2v z%nkDwCEX%q%Yyd5?1<~d5scH0`_s;+{pI{BK^MNQ7vUFC#{QQCN*FyN`ulX+#p#;S z)yWftuTmt{TvEQl?0RkAGHuRACN;7Nuv)Xfeg)eN!^clBkJ-mDCTD-;_yaTfG=+%? z!UAH(mqW$p_=wIP|GH5AVQKK~z}OeU!82;IAUl^p&+o?~K>StUGOAz{O>y*dV(UU-)KD7}$DU@Q0Ea zWxnhWn%jVa@IM71C5HtuEzNNu?Xpiv?k-Uo9D89C;Y0pSiO48vmHyIh(o^9ySqMOl zktWQi7)S_8t&)aQljL#cX&*;6A<$sN`qIkav8T*R)X@hCY`A)VI zSu^L`m}swFs(!uuYyRQYdNxt_EE;no3vHMtTWG$Z5TZMBrV$fyZyecrVNjKBCBODc znil-|H^xkPdu<3Eh!H7FE@4UG6S|s^X|hyW2q_PiToxCWVGIRtS6!lJRQ5qKlyxAJ zw9?eEhOyB?G>C6)`)Wr};weue&Z+qzNsnZ$2fFK{ALjm>W0#*!X!v^&&U%1QNmAZ4%fR2)-!dC9{hL$xo4`(1Y|4Gc!AbOD*EswS zC?Yd3%nl7AN~oC;%0rUn#A41Fif*udJa?Z|yLkZ+- zO(pqwNTpQV0~I_I`G{nsFhYw7MF!%cL{x_#GR1b4&VQ&OquSZhRFwEa57koPZcFrM z0%eAoo518G@{es!=iY1}SBO@GB~}?$vd|9Lt3ZvTSu1Xw=N!3yVuOUoDR$Wv$;Vqf zGFaA)_b>S0_YS*{aaNQVX)BFJR5k!6qCv9a&VZmgv)UWK!_=eBh{1*BHr9!#wpZe2Fg!cO|Q+#%>59zWh?%5Dr z86?yl6e;^}(=XU`O=M6RN#q*Ehv7Mj+ERp4f8+_YrO*l6dv3|nWA$ba_q7He_3u_`6`X?fU zq`;m+V1<&g!&;J>?D9`LCeNAziIlDkMWDz$c@Gt;e?@MAA}xYq?W3be(Wzj!7mef< z4t9$YQwM;BvzUViPiUp^pEx%;$UFN_v8VlTv&SL*!T*}2C{oB$m~`{B2+5usm!gxf zQzPizj2Pa4>%7A5(!X+8Q%ml~ZGMo{qA@Rs7svipOpizXEXUEisNa4nCB3sZ+wXe^ zUq^5`SYoDR^~2tCV4yM*w+_-_OnUG@E$W-#Ll|09V0;v{3X6IUSz?6}lu&K33~EF^ zUD&HFOU_CBLXe)Z>Kw|MTJT>>+&@dxF}sB${7U8f#6!s@>WRfb-v2Hd3#$r*tI9?s z{waeucZZzJY7c2)r-fv@3S_9&@242NLWeomtO4E66!K`@^aJ;l7gak>I3o$Z_oG~1 zrph3;{O!>6)|FaXW_wQcvaLTQnzlvrmNw;k4C}ZgTZ(#OGNzO)zqrVn*6n*2jS7w< z26`~pM=4Py)-3MJW6atuDFUAD2Rgn;I`ae$)}$z`f+a-?<$9Vp`bj)2H3%?41in)kCD3b63&6==V?DrYh&CJ9Dn~G;59B_#|WG zpbS&^bsAcQ-Oqi2|FJ8wgY#bvY&t%P;3wQm=Tb@3 z@}?5Crnky^F|oIjpKZUq408b;qQ^h1Kd1|>xba05rtrkz%DIkE# zh9_VeDBCYgu##AC3DXsybrIdh?dA!7+>t4#4uiUsdpxi=dsLR-%I7O?b5{P|VAia> zj$(a6)lFVvE6_9}T{YHbXM2Z_2IQgA=e&10BsLnTAz*2?tCpG@( zRBJaEwN?WPKDe3i>YEj}k-kCJd4VC)^Qmm#9cqE+tn+c>&ruq@<0ET=jJ8z?0EUqE z+9c+e%GJL$>!fWyAh4w;e*}T_&HRtL{qMOtcZRAEKVHTaGKMA0(m`s>!JZ$m5yZq{CnE1xe#8i`*_Ac*wot%B)6SUc@OH0%ap1$oHb_>g^tH-(G z^&PFXwY)E|(O34~eFx{)>UUrfJ84)+Y*j?*R_n{(l~acT_+J65-I0iC)C>9jyIgC#1PPTS$1fc3o_& z?uR-AGM-Wdo^5hw_d1BniPYx*Sn_^WkUv=)guc%AnFC+Ozh7>AIWa7IE@CPJTdsT=YQCYS&p-RGZl{Yj z{yuyY681g3sjWZQ9RpxN$2^pY*{wFrM&89l1+7!ZxQv7BgXXVGyuoU`O-&b*Vx~%2 zeu5@DV&9Hh92)C@j!(%)!P&GC;rS%(H{kWC$9p_u&t9DQ7vetWmw-G^i<7nWo>E)A zOA@iASz<9Ky_|2R8d)7jk#b`4dX_4#oo_LRdSf!?P?bK5{3k(vO|VR(ZEe$$c9Q{n zL31)n^1f6dlN5esi${=(9zp^K5EJ^TRc&e3$J?XX*JK4o#Udw%@z$_1LOHM(zhr`; zOrb~-%GzEpUa~vsCz@xfC0PH^#QR9^Wd`B>bynTh-uU=<^mSA*E)SsV_u>VfXsyIo z#a*vvTm8NpoqRP_#+Tn9jbE<3??%WS3<} zEMJ;Ar=x&qFFrr~j3n~9TBtWLGaG2Fx0R;oZCkx`qJI1}Pb#STQeVD6q{5?$1VtJj zU7DB>6qcC4henTr(?bU;eiw5}2f?)R=2frvn>eyf+7s@@)#NP^2;awDXje+7HtcRB z$+paY5e<=|Fxa@IGJ&nN$Xzu3{6@DSVjIdckM!O-6V^m=WohJ8ojlc38jGB+#I_AI zK$n&%Uj#n5{@DKNEL}B;LSGCr8qp&arZti^Y9m9ZGv?h7 z=V}?8{v|-MYbdcJHk>4&s!%k^q&j^HsFwU4*_)oW8i>a$m}v@s-+QK3HB%^|= zv4%My;#*WFohn|+^*Z(|CZg`^siWG}j{b=F^2_1eteqbfOAYVj#YIU78Q4m~;HJq` z%53~n7%aZ+FH+Oeq#%(XHxS21en3Kt9Ay|jyA*8*5&kAYr*REA?B z=ry^uI!HAv|Chl;J_^AugDzMiW6Xhh*e^MmFG!Q8H1iFGEIAK~nle|BCMuoN`}I|) z=F8`oA#`%YiV$}_5X8`@fE2`~0Uz^D-Sw7GpL!=osWGrMX`ars=OsWH&$9LFoiN2! z;@-vYTllVT=##m>ScVf0+T*C=i`yqd5D_RcH!a9=H8p>ZCJ!*2)-Z;Tptc;g?pfZ1 z?dD!R8lQyK{5V+VP!*d`kCTSEw>Xe*l+Wir*KIy$2dMomA+App&xI>XLaeZpwPlj! zUxwj_JK_~H8gw#5!ja)$tzc+~ERkw(-S7ASo?w)hX zG*R|*=qs^D@lhY6;<<2Z%eU|FW44e%rGk|!Ld)MLF&p~9tqvXB>t?Jg1s!ytvf(nYmZ40%MEdy9bZygpMg-LgL<+tErS6>Ofw zRzLeKhHq$TRF4{%ku}5z_6MIzISPXe1Q3_eBK`y_7*${_3zJK(Ra0U^>JO_!9=6Vf za}|$FF%g9Za3A5JFA8V??*-+Zy{)02HfusM<+y%KV0S}Cr7#?qAEZWAv-=MjjSQc6 z{GR-^nKx}vb8z}Exux@8Hiv$R>{N8%ClP1W zl>AzNXN9ZlkQ_e$yh)+%p0-lj&NVXyU*$T0bJY&~M3X@9!X3M=++AkusRptf&o9aT zJqWffX{SzOk0Q4E4KT&yeu5`PJ$uoy{oai$pSKHuf568qnsdJ3{5!(yJ)g(mUw7#a zNz0drPP1<=lp6g@tZjgVD zNpltFl$IIE=w{bZ9U`{ZlY66lc;GA10i_v5o_g-1n0zN0cJP6zM_{W%w;vVd;~or_Y;M`=T2WfeGiJ%DBMFn zgb}{<8fx81I-sogOJRCHcOC8OKw7`)LmRa3`D4G++mDN;4dtQ;7qKtV*)F{l%~=h< zLNavEG3+;8aO9fXF;{<`s+y?B%v>?7wKU*JB2~M$XuN33tS4A@fMnVcK9~9_-O46@ ztJ+zAZ859TUk&=CUqV`$sP`RF8{b-tVbginzj92b?=Ruhf(dHv?{74`8RQz?2-G*8 z0=K=WcQ)4MrCp>BJbjqaX;!Vcc&I~bZ0Vg&IHSShMk1qJeZs-`W$cU zOVXO>G0%cMYOu;#PmqXUiLf;vdhyN;yUgV}#U;fA*>O{O~OC>{|T+hz_;To5{qBP-CU#mgO=mlSJS@s7D_sB#O>Qc_h%*Nn5 zQ-`icq;bBG<`YL%dbM7cG`F9rrLCl#X<>b6%3S{rm#FsXs0*xZ>r9Y?NmsO9G@;$!{KJCEh6p?icYXST#K?mzB9#OP;(`PLw~bVmbs z#~N&X8KyD2@SRBl(cvP_!aj6Q>X&3}ZL2(LJOBg~TE#~(U-7DHw#G{^)_nlXe=G4! z6NvA-iC#;)M;|J7O%bh1nw<3T#$_Q}W3^9@*;ih-Op#nX`skYDNXH1@MQh%z8xH%i z>b0xyI*q1Fj-FqgVb@jD`mk*i>~y?$JvtuTbd~R80;}zD5nQ;lE9UC|P{h_mzY5!M z2cV`MZF2ZC*-|$Py{sQ~C*w$K7-E(_cYTAntNI~nl0RA|@hxxmu-UMG9&yV5%Uaku z&3%zbYv380$Z>8wOZ|^CzfUB|su|V^i*9Ley(zXtxK_T6upQN!cQ$*pF>K>(YWQ_Y zEup!?po3)j)O2uxYWa1z8pi8dD%Ys8zmw?J+TVxTvR=MMjc&F!!ftid8vUjGZRp5{ zqx+jV6!?fA-Pl0-&CDk*wp3@whP>WcF0Zk+rN6$I%~1E z=DEsDUzazDo@nEkAYqSA{cJKt&^Fp}4r@s3n`YrW2iHTpD)+tDE9!A~PpIwNc4A+(P7a^CmA*=t}D~-W@|6^?v8w&=535%pRqJg zU{RWv*)aE3L3OXV+q)%{Ycgor6(6mQvf92X{pddgLm zEk7&I$z(iC5Kr)w40+fT4y~Oln80jB;xy32-T)SuJ|%ijy^f{@^FOF8!o8``aVFVy zPRnyQ$?+K3pNDEI&3iBJ)Np~4^k}&9-!)am35<1gyziLX!}CITu4s4-Wo11_*8;LB zJ4rpW7MLdETS?zW6PJ#{gR`0YQhYgd(t;6|cKg{?KD1_kGfks+*7vt%5jY=fwzifZ z{HXIzp!G4Ynr6aXR^6H9-SgTIOvNfa&H4nF93-+U9{QXp?sxWcXve;$X0)^ZpP=J* zD$=%`4lv_gj-VfDBHO;C^?o^hEyq6sdH>3sXkD7#2PNY)`JIoV|6Z?Xt`z4YLY{Br z+A|>O-A+nuxdT)WjTmg2CkM)Jg0xM{H=r-y&$!ZeInSN96O61#J>yxy=XJMWu zoeAy_;WIkQaF@%oVklK0iS3gNSPJHA8nc_(NBVo zxJXA64;LNFmu>3>arCKdRy=F+d$M)hcYb0q=M~Q%Q?=2W`0F!w|5l|nhTQJd)Hv>l z=u#)Tr%qj%^T_a zRxUvgDEtrdqia6~PkyHxmakueU5a&F-Amn|wui!9UYB7NK(#{+wK2|rb6iqaADCQ! zg|BwluIyH0DRAjt7?Y*9Gi@HGfnmyT{VfB#Bo*9?vpPgR(!=|lRADskJI^KL=j>hj zyNmwj!!W$l8SCZ(mBO7wm!sD{oz5eE*Pb*ry%URSrT*2Gjvc;BRy#$8@A=p2b(PEa ztEVL@<~T5XaxUiwK&GrW?w5Pj0sb$5y_U^|cI0lAsUx0wy*nIjI_UL7d+iJRueT`z zKHPL=bVS9i$46~VhIwt2W2Y2?iKmJ3&!)^3Tg|-Ew4MIJ|w<}?M+_W%r;l~2hkeeE!}=Bh9>s0ryPWX6i;4b|92bzF&#!R{;8T=?Jw>ut(!$~ zX4d$-59x~-=`Jdo{B1u_S@iSQLJt~4%7uNpgToX5|L3wzH{`Bd;?_6cClAJ0q5OwL u&1{M8R^d%LbM6%XeMYX){Ha&}=a38pe3a$i$RT9RL;eRc+#U7+ diff --git a/ur_robot_driver/doc/install_urcap_cb3.md b/ur_robot_driver/doc/install_urcap_cb3.md index f327f1d..e8eb30e 100644 --- a/ur_robot_driver/doc/install_urcap_cb3.md +++ b/ur_robot_driver/doc/install_urcap_cb3.md @@ -1,7 +1,7 @@ # Installing a URCap on a CB3 robot For using the *ur_robot_driver* with a real robot you need to install the -**externalcontrol-1.0.urcap** which can be found inside the **resources** folder of this driver. +**externalcontrol-1.0.4.urcap** which can be found inside the **resources** folder of this driver. **Note**: For installing this URCap a minimal PolyScope version of 3.7 is necessary. @@ -15,7 +15,7 @@ screen. There, click the little plus sign at the bottom to open the file selector. There you should see all urcap files stored inside the robot's programs folder or a plugged USB drive. Select and open -the **externalcontrol-1.0.urcap** file and click *open*. Your URCaps view should now show the +the **externalcontrol-1.0.4.urcap** file and click *open*. Your URCaps view should now show the **External Control** in the list of active URCaps and a notification to restart the robot. Do that now. diff --git a/ur_robot_driver/doc/install_urcap_e_series.md b/ur_robot_driver/doc/install_urcap_e_series.md index 078006f..17e2b7b 100644 --- a/ur_robot_driver/doc/install_urcap_e_series.md +++ b/ur_robot_driver/doc/install_urcap_e_series.md @@ -1,7 +1,7 @@ -# Installing a URCap on a s-Series robot +# Installing a URCap on a e-Series robot For using the *ur_robot_driver* with a real robot you need to install the -**externalcontrol-1.0.urcap** which can be found inside the **resources** folder of this driver. +**externalcontrol-1.0.4.urcap** which can be found inside the **resources** folder of this driver. **Note**: For installing this URCap a minimal PolyScope version of 5.1 is necessary. @@ -14,7 +14,7 @@ On the welcome screen click on the hamburger menu in the top-right corner and se There, click the little plus sign at the bottom to open the file selector. There you should see all urcap files stored inside the robot's programs folder or a plugged USB drive. Select and open -the **externalcontrol-1.0.urcap** file and click *open*. Your URCaps view should now show the +the **externalcontrol-1.0.4.urcap** file and click *open*. Your URCaps view should now show the **External Control** in the list of active URCaps and a notification to restart the robot. Do that now. @@ -26,7 +26,14 @@ For this select *Program Robot* on the welcome screen, select the *Installation* ![Installation screen of URCaps](initial_setup_images/es_07_installation_excontrol.png) -Here you'll have to setup the IP address of the external PC which will be running the ROS driver. +Here you'll have to setup the IP address of the external PC which will be running the Isaac driver. + +To find the IP address of the Isaac machine the following command can be used. + +```bash +$ ip addr +``` + Note that the robot and the external PC have to be in the same network, ideally in a direct connection with each other to minimize network disturbances. The custom port should be left untouched for now. diff --git a/ur_robot_driver/doc/real_time.md b/ur_robot_driver/doc/real_time.md deleted file mode 100644 index 1d73f34..0000000 --- a/ur_robot_driver/doc/real_time.md +++ /dev/null @@ -1,282 +0,0 @@ -# Setting up Ubuntu with a PREEMPT_RT kernel -In order to run the `universal_robot_driver`, we highly recommend to setup a ubuntu system with -real-time capabilities. Especially with a robot from the e-Series the higher control frequency -might lead to non-smooth trajectory execution if not run using a real-time-enabled system. - -You might still be able to control the robot using a non-real-time system. This is, however, not recommended. - -To get real-time support into a ubuntu system, the following steps have to be performed: - 1. Get the sources of a real-time kernel - 2. Compile the real-time kernel - 3. Setup user privileges to execute real-time tasks - -This guide will help you setup your system with a real-time kernel. - -## Preparing -To build the kernel, you will need a couple of tools available on your system. You can install them -using - -``` bash -$ sudo apt-get install build-essential bc ca-certificates gnupg2 libssl-dev wget gawk -``` - -Before you download the sources of a real-time-enabled kernel, check the kernel version that is currently installed: - -```bash -$ uname -r -4.15.0-62-generic -``` - -To continue with this tutorial, please create a temporary folder and navigate into it. You should -have sufficient space (around 25GB) there, as the extracted kernel sources take much space. After -the new kernel is installed, you can delete this folder again. - -In this example we will use a temporary folder inside our home folder: - -```bash -$ mkdir -p ${HOME}/rt_kernel_build -$ cd ${HOME}/rt_kernel_build -``` - -All future commands are expected to be run inside this folder. If the folder is different, the `$` -sign will be prefixed with a path relative to the above folder. - -## Getting the sources for a real-time kernel -To build a real-time kernel, we first need to get the kernel sources and the real-time patch. - -First, we must decide on the kernel version that we want to use. Above, we -determined that our system has a 4.15 kernel installed. However, real-time -patches exist only for selected kernel versions. Those can be found on the -[linuxfoundation wiki](https://wiki.linuxfoundation.org/realtime/preempt_rt_versions). - -In this example, we will select a 4.14 kernel. Select a kernel version close to the -one installed on your system. - -Go ahead and download the kernel sources, patch sources and their signature files: - -```bash -$ wget https://cdn.kernel.org/pub/linux/kernel/projects/rt/4.14/patch-4.14.139-rt66.patch.xz -$ wget https://cdn.kernel.org/pub/linux/kernel/projects/rt/4.14/patch-4.14.139-rt66.patch.sign -$ wget https://www.kernel.org/pub/linux/kernel/v4.x/linux-4.14.139.tar.xz -$ wget https://www.kernel.org/pub/linux/kernel/v4.x/linux-4.14.139.tar.sign -``` - -To unzip the downloaded files do -```bash -$ xz -d patch-4.14.139-rt66.patch.xz -$ xz -d linux-4.14.139.tar.xz -``` - -### Verification -Technically, you can skip this section, it is however highly recommended to verify the file -integrity of such a core component of your system! - -To verify file integrity, you must first import public keys by the kernel developers and the patch -author. For the kernel sources use (as suggested on -[kernel.org](https://www.kernel.org/signature.html)) - -```bash -$ gpg2 --locate-keys torvalds@kernel.org gregkh@kernel.org -``` - -and for the patch search for a key of the author listed on -[linuxfoundation wiki](https://wiki.linuxfoundation.org/realtime/preempt_rt_versions). - -```bash -$ gpg2 --keyserver hkp://keys.gnupg.net --search-keys zanussi -gpg: data source: http://51.38.91.189:11371 -(1) German Daniel Zanussi - 4096 bit RSA key 0x537F98A9D92CEAC8, created: 2019-07-24, expires: 2023-07-24 -(2) Michael Zanussi - 4096 bit RSA key 0x7C7F76A2C1E3D9EB, created: 2019-05-08 -(3) Tom Zanussi - Tom Zanussi - Tom Zanussi - 4096 bit RSA key 0xDE09826778A38521, created: 2017-12-15 -(4) Riccardo Zanussi - 2048 bit RSA key 0xD299A06261D919C3, created: 2014-08-27, expires: 2018-08-27 (expired) -(5) Zanussi Gianni - 1024 bit DSA key 0x78B89CB020D1836C, created: 2004-04-06 -(6) Michael Zanussi - Michael Zanussi - Michael Zanussi - Michael Zanussi - 1024 bit DSA key 0xB3E952DCAC653064, created: 2000-09-05 -(7) Michael Zanussi - 1024 bit DSA key 0xEB10BBD9BA749318, created: 1999-05-31 -(8) Michael B. Zanussi - 1024 bit DSA key 0x39EE4EAD7BBB1E43, created: 1998-07-16 -Keys 1-8 of 8 for "zanussi". Enter number(s), N)ext, or Q)uit > 3 -``` - -Now we can verify the downloaded sources: -```bash -$ gpg2 --verify linux-4.14.139.tar.sign -gpg: assuming signed data in 'linux-4.14.139.tar' -gpg: Signature made Fr 16 Aug 2019 10:15:17 CEST -gpg: using RSA key 647F28654894E3BD457199BE38DBBDC86092693E -gpg: Good signature from "Greg Kroah-Hartman " [unknown] -gpg: WARNING: This key is not certified with a trusted signature! -gpg: There is no indication that the signature belongs to the owner. -Primary key fingerprint: 647F 2865 4894 E3BD 4571 99BE 38DB BDC8 6092 693E - -$ gpg2 --verify patch-4.14.139-rt66.patch.sign -gpg: assuming signed data in 'patch-4.14.139-rt66.patch' -gpg: Signature made Fr 23 Aug 2019 21:09:20 CEST -gpg: using RSA key 0x0129F38552C38DF1 -gpg: Good signature from "Tom Zanussi " [unknown] -gpg: aka "Tom Zanussi " [unknown] -gpg: aka "Tom Zanussi " [unknown] -gpg: WARNING: This key is not certified with a trusted signature! -gpg: There is no indication that the signature belongs to the owner. -Primary key fingerprint: 5BDF C45C 2ECC 5387 D50C E5EF DE09 8267 78A3 8521 - Subkey fingerprint: ACF8 5F98 16A8 D5F0 96AE 1FD2 0129 F385 52C3 8DF1 -``` - -## Compilation -Before we can compile the sources, we have to extract the tar archive and apply the patch - -```bash -$ tar xf linux-4.14.139.tar -$ cd linux-4.14.139 -linux-4.14.139$ xzcat ../patch-4.14.139-rt66.patch.xz | patch -p1 -``` - -Now to configure your kernel, just type -```bash -linux-4.14.139$ make oldconfig -``` - -This will ask for kernel options. For everything else then the `Preemption Model` use the default -value (just press Enter) or adapt to your preferences. For the preemption model select `Fully Preemptible Kernel`: - -```bash -Preemption Model - 1. No Forced Preemption (Server) (PREEMPT_NONE) -> 2. Voluntary Kernel Preemption (Desktop) (PREEMPT_VOLUNTARY) - 3. Preemptible Kernel (Low-Latency Desktop) (PREEMPT__LL) (NEW) - 4. Preemptible Kernel (Basic RT) (PREEMPT_RTB) (NEW) - 5. Fully Preemptible Kernel (RT) (PREEMPT_RT_FULL) (NEW) -choice[1-5]: 5 -``` - -Now you can build the kernel. This will take some time... - -```bash -linux-4.14.139$ make -j `getconf _NPROCESSORS_ONLN` deb-pkg -``` - -After building, install the `linux-headers` and `linux-image` packages in the parent folder (only -the ones without the `-dbg` in the name) - -```bash -linux-4.14.139$ sudo apt install ../linux-headers-4.14.139-rt66_*.deb ../linux-image-4.14.139-rt66_*.deb -``` - -## Setup user privileges to use real-time scheduling -To be able to schedule threads with user privileges (what the driver will do) you'll have to change -the user's limits by changing `/etc/security/limits.conf` (See [the manpage](https://manpages.ubuntu.com/manpages/bionic/man5/limits.conf.5.html) for details) - -We recommend to setup a group for real-time users instead of writing a fixed username into the config -file: - -```bash -$ sudo groupadd realtime -$ sudo usermod -aG realtime $(whoami) -``` - -Then, make sure `/etc/security/limits.conf` contains -``` -@realtime soft rtprio 99 -@realtime soft priority 99 -@realtime soft memlock 102400 -@realtime hard rtprio 99 -@realtime hard priority 99 -@realtime hard memlock 102400 -``` - -Note: You will have to log out and log back in (Not only close your terminal window) for these -changes to take effect. No need to do this now, as we will reboot later on, anyway. - -## Setup GRUB to always boot the real-time kernel -To make the new kernel the default kernel that the system will boot into every time, you'll have to -change the grub config file inside `/etc/default/grub`. - -Note: This works for ubuntu, but might not be working for other linux systems. It might be necessary -to use another menuentry name there. - -But first, let's find out the name of the entry that we will want to make the default. You can list -all available kernels using - -```bash -$ awk -F\' '/menuentry |submenu / {print $1 $2}' /boot/grub/grub.cfg - -menuentry Ubuntu -submenu Advanced options for Ubuntu - menuentry Ubuntu, with Linux 4.15.0-62-generic - menuentry Ubuntu, with Linux 4.15.0-62-generic (recovery mode) - menuentry Ubuntu, with Linux 4.15.0-60-generic - menuentry Ubuntu, with Linux 4.15.0-60-generic (recovery mode) - menuentry Ubuntu, with Linux 4.15.0-58-generic - menuentry Ubuntu, with Linux 4.15.0-58-generic (recovery mode) - menuentry Ubuntu, with Linux 4.14.139-rt66 - menuentry Ubuntu, with Linux 4.14.139-rt66 (recovery mode) -menuentry Memory test (memtest86+) -menuentry Memory test (memtest86+, serial console 115200) -menuentry Windows 7 (on /dev/sdc2) -menuentry Windows 7 (on /dev/sdc3) -``` - -From the output above, we'll need to generate a string with the pattern `"submenu_name>entry_name"`. In our case this would be - -``` -"Advanced options for Ubuntu>Ubuntu, with Linux 4.14.139-rt66" -``` -**The double quotes and no spaces around the `>` are important!** - -With this, we can setup the default grub entry and then update the grub menu entries. Don't forget this last step! - -```bash -$ sudo sed -i 's/^GRUB_DEFAULT=.*/GRUB_DEFAULT="Advanced options for Ubuntu>Ubuntu, with Linux 4.14.139-rt66"/' /etc/default/grub -$ sudo update-grub -``` - -## Reboot the PC -After having performed the above mentioned steps, reboot the PC. It should boot into the correct -kernel automatically. - -## Check for preemption capabilities -Make sure that the kernel does indeed support real-time scheduling: - -```bash -$ uname -v | cut -d" " -f1-4 -#1 SMP PREEMPT RT -``` - -## Optional: Disable CPU speed scaling -Many modern CPUs support changing their clock frequency dynamically depending on the currently -requested computation resources. In some cases this can lead to small interruptions in execution. -While the real-time scheduled controller thread should be unaffected by this, any external -components such as a visual servoing system might be interrupted for a short period on scaling -changes. - -To check and modify the power saving mode, install cpufrequtils: -```bash -$ sudo apt install cpufrequtils -``` - -Run `cpufreq-info` to check available "governors" and the current CPU Frequency (`current CPU -frequency is XXX MHZ`). In the following we will set the governor to "performance". - -```bash -$ sudo systemctl disable ondemand -$ sudo systemctl enable cpufrequtils -$ sudo sh -c 'echo "GOVERNOR=performance" > /etc/default/cpufrequtils' -$ sudo systemctl daemon-reload && sudo systemctl restart cpufrequtils -``` - -This disables the `ondemand` CPU scaling daemon, creates a `cpufrequtils` config file and restarts -the `cpufrequtils` service. Check with `cpufreq-info`. - -For further information about governors, please see the [kernel -documentation](https://www.kernel.org/doc/Documentation/cpu-freq/governors.txt). diff --git a/ur_robot_driver/doc/rosdoc.yaml b/ur_robot_driver/doc/rosdoc.yaml deleted file mode 100644 index d27dced..0000000 --- a/ur_robot_driver/doc/rosdoc.yaml +++ /dev/null @@ -1,4 +0,0 @@ -- builder: doxygen - name: C++ API - output_dir: c++ - file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox' diff --git a/ur_robot_driver/doc/sample_applications.md b/ur_robot_driver/doc/sample_applications.md new file mode 100644 index 0000000..a71fd7a --- /dev/null +++ b/ur_robot_driver/doc/sample_applications.md @@ -0,0 +1,177 @@ +# How to run the sample applications + +This tutorial explains how to start the sample applications. Before launching any +application make sure you are placed inside the `isaac/sdk` folder, see [Nvidias +documentation](https://docs.nvidia.com/isaac/isaac/doc/getting_started.html). + +When running any of the below applications you will see +the following error message in the terminal. + +```bash +2021-04-29 13:07:32.825 ERROR packages/universal_robots/ur_client_library/src/ur/calibration_checker.cpp@50: "The calibration parameters of the connected robot don't match the ones from the given kinematics config file. Please be aware that this can lead to critical inaccuracies of tcp positions. Use the ur_calibration tool to extract the correct calibration from the robot and pass that into the description. See [https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#extract-calibration-information] for details". +``` + +This error message should just be ignored as the calibration feature is not implemented +in the Isaac driver. The driver works perfectly fine despite this error message. + +## Polyscope + +Start by preparing the robot for external control. If you are planning on using +[headless_mode](../README.md#Headless-mode) you can skip this step of the tutorial. + +1. For using the *ur_robot_driver* with none headless mode you need to install the +**externalcontrol-1.0.5.urcap** which can be found inside the [**resources**](../resources/) +folder of this driver. + +2. For installing the necessary URCap and creating a program, please see the individual +tutorials on how to [setup a CB3 robot](ur_robot_driver/doc/install_urcap_cb3.md) +or how to [setup an e-Series robot](ur_robot_driver/doc/install_urcap_e_series.md). + +3. After installing the URCap you should have a Program on your robot looking something +like this. + + ![Program view of external control](initial_setup_images/es_11_program_view_excontrol.png) + +4. Now you are all set to start the applications. + +Once any of the below applications are running you can start the robot program with +loaded URCap. From that moment on the robot is fully functional. You can make use +of the Pause function or even Stop the program. Simply press the Play button +again and the ISAAC driver will reconnect. + +Inside the Application terminal running the driver you should see the output `Robot +ready to receive control commands.` + +## Simple joint control + +This applications starts a jupyter notebook in which you can control the robots joints or the robots tool IO. + +1. Start by launching the application on the isaac side. Remember that You have +to stand in the `isaac/sdk` folder to launch the application. + + ```bash + $ bazel run packages/universal_robots/apps:simple_joint_control + ``` + + This should open a jupyter notebook in your browser looking something like this: + + ![](./tutorial/notebook_after_running.png) + +2. The notebook is divided into different cells, that can be run individually. +The cells can be run by using the run button in the top of the notebook. Start by +running the first two cells. Which imports the nescerray functionality. + +3. Next we need to update the IP address on which the Isaac PC can reach the robot. +We also need to update generation to the robot generation that we are +controlling with Isaac, version types are *e-series or cb3*. The IP and generation +can be updated in the bottom of cell 3 see image below. + + ![](./tutorial/cell_3.png) + +4. After updating the IP and generation we can run the third cell by using the run +button. + +5. Cell 4 will start the application. An image for the cell can be seen below: + + ![](./tutorial/cell_4.png) + + **NOTE** Before running the cell you + need to update headless_mode configuration to enabled if you didn't install + the URCap on the robot. This can be done by changing the *ur_driver.config.headless_mode* + to true see image above. Same strategy can be used to update other configuration + parameters for the different components in the application. + +6. Now you are ready to launch the application by running cell 4. + + **NOTE** If you activated + *headless_mode* make sure the robot is powered and running and if you are using + *e-series* that the robot is in remote control. + + After running you should see a panel of 6 sliders, which can be used to control + each joint individually. And you should see the below terminal output. + + ```bash + 2021-04-29 09:28:48.354 INFO packages/universal_robots/ur_robot_driver/UniversalRobots.cpp@159: Waiting to receive the first RTDE data + + 2021-04-29 09:28:48.362 INFO packages/universal_robots/ur_robot_driver/UniversalRobots.cpp@162: First RTDE data received + + 2021-04-29 09:28:48.362 INFO packages/universal_robots/ur_client_library/src/ur/dashboard_client.cpp@49: Connected: Universal Robots Dashboard Server + + ``` + +7. If you didn't activate *headless_mode*, you should start the robot program loaded +on the robot with the URCap after starting the program you should see a terminal +output similar to the one below. + + ```bash + 2021-04-29 09:43:39.921 INFO packages/universal_robots/ur_client_library/include/ur_client_library/comm/script_sender.h@85: Robot requested program + + 2021-04-29 09:43:39.921 INFO packages/universal_robots/ur_client_library/include/ur_client_library/comm/script_sender.h@98: Sent program to robot + + 2021-04-29 09:43:39.934 INFO packages/universal_robots/ur_client_library/include/ur_client_library/comm/reverse_interface.h@145: Robot connected to reverse interface. Ready to receive control commands. + ``` + + Once you have seen the following terminal output `Robot connected to reverse interface. Ready to receive control commands.` You should be able to control the robots joints. + + Now you can control each joint individually with the slider panel. + + To stop the application again you can run cell 5. + +8. If you want to control the IO's instead of the joints, you can run cell 6 instead +of cell 4. Remember to stop the application between running cell 4 and cell 6. This +can be done by running cell 5 or cell 7. + + After running cell 6 you will see an slider panel, which can be used to control + the robots tool IO. + + **NOTE** The robot program with URCap doesn't have to be running on the robot + in order to control the IO's. + +## Shuffle box hardware + +This application repetitively moves between +two preset waypoints. This app assumes a vacuum pump is connected through the digital +io interfaces. Make sure to update the waypoints based on the +actual setup, and make sure the path between the waypoints are obstacle-free. + +Make sure that you have prepared the robot as stated [above](#polyscope). + +1. If you plan on using *headless_mode* make sure the robot is powered on and running. +Also if you are using *e-series* make sure that the robot is in remote control. + +2. Start by running the application with the following command. + + ```bash + $ bazel run packages/universal_robots/apps:shuffle_box_hardware -- --robot_ip "192.168.56.1" --generation "e-series" --headless_mode false + ``` + + For the parameter + robot_ip insert the IP address on which the Isaac application + can reach the robot. Remember to update generation according to the robot generation + that you are using, generation is one of *e-series or cb3*. The last argument + can be used to enable [headless_mode](ur_robot_driver/README.md#headless-mode) + or not. + + After running the above command you should see the following output in the terminal. + + ```bash + 2021-04-29 09:28:48.354 INFO packages/universal_robots/ur_robot_driver/UniversalRobots.cpp@159: Waiting to receive the first RTDE data + + 2021-04-29 09:28:48.362 INFO packages/universal_robots/ur_robot_driver/UniversalRobots.cpp@162: First RTDE data received + + 2021-04-29 09:28:48.362 INFO packages/universal_robots/ur_client_library/src/ur/dashboard_client.cpp@49: Connected: Universal Robots Dashboard Server + ``` + +3. If you didn't activate *headless_mode*, you should start the robot program with +the URCap and you should see a terminal output similar to the one below. + + ```bash + 2021-04-29 09:43:39.921 INFO packages/universal_robots/ur_client_library/include/ur_client_library/comm/script_sender.h@85: Robot requested program + + 2021-04-29 09:43:39.921 INFO packages/universal_robots/ur_client_library/include/ur_client_library/comm/script_sender.h@98: Sent program to robot + + 2021-04-29 09:43:39.934 INFO packages/universal_robots/ur_client_library/include/ur_client_library/comm/reverse_interface.h@145: Robot connected to reverse interface. Ready to receive control commands. + ``` + + Once you have seen the log message `Robot connected to reverse interface. Ready + to receive control commands.` the robot should start moving between the waypoints. diff --git a/ur_robot_driver/doc/setup_tool_communication.md b/ur_robot_driver/doc/setup_tool_communication.md deleted file mode 100644 index d4aeeea..0000000 --- a/ur_robot_driver/doc/setup_tool_communication.md +++ /dev/null @@ -1,48 +0,0 @@ -# Setting up the tool communication on an e-Series robot -The Universal Robots e-Series provides an rs485 based interface at the tool flange that can be used -to attach an rs485-based device to the robot's tcp without the need to wire a separate cable along -the robot. - -This driver enables forwarding this tool communication interface to an external machine for example -to start a device's ROS driver on a remote PC. - -This document will guide you through installing the URCap needed for this and setting up your ROS -launch files to utilize the robot's tool communication. - -## Robot setup -For setting up the robot, please install the **rs485-1.0.urcap** found in the **resources** folder. -Installing a URCap is explained in the [setup guide](install_urcap_e_series.md) for the **external-control** URCap. - -After installing the URCap the robot will expose its tool communication device to the network. - -## Setup the ROS side -In order to use the tool communication in ROS, simply pass the correct parameters to the bringup -launch files: - -```bash -$ roslaunch ur_robot_driver ur<3|5|10>e_bringup.launch \ - use_tool_communication:=true \ - tool_voltage:=24 \ # can be 0, 12 or 24 - tool_parity:=0 \ # 0: none, 1: odd, 2: even - tool_baud_rate:=115200 \ - tool_stop_bits:=1 \ - tool_rx_idle_chars:=1.5 \ - tool_tx_idle_chars:=3.5 \ - tool_device_name:=/tmp/ttyUR # remember that your user needs to have the rights to write that file handle -``` - -The `tool_device_name` is an arbitrary name for the device file at which the device will be -accessible in the local file system. Most ROS drivers for rs485 devices accept an argument to -specify the device file path. With the example above you could run the `rs485_node` from the package -`imaginary_drivers` using the following command: - -```bash -$ rosrun imaginary_drivers rs485_node device:=/tmp/ttyUR - -``` - -You can basically choose any device name, but your user has to have the correct rights to actually -create a new file handle inside this directory. Therefore, we didn't use the `/dev` folder in the -example, as users usually don't have the access rights to create new files there. - -For all the other tool parameters seen above, please refer to the Universal Robots user manual. diff --git a/ur_robot_driver/doc/tutorial/cell_3.png b/ur_robot_driver/doc/tutorial/cell_3.png new file mode 100644 index 0000000000000000000000000000000000000000..8826053d5e9eadac17fe73fee24b4d7ec17090af GIT binary patch literal 236105 zcmYJa18`*D*EJloW1AD(wlT47+sVYXIkD}DZQI7g&cuBC_kX^suc~iXb=|&wPoJ~* z+H0?MZlvN*Nd!1tI1msJ1ZgQTWe^Yu3lI>nOBg5+5KwN9^IhNxSVt)>7Z4D{q5lrh zR9Zwl5b(@*X)$3{&+N+_NL_RVyitEi4-XhH8Cp^}V_J6)TKCq7?d|PA;1LlO5tI?( zS|&5t&D)tCa_0{U`aF4JZ{zOn?)Bu6JS*iytq5jnZk{H_Mt6kI&CM;9YHCXN4Fy(Y z<;OU|Hop#f|ojK^o`_Vf=gcECn<=~m; zQi2fn`<5_ispoVJaC$K@_}qY%joWs3I?jH&>7rfW;>NMvhYl$iK^*7bd3lkQ z3FnSJLl56JQj@o6Ko_!5Bh7tz_b5xi+3GG?Wi-Z!{Z7~<>nJhrIfJQdrINx(M%;zo zB#r-l#24(>m}Nx&?Y^bf{+Yx+voTXhAs`HyvjF39yK=1!`XO_?nyLf#2`360K=gkn ziN6$TXB6m7m>?z$Paz-A7!`awnBdyo_!JTWSr}+o@Oh|{Fm(d?VDZ9MF9#P;tYw=I zJ&daDQ!(K9-%t=s>4SxwnF$eT5E_C=M8VwkEGGvO!qm-khkeg!5V{%`{eEc>Sp@0A z|0Hyqual87)wzvVl~$7_oMTRVY|lkM^@S0$o|+P{>j71|?9AJ|4aN4cB_Kb{*@g^Z zegzk-a!)n3vOIbX(k7`uiMpc&lQiRH$TI5bu!MuBDM8g&zZ`V7^&^`?*Z{v@-Jik$ zyfSorB+65oj&BYTXR&tChXK-gu0Iam%ZvNhR4KtdL*l=O~PaTPf#!w5@PB0`NT&+K@ZI6XfymMp!t zs{)>N^(-Xtmzs3vI`o^)ii>Wt-^oLVih82(Q@xk8Xs(WjF!>>VK;@QoXgE|Ak*5Nz zBa93MxdDwQMbm5-AM&hYyI<+htd_MF?0&j@ZsB$pBWh~aps(E*pTW;ZXex7_vr;!T zGhk1MJ%e|gbgqH^fyf}#yq|`S!Obp?;v2wY@;Ttea?Ym{FGj;MEkl=P=D?QHpP&oF zj4g6trp!376pI{8^6=#SzDQLl%AvCRTbv9S!pL~-D)kzrM~HW5N1OK|D&o&5=1ZKf zZLm+wir;?RdJ~2j^t`=Q!&~8{r#SzuL+ZLAjF~lCYdn5XRtTGroYZtiZ_xgJH)2RKa&c6XLgQ)K4DEakoJ~hj~-|k=&kk#|`AI$#CmRYtRA{d?1GJN_i z5^b*3Dn)mbkZ-Mo!3mV_iHV7zO=$LWItc+8f7yhwXF;zTjNh#tQ>uq&e$a0fFI6r7 zgFsby3hL_OTk&Qa{>O9TXtksKH{?>{r#c+L&5K^uT$_X%pC_7fTI=(yVyVQTl-||L zqg^@4AA~~={{D3RRumN>D|NyS-M{ToT|byJmX=&MxL}Gi@4PO=xvq_(-0;HoF4o(* z+RgFIn5q|2Fo8>s(%=N6vDiOp$`H5x2{^mNdRb^fntE`9G)lYbim~p2pEr4iZ*Vzm zPf;#$n)i5--f)DmlUpk2`~lU7ljrz2gl73VB~gXR!&FBTyuJF#-1SFPYiCDLG!r*A zu@*6AEQ$j0i6H?Lbtrf4j1V;MrhGwl+{io*tf=s#UX>OJQ9xM! znne9YMH$oJBqz3aH%u@I`TG=l^&*W47hJJUT6sV63<7y-I4@Q3t3TSbasmrGF7I!3 z7(j=x$L|A9GF|RAP+rQL!HzagOXf2M5f0AavKlCWTL3KQjI!~Pn4{m|AEG-;nnk?X zSryzkS{IOOod6S^wAQ;>mD2xiPrPBcZofzVCJGEt%~y_!v45{nqWK76eYkR&DlG_U zM9R#KHDo)G(C{f?j%J?h&6{3mO$NAw?^awN{B{Xbw8~gwdJa^GE$vVyX#7jqOvur7 zIQ#DE2yE82VQvViM!b)RzxYL*^m>rguVMOKXljWHosPnZ6ID{btXwux!!{2qiL>9- z*p3l4HzY9@N7R)9Vj!U3+<5nD}wW?pK9kG6_&th9KFQY%oU7#yIo0#`>Lq5l=p4TRTR@j zP3gZ?kL*W|5g&O)D2TEWg~J}LD4r`sBa_96v0NH1?Qm8qm2mliBsH;b9FScRuvw-YNLaaqw=0YWZjKPzY-00wf&)#~Qo^3&Z;2`L`Dzx8_l1y}67<4| z&0b+4L|*fanV0N0IWWAhq#S-o-x123fGI@VJ@2`d;yOnzowE2Iz)>V&1Nw*VI@bJF z3@5^RHw>-Tok`Oe37~i75Vi!o;5V1kik^bdTm`YSKDcE5JwooE^iB+Gj^mYc-=Y+L zYVHMl9 z$V+(KC(~VNE$Z~~JO3MTj+MbsDjZj1=;@BcqTCkIegGXl-@ZrT3q3l}9h3X>^{5Va zI{f#PWhdg2h1THCl83_`2q`dNG^5E|3Cx(TZZjt8Io3v9(bOEBEYj|mMi*eR$};@B zc4jE2zWNEGy8LRCmdkIfA9&^kd-{=WKQfYXZJl`@%stEp=GNX;AKdVwxNyt*@~{T{PR2DzI;owhs&6BSsON?#6mfPLVA1WxWiUT>|mepN)4 zd;n3%#Vdkv<0cx#7B8kPtX!{)B6JIchW)8GM)Wc}PtW4U=KNXgxolta3lF#)9*6hy zqWXm1Pj-oK^LSM}c!NU=;H?tnMQ=;A*b5cZY4R7K-C^RL&?M6^5c1*eOq?;|bKQfd zexx`j;TwZ(l|R68^@3E?>|UU@!C7`ya12%~WrA7Qv)s}T>udW2lpL7e8MfZfUgcQ9 zUT;&)v6>>@sbCKAP`~|4la4g%2`06^GJ1{Kic@_=Y$z|=t|x7G@x|lAmdXV%q={BB zeRjh3_~cm9(Kpk@eN8JAF30`muDrzRzgM_?n%7Vj;VLYEpuRpoj9E0(U4r-27`7#* zsmYa{b3*nI0C+_DqJiODP=uVuqsc#U@+-}ZZuL44zeG_}ZJ?z~jkBpPVg7*H?NhPl zfAzs$!YI)UrWT)A0`fUzsdwTWRe=vM6 zF?T8rbu)=h^h35i|GzH+Z-z>UV&KDGKKryF3np7}>*1Gszq9Y1%dY)T>}c~Y7n`90 zZ9TJ{i&s%+4+VY;g7^gd-t=6wQ3zdU=fp5Om8~W8#3Y7!(IW05CK-)NS0e)TAKvZZ0SK~Nn^#pv(=+}m zOY=+`oL;v-u9)iDbra4P2%oy>BmUlyHTt>zBt^(Z5TENW(uu&x{N>BJd0GT}V1A7@u3dcnE$ok1n?P zmgJJ&yrpUIo;EPW?1yq%N#rGTGV-P)xK!YU8H3{Q8l-Q9lrxh}z7-5?AJO{mUJLy0 zY;`@<#VDLGTA3~S5eEAGvN^s-qLsg;UFcp%n=~!4%9>a+chF0m?TnR z;4%8ds?<^)Et?&%&mDOaMIr2drnIO}K|d-)OKXm%9r*c_e_vIp`Huu?k?zO-vKIXH z30i`$1XN~DQvoTg?gyyrUoTs7sKMC-`x~J*03J+javx+$9b%|$XE(N4A*h--!<1Yx z^Zf>;H%qK86>*eI2<+y>Z64L;M0eA$$G`!w_6Y&Y-y*%v-1Rgkw!jC={Hg3JleTFu zrj>%_X!%T>qLTq9{*G65|Az-KHFgvoo_%vyBT|z)`&~Y9TpKRpVC_UL>rl2{KKCry zpvg0LJV0f0jQHPiQpf1d6)-< zQTvHB4peUB&AfcR0shlA5X{&?<*P7pPlgS*PbvLOFbMw*vEJzt$-8|aVcp?iEM=;e zSD6=IE0~)8%ld5GcS3}(!x33D=7{;QPfRKcP*%2y;u$;E^K)XHm_N`%+=W>rkGbte zHP=jqUw-OdIz-}kj#LN7{mu4};FtkBZk^k|K(~Lx9x_pKaEy!E^%I=fL8yOZ0RNT$ z^}&@zAea0fp#*k1{HwJC;}s&%a}7)3f*)UU&V(J6vIo<_{0Z!CLQSLGp7TAp*4bYX zZ4CIQMA2efYu5)T$HOXuY8ye*I$lfcKVQh&>%f=NYe%LklQMQZ;C!oRH|bQnTM@&q z!Uk_1{4O7Fg{CodZoNmi5@A9S(oKiZ?-p9fUZ5p1v8YCyK9W#bag~BeBHnCHOJ|n4 zmu#m1&+#lqPn3wuh3QTv(GiNk_JO{f>OWX9_la-=cK)tAzdy7wSKG*hj=yuOq+6B| zsZLLYPQ3kJ!ePtS$NAVm)?Y^w#=qg(zlx}wEXmz-ibH;VykrFu)deH>x+536P8n|V z;aR)X?I+69pDuHV=&NJiFR~JAEJGxE=oj^W2?YGpr3mU0njpTqwQeH19N{57vY|lD z^A*28^eE>P#Jd@>mDH|B$u=M;4K6zdbFf|$D&00+!f^o0v%*qzkca-;+YT6i(#fDA z$!6xJJ3+qrDV)owi_6#o4zc+Dm$uJtN^D4_!`RLik_V$ z=iEcqGs$l6tsB$duU^O1MqLV5hAHEz$HgUgw;#;sq>?J|x}XXsS;C!t04#AN7YV3F z)*z`^HwkRZ(zR8hM{0NytR~ZET2{iyx))YjT#7BpqNwT6m8DI>mz1$69^)7-T&r3X z2NmKzc;~XbL-i$|2Tgt%XVFiOfEEC85;C}wf{&Zw9#jW{X9BTTY z0LEvN2d#;16XYCcp3HZ~EqvR*!bZm<6%Yxh);^XK*yGl(knHE*PM5WCc5IzD&_;$6 zEL*O3BG3pF(DzsSu2h`bYNxo9*JdW_Dh2k57j(~)!=#ebTZq|F@8c7i3yz=*g9CG> zwVYj8tKjd8>i59;r6c%~HM zHnK+2S5QGFKxsljX4?{-10eBM{264oAsDMl9Hzw5hKr2* zE5K8h6Uh%!du&opwT3=?t5J$iHZkSR1&bXU>@aU6jstrj#Bab0IVm}}fa?VkDDyz9 z7=97@yCu~J@C+J#8*_pYYz}-3tNpdNhCUkCfY@)}^$0Fv)1^b4)~8JLETrsa=v5}n z(_stCt-vE^FBM+&!?btr0jqeeQ`!~6+C3x{VmX@CsR?nb3Rlb(8O|Y!!;fPwj;2;M zyS#ya?U%e88wsm`o#Bz3CDw@8(g+B_BuIylv|NfmmkW=)vs2~1(0Iv~88FBpj{)-N znH!oWQ6LaN0$UhPY>}|C7sK|U0JEiM7Vl3V-D*SsZM@v2R>~$4qmM=5j{B}GOW{Rf zB`DE^N^wTGk>y+QquKCJwbWidF`}zy@x_@kENk0-)MU~6N9q>2>a7Unt9r zUvgji7+nzqWzka@URa~3Egd(zsfb(AG8j{-y&v&d&)zXJrk=B4# z;L}o)C#`|Z4UQa++&-=mBKce_dPg<+J_!prJbz|q3R=)CHwKSn&;kgMK!l^RW|3Je z&DY`Wf~y%BAfB(FCEVJh?bO;M^2YN)La|Bn#c@WhJ0SaxlkfmGAx*p z226b6BSeP3owO>--wu!YEtbeR zL1DB4qcCAOR2gBj@aVUizF$eq!c-%|-kG;1wFTui=cFHS0LM-hce$D0zH zP~yUmD*Pf_EgRdT*BYW`E;?I`U5)M%8n^NT$HA_O;0>qXe<-qc5B{9@^<*^!M=f2J z2paIrAj7*U%N3H}l@8GTlO%&H3#(!*vFN8DmG~a37B#co)@9x$vE^qw_3xT#?}=*(%= zaow6P>nQNUlt`+)6NV)(%ZHGx=Qnzq`Red^02M?V&iuX$nFARqAATvr!JnZGeSy89 zQR0~*R%L@13j5>_T zmAx`=&^j=^{PhJvswjW&FF5mcs60D)r-iTG6)oNMK#uGj4e^WEyHos))&BSjt_A_F z4-h_GZy2W7P$iLm1(Wa{@LL))JtVaXI$7YEX*g_dcNH4n+f4xmENh8Ao&&Nabc$rKU<1b`JQO=^DZ^o;qoO7(uS z8|E>DPr!Oh@ne=~@7?u@vQs@gD>8?@19Y1OV0hUnXa9s6VKkLH=wDNhUto0$n||JY zzPUfcHg1lO5nVBl9eo9PV+t~Gws$Iw9+Vf<+v2UN9`LV?jgP0QssarKYKGx&JZW=tbLryHlI%gOFjOU6b+a#e%m3efkowPkpaHrM z*wE0>-ddzGCT41$W06z_x!1v3-6Z0K7Y)X&Kc}$`EWcwrCFd)(c1dSmd~+3tTi*oF z{G9&2z&%{h@6?L%cz%4N!KvB%Oxu8Ao+On!YlJih_&bewdXUZS1;hpbf)vx#{j7edAe~OqgU7;)@-bQD*S8R z9Uhv`>09yy0|Gd(gIoo=sbtKwZzgD(8Sh+k9S4&DW9$JQ)}959bY`LzZqMZA1#QZN z4!?N@tFL{xvM8c4Z5sRJQ$Zxzdlfxhssv#C{A2X#-TqIxdo7*fNmHoY2Qm90P50!dWsCi-wcw~ZGCTR#$b+ihZIS<_&aFt&2vJTe z?vOuoMqkqVG=H~(>+jo4SPB}B^{BWaAvDJlWARb*C>RlEcf9zXClOi01^KK^#7Aa) z!W#qhd~{3E*DLJ9*NZg6oPJZLH;vorRfZ?SLo>JMf-m%W9${!u*A7u!R&eZD!>O8q zZm2QJ^#Ki;nK>KY&dWDT%$y-i61F`Uz+e(Rb&P82kW@0VKVlFlE;#%z9Tg28V9r!I zq!*QN&G~{!EFEr9;3WZJiYfo2u@ENn-zXDPmg;}%MbmRz$~iv73QQ_==Srx0TIqIe z-U}*|qTeM%hf+$vQq!=vbg@W;4Vde`Y^XTV5nGT-V)~?#?sn==)i{oqjr|TP@jM2? zZ{c5h+(1%B2}LCSVh#PgjA>q>ygd|9tA_s!@Q!z1F#4xo6I|>o>PTJknl==g%>&J% z+OdO=82po!?DP)GT0Hg&fH8ZOkTTVG@-xS9ZU_0*Ze{;4NhKi$He_-!b1B)4?lb%? zor<+6(~q`(&7`sm4ih-qG7dQf{smc0RV)4Gzd3V>o{(3RnBkFQ3gEkjFhtbB>+MHS z5^=m@4wHCU{SOa#+E(acTG7KKTG5#{f#j0nqM8>fMgABKj!-(Y@GDoo;1CxZ>2PwQ zs?rs=!ABV%Q?oeSwT^iPq5kCGO1P??MMl&<6E*V*>Sc+Ps13aufi!)(1{>Wlle zu@tn}jOni8SM7LStbfqWm!}=G^|*1o=Ie}F_i)gccnXD6H6j$g0#Ovun6x>GChqU0 zJP#q)tq+n7kSP-yRn`CA#?r;uQ3dl@S0A1&EXh_Giik=Qu1rgZ0OPC+IxUp zn=AG(s#VZUJdc(oIK3{2u7A`>47zbk*b)OmNYdIY4ddd+#I9bIussyub+RUjDT(TH zJ@N85v9JdRlu1*(awV34tneM)8=7ev7IBGElpV=Er^m#)u7i{$!wrbXQrL=6gVi#! z0qhyd#Zxh*$r@lWSXu*8&>6xC@l)agSMmxlz0NmBjppV27YvQ%d=n%!TBlf;VM4Jq z4>7cowPlBz9xSHm;B_qXeRv8<|?RAa^;*+kMbj+dJ_1WD(^9{oi1(0cHj^G(iZLTIx%(%KH_p1XrVJyps z*MzXg<`dWFQ`nk*Pp7wAcY&s*FDBacT@F8s9>2x=F)3|wG&@3ZrWeaLBRX!*xN=KM z!Mqd}3-&w&P!uoed5*$2$^uK{flVIEqfBPc=#|aHnI06cX?Q)Q%=RYIJa!Tmc}=it1P5Lx8?L)xj@i!`A%G=;Fi|TXz%^Q>GTU@_5wl)FBtI z+4#wbMj_y=3hOCBGwNOv$LvdOq4o3hS^*tuAnHIU!>4%Wz6hHCB8KPH_`v(fF^6Cn z?~@_xvBs*_*VLRrL;&vQM2iwQFEY)hFLlRD6fPV73BGh8I zzWk#cCT~1@M&n@}ho(UE38_M4a6KEtQ{Gq5zt11UbrUgp-ZDpSzKnDM4PT1IHfN++ zZ|!Gg1qcQw4KVE-sWk4sA_vv;bGmIP2_7JQF_g2VEP^b2CLiu@w10mi3G-mYt76y; z(I5uIc>~a60cVb|9{L0Mu;JHCsa<^t=kWGqZSAxV_TGznoV`loolE6>VppCK9g|rD z{#Pz95AFk0gZ`T~Pe9ekLf=D1!wbxN;yl zYCNJm-FdU&LAiwTAKq9-Q2}vwppKoeCU61%@eWX{q*j!XSIK zZP~SO&nzVl1}2iJ%wSR`#E2OESeSrz5)_BR;QeU51n?~-lafv#652GMn@WeS`rqZKXG@9` z5^Cz~Org#WHLHT=FF2qF4a@`JWrAi;|JbA?k)RKZLwMV$BmPzfKCsN4wGlaCL5nK< zVK!DKLcfiGTw^x~oc^Owa8{YVwj_r!sICw!a@BrXrUyNVRarEVVYB!Ar&DzOZ%Z<@ zV%BvCxKiHa`O_CQuy79n$s90mSA*mLVU8Ss1-j9nBOoDmNPZULNY0~Om%=>}Mfxk9 z@=Tirn13$!oz3FPSt*%IxSU?2pVG?oO=q?>U?Psl?}2Hj+-U-OV`e)y52ssZUTSZ` z@|$>>E)|JW8I^?%PAb;6O$9n~Dx+)+k}C3gY}=}2j3>(-#Py@ErWHGYLJGjL<)^7E z*PeXzGZ6)pXgTvSU-uN8X__G4B81WG1C_V4T3TbtmivG;&-2r+9PXroA+J%x2lG*- zb6p_NzW-@DB5+q`U{381{ISd5b9ka0wv_*9v3MkC9_RpJ17Q>B@%2kX@;JO7FK=L4 zPw@F@UHH3A_bBJfpzu93B4=kdA-;#CXJ>fXG7KH@2oEFDStP&XuzX@vPfJEG>5orc`!}5L+0Ry2NsIb25p@?E zL`?lJlh2Ir8a_BDmS@pqhx4~Q252JM+qr{+qX{h)ppL)YC1;mR0<81Cv*Y|TotI&w z6P}F_a&P_x{R?qQV8Z`#8z=6Wg7~XL!Q7urfII^(x0?5mWb+p*H(D|Ez89jRhBn_% z`z=s_-%6+A?tV3`=)8a_gMBP3ed7DO29-umJxo&CqN2kQTR#Vo$sin2g)$S;VCFJo zzsYHv{TFIQtPw03V7%0+iFT{dt$wUmbRu8+xfD0-kN&khEqx3~hr( zt@SB*PPhqs1fwL_PYSPay}Tcu)~!BJmpp8xQ%4#+NFv@b!}VEO>x=IWSlUzlV|y*w z#IXUwI>q}`mVam;uV}VNHp5x4%^%O3gNE&X#Hc`yv?rY9j+ZIHQlyEe^y+)#`ce~Y z@<#B6`6i5rn_%3TkDje$X+ExCscX+fa1sQI^+K9u$Y3gcb<;Pw*n0p zH@2+Sztz~Vl7oI+1YoWkOB8kff;G07=|6F>f{~dV2`zeWSRDk1IuRtUZ2A$0ZxFU) z$FsN5ePOw~E_%6@$w=DJg?MO7m6Kk6+h&+?kwL~rkD-5uzx9b92VG-p)G-3T_@K;G z`&}$zMXY7wwbOCu%osB3TDJO!V>iUXU+0p?8QJY!Zm`4`&rxz0$Kbsw^XOY75(fe3 zD1qds&Bfg-dw$v%)gN zG%T$XJOGIiA8Y)6qZ8|ynFW$lk=ZLNP&F@Ph?T61KSXJ%6liR8?qjxxu5oC+mFHO0LlJNsqG)B}elI$P71e$}wAoq6sPiBd zuRujzdH5Yuw&)2)oYkkgnBW%c)S&Q6m>W59PdA%uAQ*471LqGH3X(aHq6InR*@^|8 z;aU6;>!+hMAWXmG4AkCKndL5W{DlpM^v`xoqNZ!s`=U?vX^OUl=BgvPF_}l2`U4mo z?v#K3(N`m?l=P8mY9SR+4D$NGyPmO(BWeI`1}_v9B{Q-r4n;z-wJ4jAh{Ty5-*WlQ=ku&RzH4@XlMHr4-C@keb-85+LT z-%OyV49{2uC!wT`t@nsm8twq4yWs4v$jq%D`vnzmLeMaAMZmQY-0#Z=oed=m!F=?i zTC69Hl0Pzo<#kMY&eulse?q1P;hFK~-#que0zx4HQW!OfpczQlg}wa6nuegm;@C6c z+22w-1wru*6)${-j1Hs-LGYjS)=aM1z)fbvh25k*O*AUjDaNr(ST=apM(0Ih4RNX= zUGYl_s*lvo3%5=2=M0lZA2aaBNw1zQ^&Gh~B*A~3nbbxRu}}q5^jUyryD}@TmLpL1 ziNFO2H}Vv56duKz5-HztsMO1MwwE;rvuE5(R^Z6TF5hc%{{ZJ-r8@jgiQ_V@+Q*#g zV;aU~v^x1k)OZT&LgWl0o4A`1QO_s#kd1(qhw*a%f)LZZNNlp6zgMC;0lZNbC!riA z^@t&iT&$f^s?P(AYy=*lzdVXO=2wO=l{tcS%1@F1?Elq?9AC7%SNgjvJ%%Z3>HWxm zfF*wl{E}k#a}ec@EX7_k`Ftxu_<5V;`cZGZ($$sG=Qd6Jt`+Q3Wu>-9cBts^XrFk; z|Jy_Z)3W%lO)=pwF*z}k+SQLcXA@*=g=QnfV@T!IdXts$zh>>i4*@+l_2Eh6e$i!i z(ETk+=%fZt2`Tf0kBsWq?Z;oa^JC2+9DnAH<)107nL<(sgCQBvn6 zrei`oyyryL^lNgZjbcPD6{sJv1qpV&2;>T4C-Gr3Wnc3H#=f{1#}|>7r|<4Tg=QF3 zF+8zO9*s`TyHw=Em$ZYtRb3zAMMm05;rGYn=&aa5z|>o+Fq|QuUDW6L)mr|M2KbgA5dn5!VHurv+?es1)R>|tX0-Ly1r)Zph-Iyj;OnGej!h}3z|p4{ z6U-%Q&v?CH<_*pc$dH03=CzPe`~Y1wpA|*Z7uVW6>U4CYs0cRd2rP?fkemhif&T@n zn?2$x;D5`9oK|ah`j}RP9js)~fsaLiF;_n=_Mw>8hnv%HI3cQ)(m#f}ifmfkOUxg< zdm=>5j{7^O$}nx!na)-le%e6l(CGQNe#;j%EtBLWn_Adx{KxIG37c`xi^yzDMbW;W z4{Tf`hI7G~j1x-A8td6uH<;+}WvRH7kgg#-zMpa7U3@0k^2gI?A)P!f5Du|Q+2xw_ z+0`V0d<;c`C_U0I0u>0qj`=0Fp)BU>e;mqic(o|n*~el%nh)CyqB3I-_|X>f%l+78 z@i^WJri<*(OZ zB(H+W(S{B=gP$niE98>Fr(>C`dP|5O`=@tRiY- z8iS7;&L!EYH`&t6)bH?iC`o_hczo@>r`btKX#a9DxG{J~UtV`bb3)Vp8dX(81lB{{ z>yW-O?##znIoIkC_&?}p{{7|bRrNL-uA2Ht!_OKD^_AAxl{VBxad>An>5+i3`F6bf zijFt(%Hz_5YdMNwTKOszEKvcFce)b8-VY`Y`J4FVx}N>YWET9itKe@s4^#gRK&Cah zWU2yA76gUg%m@cO4x3I79`_bHUzVDuBfj)zB4DEav5blZL% z(!wRRfc`yr3=4=k`lTer7ZTN^x3;UwMIKKk@Ja$CfC}cZ;%23P@4a95ms~i)Iy2$B zdYA;2XsoTJqWMLR)O1AuTsyP9cY&WIktTTS;?i`xz{&sGXFaCVZE-7E?d>w|kPBhV zgE`E^lcmd~`xg9R0o;I$`~oE^B`b|mT_!+j(w%v?Q`tRScDz3bRDE&kCLwH?j^a_7 zak;tMlOn=Of{2GpUN$2Qjf^U`B0hQ81t(%WIv3Ng+WQ6ul$}$mMpCDyrVOBsf#;DU zFym!a{}aW7Rpl+(+5|&m8W;!}IB3z24;ENYxjOOA<$r~j;nnP~9bkUg!|EwN>UP2* zH8w#ae!zIO-;hw7{aE{w!+5g3X$!v!{%w4qcPC6dH&I=J5ryHy9bQXzp@q-lH0V zjtwK6UGHy%E61@Y*~nln^sKruasf>RnC3O+3&R8VyeZ{#$cZE`p3AhZ)n98ueCyVd z(SX27n-vrc9N-p{Pzzr)44fdyM}e|9`yfAuUNXN3$DI&P7ju}E3-n|OQkIZfsHv0) zUYk4UWveK9Bn2wJ5ONe8Fcch-J)!vmPF=3LwJ;0T5mNW07hPrEGK`z>_y|D1c(T?E zr$yNIpS|uWEDPq(K>b;44O@IU2M{l9Q?W%gNhPk&LpT%IsS*fLrQG6ewaZ^UV{@xj zB~re$%A`f%oWhI^2TywVIYO|xB!~V97&vKy1yfN!#Z1NSv>f#0#(r7aHHr^}cxa;J zh2v;PD(V@)SE!H{bZCQD5K1#?R{_(@ip!YRR!%TYrW>=$G+~1h?~KqH+npZmlDMAT$R8#3;$Xu}!#qJx(YOH#US>N~0Ap(I|d zxi30M=}FyNAML4{lBnUja)?9dO0Fl#j9uy_f;NO%q@Mv{m6%D&Xr~1irsR#H81gUS zKNbjxeRAXiHK46NdcTNq5?_6-*Oo?Hl4P+=uE}d3!Sq$Zyv=&!kATHozv;>>X#ggzm+#O{3)$&*|_h!57N#El%Bq5 zfBrrA_BAyBE_1O~H`Sye#Zb0f;?Ojb=xw#^ZKbK?$sIDa?^(N>1~=U^NslJWeN|LT z5j}Xfeb^rDAAj`XJ5{Ly>CBDJ|Lcl*ln75`naX-dD`!RO06T% z+;0gUDIAmGxX~lg}KniQk!{$d;0%uo9NgJl|%EnP8X~R<)PHV`)_|DI{#QWYPMeE z=ljn#4{!M6cs6kB_z*KY&g@@kkzecpBlU1A6cv>@VHt1y^BN#N=B{vICL-C$!*Y#b z5u8lZ+uS{bVeuV5igp>RWUO%=9wbU)3sk`t*IX8hseB|j0oDk*@)-&*tBVn7beHsAfflK~vHdm85fpl1IphRNKm-0rLypc~nbpU( z{rjo&vgd?a&YH(qi9q6SqeEPf+$6!RZF(|eP|$1`?QdL7cwc{@WU zl)t*BE@lu;-5Je9)*II4PXPw_=HjJ=D%7FoFH`*w;j^)kPp9pPnd(2?4P^7n80lFc zfN&=uAy~&}#cfaXNs`cC;6>D0Xd-BSc^v?u>~tX!9YaNMp;{y`^>+UP-qn5m(0W=$ zcGQfH+2ux{uaT{-mPt}Ro0REFgiWzy77zh2`eRUSXt1dM`|j)5v%kfB+WJ9xCjjTZ zlINYnL5Tklx>b8{Jg8o+qb*{zPDonJ4helpPhKCst@OuYh`m#KX4tHgA1`|G*g#1L z12E&g-(SATaK;=%oR-&_+UBebw0Q=`ez2sM$gY^lVWGC;OFegqjP*!gf!% zY{ulhaWFCCXw+f~>I5O?=ike*?2ra#5YVy}%%e#neuCUPYq5%nlNStf_)Do1MOVki zM5l;qHwlqbQP2Ur)rNBPcxU`WkD9Ct%I1l=X7mEAZSd#Tv@kz^4#N&4;K!yc8YdX| zQb-Q|rQK1U@5Es~BYVe_^9hN!!DFF3@&zNWBH8v}KKEW0-%C^Xq$On$sjDFWbXNWO z1IeljKXzWo27<90e7h$Wh0_&X_v2|`)QRuU7G2uYOXSSl&Pxmfk8qTdoL^iRviuL4 z1~;3^HW%>7rK6qa-MBXk$?p%MLHSa9dA$qeXvU126 zI3oQxVK9FzwnHs>m)g$d_(Q(6IlafRaQy6p_gd>QyXB5fEGdc$iOD4g!^h{D)^T;D zjo!xm0>_ZaGq<9G7Ih(b?%X4XCy44swz$K2Xr|^B?|>EA_IUK=<~TaWa@Snj^b`WF zQ_vdj{XsZSCZ&gnRXCr*t=%9B;0x+^BCOw0j{h^Y>7ygh&GCr)vb^{A30v{Bh&i`x zS8XIlW|Vjd1}-LM+C4Ze8yy{8$xqYo*W(?Vuu8?^PB5Q_TsRJh?sIjf-j~?`Bdr&VK#z=3JUO3IqtZT z;qsto9YH3z5=F>doaj(wb+AuXD_P+~@9F{81|4;?E9O}lj_GF@zkYY*8=%R{J^u_z z4MY5ec9^d^w~7xh%U!wv7fa@5QI=E)xk;-xhFw4rWCzT!yhwo2hgE3_Sp+I@C$M$Y zfmqnBB@L^|d=cRJQ^LPG1Y!g^ZcY%PRf58ykSwzHSaUn0WNu>&IniDU0cBYG1NWpQ1vA%-3 zJ{-u3mTI=Xf2G27Ul7Sexi7c95tut&hn?9t&SUG{4AHafKj_w;vpaP4&KLf- zS-KtjpY^KP$O_d%&vD2`w1G(~ZE{fs#}}f2oxQ%yY;0(WYk9E<8J$LRa*4nlBg7`K zhwfj)|dk&o0K61IpC7tupSQ~#?^{?wtGuSuxRnM(k(lpjF zIE;kfT9#s1&R2PwhhNxuGv}li8HtCLkSbG$jx_HIZ)G6Ib(MJ}7TN~!uwM*t-a?+Y zJ4m>mYMlN?{^me+MI4$Ng5`Z8>_4fNbCkDZo=)>3hkT#k%G(Dk86h(&!iygRxT#hN z>M}v}8=cz;qjC0kJVV9gabW60&j@W-BIe#~!?au1MhMKqi$TysT@Sj`EMoX~2r}s2 zj@F9?K6tGoQ3yA^Lz52~1mA=!uBmbgzoau^XQ=h7)?sC^*CS$P%Z}Dm5Jqg|gm*zr zGL^U^oZ`CF@0ojQ2^eFh2^K2DO|O!HXJT0F({Vp$XXtmmQE&wLl0%~soJSW@t;Ls) z!|ikBS$F*a){F8nZB;5i`J^*zUdZE{khmUGT!%hReTmYZAB(J- z+u3KoT@0BP(~mSgAoJhV`?)uF#nChUfXN|Nf}XXcp?}&*ji~Vy8{o2e=IL&SrBavl z5B*sE^DK=_;JCvYCQiP9K-Lakb~KrAMbr6&ANT2ZWI<7xv4jb|{ut1pT@l|}m5gbk z$%|xSz79;V_*Y3RvqRVjb#*vzdTMnT+Ph1R^qh@PhiDarOo=l4X7nKmI( zf{weaecd*I=P3`QTB}u3t7vHdac8jIhNZptDJpyELqt+i(F7n^TLm8QR>8%_p5#on zt!~Ygp`o#*IO#vCB<_$MAC#MGZibj(e=EeXe)EKu@6B62YKgz1_Z9Hvg5>B zKpX^?@z8BC9t@(|mAmr@omBpM!&9Qc3byvP_C(1MY0c|~-~5SnWvX-4*XKanCypiD z!J)SvtqqQ}m-EbBPD4ZdD9IxL`73{BVbIk^zS=t-#tj33yzIxklU!SRnBUKZj7Bo_ z*3s&as0$jlLC}Y_PyA0?jNwwgo3cd^dj}$;dJgDH>kcXT$WVEC4T!F%u!0Ua=FuvVM0-tkY{zew`z!s!p`{9~iW*`stNaP8ctJ5KMV2;QM8TpA#`$S{ zKg&!F4`!q_8 zS@bSD4t4jeT-)YxaF5d=#Hj|T%=yT0Z_jPO!85kxe=X#Y)>ZwVIX*bSI%PQY)rxta zTh9i3HVdp5KKES43qsx&ApQFS#%qSH)xwl1=jFP~;#cFZC}|XlsX(a?s6c~1QwpoR zH!}}O5rFRQ9_DWH|C)tCT~SYm)=}ovX{#M_RHM-5awhypA39A+Qc)OSxC)7dA!AJ1 zT*-V0G3t)kj@B@T9+HMoe(#k8XA&G(>tcDY2j|sZ;|bww1HSNwZ6`UQWRHNM6njE| zv;phciCM+mGYz#L_<=3vdmA3;W&;r-F)%WOjCg)?hUl)euT-A`alca=P+a4)zu}EGq2!SI~r^fP%M~R zR8Mh{Ha|CS+j zS_6IsdMpwEmo!%-9%kq;z-6EH9dS0e;JPg9O-;iRQm`ejRvb&5b=+_8-__L5s{5UZd0cc^&UwjBG zZ!vcEGt+L7V*Xu&|-1@?f zIWGwZwV!nA9Cqrs5Zvugp@Jq|NN{r^HswwFe{8*Da9!Q|Kit@EY#WVj+qN3pwr$%^ zlQy;+t4U+qcAnk)`+xJBd1lV!yg9Sa$zE&ib$xWLGWu>zEJRaJm6s&xX|sAKh~F7*1`;bgC$-yK za5Y>Ny|p+Dg8fKK^^@NgbjmQkkdkP~zL1g(>IvC1_2HMF3?ve24v941TxQdY++H9x!1{kBG80;Mful&OJa;AR?jvZTSrrUG=ruL1h^%f+(O1_8=E zi{kx(9vQi>aQ3JaCqEmQG_6`CCVxE5MZ-Ng9o=WDzq$pxs*w}63@&3~I!hS~Js~lD zw$kPvOVY;2h1T*t1svRXz7ln)c-Jb*Sz2bm#R#e;2g>DM(*$9mXsSlWZ^K}e zCFGyg2=J^ajVv#?QyY>)adA~wnKpsLrvfGoO>AlWKH*{P2QD771VfC@l{*rBlp}JY zCVbW|9$2w3g(j9geWFD*m8WN$bCAAP)561t_b!UF=H{TgIXTz3H6;ZBm&dX!Y-1vp zOK$LFq^ zlL2bA_vwu19ymlTqKK%8!b}1W5tw+-bS@9%@zXCBV|S5C=xy?->&Y!g8=XZ{W6!{I zBaQ;RXdxM(YocU;)%3%(_hzvNaj^d;egGB$0OXbb(3ct<4`;h~KiNC8a%$|>g12qs z1;?|q&TVmO=qpvv=O{YjlzSbt(V1=lAl_DVx7iadUT-A@b) z-VQrv$*{2}T?Bc*$+?*&8#vDSY(vE@nnTH4A6F+*+pPk-&H^XnS*8ptXW78Q{IC@G zL8}~9(WjF-WB)Q=P&3+~Dyms%WMo9`N>eja6EQsiZ(DZiJsNFZp?!Ekn7b+7!e2MU zPu(nVyk}@}M`n@%>!kvG{J9?BJd{=qL$TjCirzP>Do#95liQv{`>Ci#jY8qJo>T6` z#zL~f=#-Ow9GOJw_Ra=e7w;IFzW|o-hQDS z6HW)H+GhxWxKXC~=I8q@#bC^zA2K;OYo;!?Kl>BA)Xi zDT^lxEv*76WC*ryVilV&3_*Lgm=>7oNj$!29lj2DSo57}{Xv!Jsn|W3!`=$>6LzvP z%I{+ZrPQ{2Ld8a45i!XS-z-6#pxP6)Mzbe4ANKkMoz6Ux9ue(wVbRFHOEa&x!`zP= zYpC1>Y24EtR9A^sWL#WOFQc8++L|)d7ieDRU9!^|+8QgM;b$JX3I$|TdVZuHow&X%k z;5)zC7J-Mf(*uPWP!iK;Oo7X|%6YL>7#~T|qc1RB0}~LgbZ*_WNJm3eWg!2XjM6jc zBB)XrVxI*#-<2#w%kb;{L?==y5$0Xv8JWSkM-oO|h5>fCpH&&MpVg~tQ?J8Iu>zCW_i@|6mmSc#j}}r49PHyN!*gc|NoXjqnYCn}!cOWC$3nV$bv` z8=8_y-<+`WnTHUn_MCy{1~I>N!ms$;?gU5wGCDansX0^8UkOjf{&Xaw0W0atc?w6# zuS^p7G-epx?Uc3s)w)7BysFo@*K0xd^E|55V9HoQO{cjgF-E<-Ur|RQ>tbBQT#d+a z9mg_a3Mv_vYYQ zx@2*st|bkukxR{d#4xy`aghq)$^XdxzIVf*%q)S(CN ziL94Fi`8)6=k=pCx|7^H#?=0A^TGpwh{CQaUHHrxS6{ZSFtj#YrAR-6vtc(NLzk`< zQ^E0}Xvv1Kc;n-+9V8HjZ|t*SnxEJg>xpXdMuA4tNpZhE-EADvMD0b#8@+r<>Zh_GZ0LPhyYbY zVNW=(pCvYs=pu>a!lzNie>gjTgPC?}f~)>#H+3@QrUH@r!EzO0zUt%z(~Gyl>4HbA&i zmpI}Kp+OeI6-?v(V$%KFBnEB_RqD{4)ej?a|oXBxRLS!HJL0M*8d9jctMy|?p2 z4u0-^(dUmC93|ZN=098(I5v?&ehyh`_iaM;pdxKV$B~qrnh{LCVRj^cYbh5oz6YLhP!U{n_jCla3BO z03Z}ULrdk(m|p#eZU!C%i+(e02X;ONlq}khh!7n84^e3zWt7d6kiAS5FO3yIBvEoD zPl$2c7e%Ym(WQn0Wl~Me+4YC-mz9O4k#=v83`Yxcc`~Qj-0}U;E!V+fQE?$5s1=<1 zt7|LY(LWi8k1|?UR<1}m+`)+{s0gR+_}3TDVyx^-{lQz{bRF$zue)tnDqbzLz%!^WUSP@6Lt!2rkMEgh;KkzChyG4-jT^c_x|;s4V)?5?9b$em zY^KTMh|$%}9SDb1n?xO#!C(+n&vIDsPslcWhrkb-a2Qj%Zkbwd_UEF2&wE~7N;3F? zi|rgnDli0vYQ@mwDqqVser2^n*Y{8>V?A3mpxXD4KRDE{oRz{;cZldFJ>Oa7 zK*@nJ8U?3x?$TLug$((niP9 z&^;RMY&nz~Ytl@R2KQFomx=Xuyy%fBIwr*=l0$reH-`He(YmZeG9dJ5R{byZMYODu z|IXx!EohK?m%Qyh#zIK+HPd}zD$kunaY+-?n_lXci&}Xsdfj~muWZ!ZLjz$}FZ2~| zm~+8C5DCzP@h1b>y%sFWeD597Y;*;TlY=3Yhy> ztKNMJK+&UK{_1-T%>Wu|NW+U7-m1J=r#Z2Tdph-2^>|F~^SthfSPl%?Ae6MSqz_kZ_$HYR$5gl=Nbo*@@k9xUEofvmU?sVb9y>__E z>+g<@Bm>H6!2OiEIstz*p-1*L!NaM0kC50c{*p-{SjU*Ey`#W^iB!I99CZRSaby+o zQvazhauyi%v{wkx4wlpSGWGKAY8G7OH)_R_8H;tO zr<-5xtJW%;mqR;LRDhPziJ2M!W=UddBf6zb46DUwzQI-%<7v8Pwd|)-atn)N=aZKSw7W**)LJeT> z8$HltsT03poGoczh6i!>aMLA05;u>|@MPZR9xj0$7@*?Swtd9_v|P z@%}G(Pqm-Y)X?x%tnF)7a#w2QV9E^5!D>!xtK_PyvLq0`er5FPr6i7zqovtVr!4rZ`@j3Ce!;`7OSR+S>5a- zaSmW~jZ(tZzffFSJCUqsZd`oVGW8Vb+z0K6vw)CVw8_iBn+5Km9v=MpMmcgzW_#AJ zhN4GFB>X!b@(ss&AY;SOYTcJ{xbiO+jtZ7Gd(F-08GIOI>5APNe;6=t7`ex zbz{Qq?V2ETPEGN@&C6#AQPlM58sjUrmp@1%F|=41*Su;hwk$xq{FCO!Fp@GRIuPOh z8=1+=gdw>wItl#$wHHJQM#mZhTGmN0@^nsq4I#hh8_9Vf-s?c1v(h9Q{N$?Qeh{?c zFQ6gz$$SPQK8+JVbgkxgNd1hcrL7ZUAHuXezD#)G(?U+O>)Yub%s!=5D&Ccb=U5oJ z7+q#=_r^$zk_i2Z161oI%taBfKo3E3M25JmgysxrxQ*_rI9Z+qtH3yxx7k0_9JfE% zm`2`+cj#4cr+P+8rqnwzYF1K47s?*(fwC@izZ?K)#E7K_NY8ORhgDl^5t2vss$n5D zAj*`!TcL(l24n_|!KLGnq8Anj;Shxp@z>>ur7GbILpvmXCSd|N@oWejaBE_gs`*h> z0tCcV)B&*dF)??X+NRKrmAXe&PRJ-}P{lM!SB`msVbkhF4I*gEdhPKGx}Ic z20I3Cc30#gW2pXXnB=RMXJYi<-2iR~xY|i&75f}0&iX+vad438DAaWS4PoWogC9|F zw9rleAMDM=4~H8Es;>+{uS1}S`!HDAY2ii}wcdgt!#fkL$9(L)o&O~wY<5RDD8`NP z;geLB5WuVYlkqG(=+%sa(|jP5=LQr+sw00`EkRTP)1vMU+Op#<>q-N5SjZ`AGD8SKHg) zZr)>idHB(rLtWmRm^?t{?P>#UNRu+XW*5BLxN%fm4CXB7jKzI6xLjapgNfZwhO-pn zZFzJ^7E8?|d~71CyHjiUuK~mQ;;~|Z%TR}sMk_yWcr$ffZ|!#vJqKHV@ zZ@j;n#DaTUJlwe;{?u-4N#P?cJo<-~$FV6*U$T)h`$HRG<^6FI?9%uMazPm_SjKd< z>fax-u87eK#iV^Bay7yG(Y+**CxnhAb0Lx1G5KwPZT(TZQcj5H7GMFNO43zvUDhLe?vqo@qZ-QC0OM^H;Hbm8&@6v zY^dnj9SwR=w}~T3sQ!Xx6E7o-#>On7(ZnDe960w(z0(*OKz65m#?KM?1Uz zXqlXL4&HAU^6bA@(*sxd%-trkQbv)V7@hlwp+TcYCjp<5W{XB~H}33zW|c5ayD&u; zJMpi;iaRb!7W9o6ouOJ1&c$AE3TqkF+Rb$7@}dqqwq%GS?=eyiO3vMRtb?cksUdMY?-0S zz3ptlNhf>eusf-txtyik)7?9#(H0SJ%zHunNlRn|tGo~y85^Eg$Nr<@@tf;+Yb?a? z;E>1DAffF+cbV(R-KM5j#k}Yr>mP;-c$UIQRc~H0kQB)}Le>GT)zJM{ro(WT5-k+ste1OEO3_6vOJHd%Sm1S zT*x0ZK91$B5NiZQQHGG5|@)W{yR58seWfradqZ);@+ym0J5mU z3Y0w(?YBo{gg-tZf1<=W^Lr=yT*~Sx+UxW{;yxTuwv7&I;7`k7c%^8fb&QRk52@XS z=j(O0U!Z2!;E%sch=vh;#iro6_0V=T#35xCRc*&dcRNBmu*)#;MFOlpn!jV5DE~>; zsYvP;nwpx@xi^%o&q@|e8@Nkl%#-6t^|pe=?8&|L#gSW}KRI-T&i33K{kpLEc$5jS)inuD!9o36d^BEt$_F(qQnp<}K>p*gtH_KvBhl_}kVljJP5c^uUHE zq|}6RejD#ny!f=-cR5uT-HR>fs*|3D=6!gG&0^6J$2BlMz{OQaqqAOBlwmcF$lOL? zCAV!mZ$$Ep94hVy+8!o-(e(bNjJEC<7xx?y?t5L%-*JK)m{pyctz54N_gG^geYWfd z;ompaIol4AS2Xtw*I!jlCvu^cM{U|%Pzd&g&bUy@kK{b}6>dT{1lAxr#7PT&m{ZP` z#lB7YGmQ60KcnHmfB|*`ti(d3nN4xL84{7JOe+2+H(7VwlhrcC6lwPLqtYxrB-5|6 zAZ|>VdxA>&EknFXVvq~Uz)rolUq5U5buK$1UqLjCDUstR{qq42=pi7t*JHcJnm2tb z@4dGKifu(b2mByvbQAzOJATh&tqI)92{NuMGEq2h!n~joHic&M2$o8w{8g6DVvcA! zM~!-LaOO!Rsgg*+dlLebaKLPP#{Zo=bEl#)keESwW$+EDjy5PEFA>D~{s3BjIR>Xp z#F6EU`p$#?FIRlIPswe7YC{?9e1YlCbW}Tf~u-&&Y&7 zpC|C=|HaIixclRa_5t8i6zu*i$T`gcH0+l(67aD2-Z6H6@D|`lf4y5#A(_{2(EASQ z2yv}T2M>TsI)Cvtw5&X9jcp+}c4N=v7GeR=Hm<0I6t$7I3e#qGMTt#`{F%W&pw^5V zfidc8o%Pu8fd4dzlRQY&FhMVTmAN z|E-r2!c|gVJ5Idym?sAs}+i!6&y>dd5vSd{!t3|KDNSqtX zsMEX2TQ#-B7IFFS3^ay=gNeqg!~1&(jLB%(#h~Z0aqSJqj)UUyXvB*dFb04zO1RKVI6mF zsT-q?;uaP&t`HIzLc#kcLR4)VL>?xqC2K!V?ZH|Tt`R>Kv;c}vAP^HbuCA1o$*0N( z(idsTwDfHR2y!(js-p}JjqKl8XJn`b&o|v;ExB{Ppp(UckM#n3>W=%wOd8}s$P1-FF=S0%n4f?NaDIfx>O>dO! zGXTCOJGHAc?`Y6H?KK4F+#r9{AqJbS@~H|Bg=6PD3!!J)gl$6Kl~H7=j}`lW%veYfniQ$u32<3-mcHky`e6mvM8D$o$zipbqr1sx>kndwKHpC$23+RWI#}tibt2Kx^+-g*PF^50gy9Ya zjH`i5h>Lj$Dsw{A+G9{9VvnxUoC)h%UMo|L(U6*R&!@hx{f)hH#*QC?oXE&pO<(G- zeHYymT?=kjGD#o?e{1CP+itAT7sIsXAL^gf#S~$95}EJ)>YlTBX6Xok2 zj?iY)xB5y1yUuvg&9c~xZ%P#MM{A){*&Oy0iBtOaWQgdQbEG^G7@1kLzh-vR`CZh+ zetGg#NWpwBKD%8cfLXA9W8*?BI|)1Tc*Z4I20KJ^o>5i7QBkiS)<;4TdJ3!lW9*X4 z-Fovv&DU)eV##oJ=c?Fr%_Nj@45FlIW*^{A9oe8hA5z;~x$Mm2kb+(9no=ERV$Dcg z=F5;#h zlYNZNqH@cMBMZUP4tYclHuyF5fi4okgcU#Nza+A}&KV)D{3dyw7i(2Nm9(!vC*`-F z$xFs$s_8*s_lOah7U4hgejuNk{+fUDr%3@WhpP*8y&b-^B~>T!S|0nTW(;2Vrj9zV zBa_dJMqA}G(l8tHir)hVZ7!CH;tGVEb#NWs6_FzmBXblJ%1AF9n`eKfwq6rYWezvU zL;WF_9dus*yzbP5rmuMkPV{E=9Le8yOz7rRN{}Jw^dBkWX6GB20sPALCv4l{|q) z(_m2)Hh2}U|HB$ADnbb7!DH$Jbkiv)DUC@<0|H!w)gyDIwg6xCC{k*?Cek6c2m z*U<*$aRm};j8`3Llh~`~iAav*Wicje)|%dPi2tTp9ZQCYoD%oLPMkyl4$xlTu+5Yu zn%-Xo8_$cx4yG%tc5Y4u{Xz7|7khF;@|kBgLO$MLtmc^i)3(um%T=T0qez_3HojZ) z3RFgk4RjaoZ&*1vd&95JTx(`-Mak4fRXE?{@gug;a8kZEvwm$q6jT$zsFc!5NKY3L z7pGuvA2-a=U{9$y*QaE;CXN6bNBD82nH)|k-KM!S5opUn-Kjr3M4yf~Dw`%Y@{aeS z3&CeuGO{NqB8MnNor!fw5l!FH)Nstg6!@FB_J}sveD%kybJ5p!xAB1~{U6O5CQf!} zGF)q)2{8E1*n<$?O+=WO#_(pGv_rr*JzYNHMwP6+MRegKL^*&B2`T}&KXDU*W{t#N zxQ&No7c^dOyVxV**R4}Fv?_di5)!|nCn?ir^(r!Y<`OSYGd}Z23u#k~E|Mm3(0Lxk z(#Tgl53%q4z_}9Yl%s-0Dj3XQk}EfS?lb|^`ld2lVJ zZ{G|>BPZ^ver&;y_PzEoKMBFW6Ou4@JDXA`j-kqwc@qfQ zjtO!zOTV`-bHVb3)bU91^@ns!$S5$siJERr+Pv19S%rb6C6beZ5?4+%y76u*`Jh0@ zV+>c0Su?w%Q48H^6!VYq68|M*paL%^@Apmi@M|OBv?=Mvg?UKkk>j71jl=vY<6O)`Ip@f646EjTQ0UNJy0%psGqFtTU%Py zy0f6qJyP5jdOmMx8#X{m@f1nf9&Az6Gd$>hncw*N1W(Ew_=p|sJy3A&U!l4A4f%6GfF8@f8)W`qSb!@#5Z4_P zFSj2|vI~kZ_|z})*y5)9<%O;RO$RzV9pH0j3z@#v`7A}$B zFt16+0EekCry5>$qIaU#HBS*yiBay|_$&st8UMQ_;sbnMs1Bc95zr%QhM6F0+&90^ z%#6tQ?KhJMaM(b+*SBi8smupXG;5sEKHERWYx?Y%x%b{%K2G3PDuD6NLn$0J)9s4D z6H-kXgH+ZZ;>6Y>sODXSh{J=Um3XALk{iAVOlO`@uOw8QwU$3PUf6PnTvP!EJo&tC zi&Yc!Q@hr%rw)TGyRKkhKL;P?xK2k9=PVi(5N1vD7_Y?FA$E!q+t(1PSTgP4wIm>g zer7_Ptu3=?a^*Q_y46bf!`HVE(xwqabQu+-Y5G$Ke z*%`;NU-%&t2`vfLG&TOK4!Zc09GFp2rJ(;zY3Zog{W(*ek-NG`*Kt=AraRFw;4G^} ze`ju=7FF%lTr#yVkYugMm&?@*p^*(tkEZ;8Od2jGVV6*Oj4I1+Z12<{8Xwa0bb$sR z(@j}>y-I2ZZDmC9l2c7`6j?f7Tf6SLGVRGh!h}Qk8IPRjF|DqMz->k=mzUltPo-h6 z0Wpe!fe9`Q_sr7uRt)3A#5MT7UYTV}Me#uC2w@#*)0L=DdVq+2iM6RfYGM$|J@HB| zF{_l+og^w}@S7@q(hwUSQg#Gv11iYQ&T!yR{*Ys18LKg34m0)>Krdm=Nr=fUj78n6 z=j8aU^R!h-BJ^iBlq+8QI_&!m%?koWuz$K-mTY^(b|AS zE#5hUo^WAXYa)aE-`F^$x7CDuveu+`t_-qP(%T0e^gZ_Qbo)Vor$E$H68-S%fZe5b z5bQXAvn)qX;Ox@_SHL;oZw6{+gpZ+m&&x~!Gvf1hk3$gkKDbFV(rEh`%zWHyU?-8Z zsm+m#=j1Used2^fwh^DB%^Gh3B~iULy2dT{_V0r4LA#Ggxq`2Hk3&V%lSbTR7d}_; z)ma_A0o3&U7rgU$`OjO3f-rLO>nJW}4z0)F6{@b{804%;?CX8+USaL_!)BEgqfC3V zo911oLRr#>)wz8Y4^M1*5~RfCVXYcg4F;4s)4YcpT2yYU()G7u6yIoIvmhaZm;h4k zF9M$-Q#oIEnDxxDwB-yIteZjK>@y+)ElWuq7RaJjc?Is9XrwIq$}#4D066Q-qYA$2 z`u1>Ixel1kBFOjaOCF(&O(bg7qYVj6y&V;}L2{XPe~)Hr9hgWH5l2yn-+ssUcWZ+W zQAo**y77+cw4jv8R13nC#|88L^3^0=mWSV@b?bcJs1RQA;GIm;M@=LKayh6x8(aNk zUdQdpYmyvTkpz1d0V+Qm3{3qR$EM;vG3Gj5{@{$o!0s>2a(1>8yXCpG=!NcBwey49 ztK)uMF|apzC7CM?Z0GRkXM06tRMy|5ilc!2VdhRY9Q%W=IluHx8E}u0C^5UT_KZxQ zSV$*vRG+46ukDJn(f(}Jl7{*p(~JNA_m=CgVsWzpmh@@+qSyCjvU5olkInxyC+>CE z(Xrvdzny@Pc|vd}y$~RdDS-w0uZ{fpJ80L2!?^@6&I79AdGJQL-_}F(vE&nT9zTZT z9DWPyfnh_oSfgW`f)+H;bN@K6m!1P$aOPxk5)*FeeG6ydElPUSqZkOvFz{OOi&eTF+o9y43l<21BD#^G_3p@ z3ScQSs!K|}AsDa?c8;LQ_GTtshDj34c{&*JsCEORb=V|Dgac*w+MQY&4rxKUy7Hev zq6|=fPPALo5)?-x)mNeT5?!d^#iMQ{OI&P1x*Z<4^~@j!%R_fF(lLQB7LN_Y=f!|pv+y3 z#e2aj3MYTM!s(to?|9x3M0D4^a$6XVk{d0(kFw20l(XZf?SDnVW%{&4#DOKjbT49C z5d~WnN#3%ojzfR^L&`{jr_3gaB7u>1pFLwlfY(8UjC0M6STnMTciLu6Gwmwt1+Tg(ihGd5l>5NbT4wkkEk+!VuH@1Ep9{=lfLHOD2h33 z-pNptsP3t?e&)}&q1p2MEh}3Posl5<<_zwvS(Edt>u0UI3pE69KJ@`#EBmkMP@Z^r zFqt%ALEJb$S6maH=%KQH$J~sf5VGPq3ZU7e`t=HtLT!T_8tE3_`uhUvhkqzANYhE! zm>JCU*pvr&@7o@Dl-v=D=uQhAYmNuPFSjfJ5B>6|did-}VC}z?A*eO{}jl z`;9wGCDI;f6D46yR#FCYVo`GTU8G6T;{fl2E)!9Ea4408oEf4t0T?B~ZCyt9l(}2I z!^zWz&0W_Mjf+;5=5_xAAC*LOtS@zy^mxqtyOAjnzZA4$_M^)T zS4v_tXnvwJb^4;b=n)D${1l1$0izp!QC$4wk7wYx%Sg174HJ_RjPf)=_&}c>oNW&u zm%|li;4Zv$-(Mony&r!?r;z5XJ6`EK-VLX$tE$jYkG|2o~ayiiA>CzFIkJE8ZC z_{|+tc)%8pGxIp&rO&06MJaKhRqkW?W`9ay_f2m^gII#2*Jg)r(0ekx>y=tMywfs~ zI;xZpkLk(*HX#{SvbyMJG+PzKs_|JejbvvV_KJA%l}i;D89hZmZ(lSGn0D~yNAt^^ zIOn+X=?cZ?GZ)}y{dddA;F-oLwS6$}Jx?s<>M7R=Mpiq79el>qMH{a^<9C64E4Zzn zGaDn6u%u5*lztMm8g%}E3R8DWZ<)_#^npEL| z|5KI73a9%0oUEZC1qOK3S!wBPFLpd0EjF{qt$9bjcFMbzfMWir1xNgSYjV;1YZVa- zTtCd6{kSa~5&zaJ0<-OPD&=@0n!>Q{)>uSLbq&1{plSV4i;otYF67LXs{bugN?YQNE_egxT=n4;RNiHh&KW|H-6LkM;?wUE$y%{ z6l9a?ou`EA@MRtGg+MK`-dZRqb9utf_Y(5$wWQHw^f>-q zHdh+OM(77U<-0Wt5xeA%v9VfnsF^#1UF$AJoY4QMt>K4TGPBAf*C>IU4 z4#(kziL=lN*JEEYC54zB-eLT9A@Sr=Kzq(4YnIOf2){x|*F<~%f1$-zu_Y%*sf>To z^0yJ0x4eiDlo{fa(eqhQ8U%T^wn|-Ty1`a|j}Q6N&d{5)Wx(s07WFSuwIz{WdAaCN zR~0BkdeSG?QqV+mts6M~M>mJiB;X8XeVga-3t72&L6$F?4{R%v>pPBQoFAADANj;Z zL5LN5^_CwsoIZY3p6;ut6Z3+LYy#>dx^|hXqdljD1HBABn@@yHVCFBH?!odMUUDYY zGSI3h_N|HsF)yHHM766Z&^B)Y$KwmB(}BM|TqMb_b4wSpB7%k`Oacnz2(W%E93(I84g#=B2YMTN_ zUih8bzO>~YRf<T3T--!9#|H~?}eSjc(;+KRDZz(?KL*?v00wp2Z(>8t= zuh%Pty@JqpwTbA{`c|A{cG-=jgcfv!VV9&bvMj7p>o_2%C=1Gd3 z@xBUWQ;(G%=`Uxh3#u}Ay`_DXXB-j}_hCBu^3u_>g|%t4e4@1D**UndN3t8#iBCQi zkY0htEGse?Zy8j(Kp5j(pP`^|w144dqo-w72!vbWf8KD4?Mq{vtAy!SQ^hc;GBB^5 zELKCD#uqEk^a|E4bN1xr!p+xBtZtk;L>c-dACI2Z>s@&{2!+3Tg z0`u;{;Q?6kT0^mUv-rEahMLom3v=>yxr+od`(>Cekdf{_+=aon1CCt5Y=pv#!d@ zD2Qqj#8gRQcxz8(q9k1WI!&MLpt}p6_8CEyVUQWx%m12nmR+2%WQZ+~dhPUIo1TTN9C}zqg| zi(B}aBSeApxCAxHkaN8k8R*NQab!XKHAtG`Ugz##R%s{)(EM*72D&I1}Q< zNNlI;pDOevgM0mVdbDIuHRWenNHSWg;_XGoGRpHh z`SA2RnMb2zLsIw~D)e0UUKj<@!y)b(&pga^fsQM}#-;@DvE+ppHo@`U^1|)!qExz? zVR)6m5lX0G3G;Ie1|yv%5U*gTJS@o@mW+R45UiOAkZ*ZzJ=D)9ilj_E$chv z{k}WBs$a)tQ^ygSvL)|g6rhzk+i*Frp5emb@1qSP+0O#8ayS09J77KVLjk;Kn!MLX zU&K^@1FG!A;&lbA*OnHouwuV6;a{tyQ!DvwdU_V&d*>dAVkl zX>?wE$uCT=H4R*N0t?-->yYTYmx`if4jH_a8;k=|GXskGFCCsiY@bP6tphej%R9WT zSv--Sa6>yq6_g~*K^_JKn5(}ohZa<>qvgP7jgy~ax_aS_p1A$Ik4l}EIwG_?pu<)# z;Nmj5qRJ0{jA7h?kM~RoP_sfDySG0z%8*B?&NA@P(%{{ir;M_`T4v<2ef9Io+27m( zW^Jv6S|bxIG@%Wb9`eZ?!5(2XtyWum?Owqmv(i%y#*V^G|Q=S=6 zo)7ZB;s~!bt5Vge_M4_lY0lAtktrmfZX#|myTYrx;Tka}2Kxq!EKfNDnNrHnl9`zE z@ffz3ZEC!D5rwS-2eF3r(7K|8GViVihF&er4}lM<{{n$JG_^BKEXJSDvvIG+4vrD} zh423_CSH<@3zEvvb5Zfobb5pnCu*}dwHYJAOYsN$tBhC)Ds1f4J_Y`*q{=U^RPN^B z%8x_l1eOJO%B1eOk%2mfFtZl3(FmT{f#C4M&tnT4=kKECZ)=Ooodx6*)$T(>@xq5P zy88I?LV&40gh#|cP`sA0PEjfWt2~~)BRJ8im3HAJzifnWjFw|?-agbD=`!lTxYAbR z&JHzJjzh(eQU}5sDzsq!0ooJ@?t-7fM*+<(U_!+))aYuik8gQ^kpGu*a+QJsXQov2 z1~jnu$V+r;DypNc>y=;2t<5|IYlzg=8I@|i%PUz8EX4}(YS1Yk?j8Mjg;)Sla$RR z;l~@GXTrZczG1FVqpBzXoKwh)rkVh&LR8p){a=*B|IgcDJ~GaKlxT8WTq{!xcJx+( zZD@Z2#j#ru1EZM2+(XBnuO^t(xaA$565!8gbkWr>{l+{;AgHeog3T+y?jt##CU*T% zc64CZ_L;+sk=7#u6mSKjn#))x#)r8?4zcu&O--oIL`yxAi6}|2@!Q`j>}+C=#?cBk z{gSsvODpg+Po+(s^ExDxYQxH)&bR%J*j3?kk9NUifBs`PGuIa!hABaKd_w0Vo*=>p zX4kL^w+W4mb@6|Cf|bkP89lTeVUN~x_nY+ezMAZ+R^*6>i0Q2kpE-tz{{2w zqFROmMNXs)oYcE$%lK@DKBtCF?b`;%&NJWIX91Mc_G|1;+QcLtOL ziP|FH-x(Zx*@mkJ7b@Uv)s)MB&KM#G=RHHG=5eSZLxMveqi<+1E5!Ixvy$z%?_V$) zST5pwuLj7|JuuSz698Q-idOBLd~Ea|>%HrMxfu9qcu9w-hm&ky6&z-IX9pHs3u-V^ zeahIO1u4(KfD-&7M!8{;pOKt=om_8D0b7QJBGhr<^DG|T(}!k`I)HMQ1zfY+_SJCy zmb8_h4fXe_O*A}g&2qj7j0t2OQ5a7VdDjJvQ zTS9k}zBSo#9rI5ePlim!l;63rMZ<8u`+-><=tJ&tgC3`U2?ZpR*Xg7%moD99H^ZD{ zj*MHZ_;l9Z5L!zIJ}ts7Bxs0QJCMZ4-%#*m0aCQ$h6C{1@UYJYExo0Aj1OVnh2f3@ zgV<^kbJ5ROCB@-jj^A7|Vxof`j4#pQ*V?h3BOMc}xIRDq1%V|Y3#{3rWvZi7oL*Tz z&;_12#VWG<^Hq1rEOileH-fK7h{Gdd>xKhx(}}6Ubm2*5HsqcDtr|WOuwe5$L_n8#?j45)zY+Kl+W7>L0k=; z=?(L&b+35qy)A?>%w=M|dG39#|(M654^++q*gHJXn6Ve+b)m*s!m2H-k5qq$97wAm4cX z{Hc1y9Uy>2mNfctFsz~emjaOD@T^Q8DKEzi|G0=i+%DaT47$P}Nx*tPWfM9git~&v z=0sC0X9%=qp`D}x97IaM2%!6PlXvJ$hJt15KHo0W`#SGg6qsssnGWODR%^6>Ijv6Y z=ngR3ITi1iQK3bw&bRbRC;Hip@cS`?@OPAml%>!#@4xuF8YS%WdNFW}mrKf()^&)F zOTYM~HgQrz!Dim&vQ)$#rxePP-*If(C@o3FN^%ci)&0PzCd1{cM zrA$fzaw@nrvPIR*;Ds^DfQq*(+ThT2G??zbmu$>-8c4a)4CvS}TtGR4kzK@)2^FBn zrG_$X1X8-ZWN*roeQ)moMc}@bW@RzHamS0{0{qPL0E9iI^~yO~jA{&f>TA}^l-1a%ZL z|8Mq7nH_+0Ry~zbp$q+Q48nFC_wnY0+z6tfy=@j@&af5_o~&x0{6Rax z!oDs^8fulz0mBFfWu!v(BuS-R(}PL782Pz>9KW>yw@Qa`Q+34DrjGV?_YsER1OrO7 zJ~00ST$z$|e(q2sbQZtqzzv|~(c8N;HRWsi0S0CJA1V(CDYpKXM|x5QZ>@R+ztaW& z&GKE-s@i60*zUGh1Dv9$z1$G6#Mo~$c_kL_-mVu>1h5Q^0KYJAkp@nCp#kgUtFlj_oiT|E6_u*K*l@8{9#0C9AQAL@54u03UodhmBKNYdPn4{}58(5id4zlBkPpm@8 zzE%xRiKJJuw{r9oLN68oB_I8t3%gMnv z`e(hEbJ%qjaC}xqfaR0S4aE-c!lM-d#~ZBmV-kHw5YnI3%E0$xYWF5Gq6LHmsYCge za~zPGg@Kz)YfvyA8|Y3bOFhc0cG5(!ry=e^W$gI)ZuZQgo!RT(wjOW_i=o5K&w;+I`JZgcQ2!O z!Q=L(eZQa9*M4yPJGgwEg{fk8Jv*0mgPxuRVqen96ILg?y8?7-HBW*)u@ec=Fl5gH z|LGd-U?WX~)M7)?an<+3lqA(Gflf~|X1~d{%j?~1GVPXaNK4`*rtZaMO3K6>>jZ7r z#i6T(mGX7rOJoW_c<_en!sh|Rksj7Eb!9omCi*@0W!N9H=^W)Mem+C5oKD3RQw~#8 zu7m*c^VWcUa^EpSXH+a$fV71yWwMit_K%oaAMk%X{QrmQ{J<=182^XrOk6KJ-}nGBP?OCZE=I3leB~ z1&ND`iUHj5GYTbrf~}&?qMuW`2cO1whYd$hr#=~={<6iW)IpMi9pV1TTHB~7Ags(A zO<^GPi)m>5;hkl+IgMEl-y(2{E4?q%mNWDv=@s`&0IL;0Ck)zbn3!1ynst&4^{n>T zVFDblOUM4?%8PxWE^w+87GwDhN%!E(KenC%r5ltWs4)DJXFqSw5=*-SV$+!3;c!Pv z9b)2-^7laLME~78VA+I3Lb{i`lQt&~lJG@-zL}1$pS9onHqxa_g})p0^JuBqpQuLE zKxZ%Nk?&ec3GW0+qQP+spG{06!X#p0g4zvG`(yiZAvi(lCMq?Hk0k!b#-bUG~L@Vi(M3Ra-eea;ciVD!y_)835r)bPIW(M}i1H5UAJJ>Igv+}H} z9&9-+g@=gAdD{7T00n-Um5Hm`^%)q2x1}6Qi^z3ac=h1cl^ihf=srY7MhieKlDUA) zw;Rw?VcX}9V#K=~j-E%C4~W}(Xb+q^3>giWA`#OKU-o!zKtM<_H$YgTG%r}x zx0pMl>5VcC)L=XfF5a0hwpv41{cQ>|Q3G8~Ohl$SZ;@6g3mXyAhBAAO(Wt#CXOUpxy7 zbkT)OJR2#ptjrt(<0SRW$=HB`g0ghx=E^d!6T~%Ax{1+xOYxxxA>f@6*TFEjPT#MC zM!=lVu{-#bUD|^=5($&Syv&M-qU{FaT@t>m zyE08N^t^uPd;`Q!q(lJHhB6LQV}}oxI}f7;(+L!{T?-K&%pwsm0%&vQJ#>+}aqLRT zx>q)Q0@TuPMO_bflY`84pE3Z&0;DkX(1~CIUTnePMr;w?`S>?xnmY(+saJq9(B!t^ z$zgC$HV9gZBP10w_e(5sv(MB32DCw@%Kum)t8~+D3)av*gB6Aj5klU(^ftoJ3f(S4NJh@Q&tfv6Rp78msGIVr$8`ye^T;Vff+o@+B+HY3*p(al$ z$=xf!w?uq^D-|Ba-f7ok-su<2vyZ9_y#3Bvd#rSG;RM2n8bh(IF`Umf%bY z4jFC-XP^1tVttnfAS&$zWNoP6bK&rCJ+x|P;j5Z>Q|5bQ?2O-Oa!P1FoFJ`j4Is!xyTkH zVEOhWf1m)G^R|7=wsB_K64?rl_dA$|7H(>>XjeVP;BC_Mm?JVCO}<~ckI@HgJJ^fR zYji^7JEga(k=yU)t4L#ar~~x~JX^CHcC13UCiu=o5()Tn(W0d&{;QRr+bfp;ts*+% zT*Bp-jk?ZIZ2;^I-4^5=;Vpg5RosiYy5i(X9_of4#}RgIu*!~34I>*=Q4Yn*2Q$dV z;X~aVKJ*l{EZ=2-ebMm_mCy7hNPj4~jkX|_8M)KwomTM&+OVp*4?NfGp|=T|Yqn&b z8K>U#gNZ%MH?Wo4MELQKfSsN14U(D9l|h;WD}afwuQq_li_cfk?PRAbtqnpR+^anf zgHDXRV_g=aQK4o;XQzoGcvAT@@X;cP9)yq2UwU(`mZgsB!F#Kiq+e48`BUvuw6gT2 zfq?nL2DV|JzxXKTW$E zpuu%fZWV&7@Ow0(71)B9?G3{Nv(#=aQUzHUj772WVm4V9?!ywC5qo~LF_hq5_|2_` z4sEKib^S74A|`_EBZQ)!t`*gQ#BrzTJlhI(yb~2Yr%pO9 z*<)o9j`X*hP~5zS07`l4E1YarSWt%QVkenL$tz5|1zWMH?yLhLQ;VIJwA^SrrXa1b z=uu+bp2tMj0F>JZcnwOgWd=&vVm44yD>`%bfD#j}zsmrw@HK#h?2#n&nXw%)^h8_o zuu!LydLepz1-y$^_cO;%+u{B~RNcEPEDYW?Uo*FG<@5mu_nCag0QDi1h{u#pbCG^{ zm2EdLQo+N+V`aiUGLGtO7n=tcP$NVFebvHNw)#%6rLCc4?OE@{Cn)-d(;EkOXYV+! z#_4Uq{nnsUs~hnxXe7YP7zPQ3eBe(UYECRq*jiU1!cKDVn%D7;MAuQ-_XBMXI}5+h z_K5r0j=$&Em%Fi1(ArOdmyIpdMOrVRoWG;SN+wDfwAL{R}$Q=&LY5kcHGq}=&-sx;63V+k=gln_XzvExY{z13msDv zzOO}_oG0FV!Itp4v+EpYqW%@O09lg4-5xqzxPgb;0$-s8k2|30ES#N-cO7d11 z7l^AJn31sQ+h9rf5mzK;K0E)%3W7fqsW7>&$UBag2-gwEdk*h3=Jp=HciMOy?2E1z z;d8+nMVf@vc6nYfw4a|TK+laRXaFUc+U?&!=bFoX?fB9yJ{lFiX>*oPmY(iAQz%Lp zASHWW`^2qWQ)qfQx`mS1iwFamEBuLSx`s#jXh>ZhGz)KBKkkQc&S{#GokC4i6=;_*Xw#(*S)wlvBQ)|J6UQUVTIep6N*#0tYcy*&@} zQ7}x2XkTpTP<$jA&>SNDCp236^3DaeA{^Kx72;uM$-~+8hv!X&~ z0J_cMI++c0ZOhy%%nroe?84j z$4IgP$~4bRBSuM-zOht|De?Z*4m6bwREpD26~(%!{b;vC#fe*6&e3gNA;S4l{#Pqh z?3#vA7NDi!ZuPNlLTM!eP#HZ*7vf5#gyJBjh>uX2yZ3)158WHcwpQ=<6vcO1HHFC~ zYuIu0!<43bg`6tCa>>+H)p60Lrd7KJP-^?ySS|;->qZdUkIK8ZIRr57>NPgZ_Wt~> z08%V+ly-R;@z5PRx4Rs)X44l9%v?h?S57@>YmL|EhEnbNJ4mr8@gf~#W($(Q+C3U? zmANL_{}A%Rz4fTdQrN8r*<1_={<~}^+6QX?5D~sQiAo5%JlU|{H8;|*lwGSBI&g+Z zzadP3Rga9f*WIV(Ip7FF;(Vxe}gpYa(%C+&{+LOYV=@Ugsk5##4G~r_c*&pLEcUKHY8F2YGLP>0fxt> z_6_+RlF*S0I>KJRH`44|MG7^Q`gBc%A-lZ}ctZ#rDJkz=XW^&N-f*3x5z##s=SRrfy}6FAoC z7r=GVS}oyUx_S>ME0jDm2UinrQrLR$x47?SL&a9&7<1qRU*-+UY{RH<+6;X{E87A@ zS?!)?4pVm+s(`W3vMgkOfFss9U@$au0{Q6nR_l71!*==y2W5j0E?AC6X7|N#fW&Ue z_cb4d9x3~h;)hDI6md zk85GN$kbks8HyUqk}`tRO`Q?s$e*@{%-I%I02fj`gRB=23C&OwC;~3xxgTZnS>9)} z>6MxQiI{?x)s27Q1fY<&rj=V59T3SwH5WgmqT#14D}PaysH*j6#BE1az2;eov|22r zLa7)-{r8EUWBX^uQv(9?JG8SGKHZTt8XB5l2r^b+T{c%gaM$1;*M{lQondZBX5U1} zWT37a@Jqh{4dC-Ui71ZvrHX*YaU}&ANo=~`X*koGfEtE0`~7Kxn{>X5bvl0cTE6H> zT*SLE?2^T^!fI1&ZaL4uBqOC?2^_#tIa={D*#m%Jcf6)NUa$}Ym7lJy2V&&7cZU~S?7lDX$puSvI=(Ky52c87!c8g2Nn?(=#x{rx<%3Gvr(?-u2&d>yHc@2 zm4%1<7w8kv(2zELUrf|r)I*o`EK@DtZ*)wRb2yora@=1{ux*dnvg6VI);i(r)9NW# zgX^fq zpyTG;ey^?N6q>~OdSS1;iXV2idC+qWv|eOp)6SZVGwuo`2K^0Q=1e}nnL zu-Im`vohma7Px1^GVBdYKV?$eprsiDjdk>O73?$opnzNa2A9oJ5ymr(TcdH~A>-VK z#}>QWBLvUCHrEmMr$+LJ)*$j7uMUVH+ou!~R_E5qZ1&Lkt={RW1LwfE<(d*%TuJ zS7-=wgmN$}mliPF(Mu%%%Y1nP@?_7?XS4Zl=w~zJfE)6=+#GWcKH`RO_3lgbVZwazH)lO+dDX6PAl1V za2U}g<2}|FaK)<=``0xKe;JVw(v6|EWda*#X@6PghR%Ip989Br26YNff@c@13eI`s zWiMNIft7#VzdqjSI-Xqrju@oNz2*JH71a!n!yF=wd5fZ5*#vbNt|`T>Q@g0J{!P)v zfh{0bWzgpLOYq`2f02c3MdjuVo&Ikc$YXNpi*Ha{Vl+FYth(GXuMjeu)!-H_|0y?l z5h^_&L)$DGWkZ3f%H59|YeRPjdbml^v)hr!T}`2d>vzb%K_i4;CPF8Vd!VNUCD`9& zN9MSFKDWw()_TDi1Ag`e6vHNGzgIXNfvzDgymFQNSW0Wl<13Bz4E; z@D@gn$EBK6b4y3kru|XC#u52IiUtQ>C$v65w!_Lok=(m&2vnJ}AX>lSP^RWV9nA1# z9Z}>AXU(|{7G)DNSGGUX{Q>c~eJwQj6{k`?j+ng}LSOC&N|(AQYIJY*&}wgksq@9c zi8hA51t{gJO~$;)0TtX5RZn2SibO*jnkOYS`2qy4$Ql{!^-VaVI-A3>ZgyFmOw;iZ_mqk;k?FsTk z>B(I__E~Ri)N9~iR3^F7zrUQkAHVxHlq_s!@W1N17q(AXNG?tz;myzsZFBE-+BUys zhm#%F7DzMR(tB;+bhLK13tuH=;u&ehdFSxg2E4zg9grdTQu$m9b}2uWEM@F3YjIJ$ zE(XXYe`kt1URT)H?5S*bUN-I{7qj2VcX~1xXv+1bEju}gyP)l{8Sl)+e%fm^p(vEf z72IB2E+94!9;EjBy;w}s%^^>^Na9?w-(qHM$p2|<7Y4{np*Y<3pu0J*gP-n>(e_DsXtoGZj z$xgsvoJJAx1uuJZoDOIzF3S~f^N3fd^`E_&cRw~#GzdnDk5BG9UVVz6V+uxL`IZ>{ zJ9kCtXo#GrPcVE_bAVbLiS>OUBtr0^_mO}c!^nbYe0*&1H^#Atb+e6V*qeb*4`9x? z#_V@x8MV(8E`fNkjFL_|?XQ6>mdzr8ju~2t`Fi+7=&IDZ z^HRNq1Znq$@kLTa{!}iOcUDp>78?#pgubl~TBk`f25-k<(a$QIst8yBCkC`Wy^%0e zr^@q*{k6lfwJ8lab)#g99d|#~vDj?s2kcV_8AcEw0qUMj;f5V0tck@%2h&uvX87lT z6f~!6L6>Y^Eb)c@d5*)ns%gbUX%3MWj8Bx%;X}WdD17hGLK~Xk#$|smek|uTnxPET z28Ol1M{wz92$24`yLB06-7V zLOH&3Uf(`pupmIOxd`?KPW`mrqf9wWS$O+8(ldYg|~=FG50y;NZR5Vd>3(g`BXkCk;M7zzhjUm zNB0wHxarjmqP>680LPZXZnRozUVA+E%t1Z$SNwhV!@7!9r5Tb6bi(6GSM^#W z2o(7!%3>(^%*)<}Y0WwNRc4(G0p#EM8>i;!<*K=R+?Tjpt2N?4NiX#!eP*?k^qj9q zlrqrahaTVKTZ|zquSkfBvRNrP#m~HUnQYU5#NN{f_GEzy@EkW`#EJYM_o+%om~1+i zxuWXOjc#S7!1|2*sjzh9QM{17K21&{N}{FM@C;{##ZU$}2CFFo{h~=1NCre5=5)l* z8i!sUt?JyalrOj&ap7%D_sb}zscV@7uyk#3*ir{Fi%=|oGaNk6*c4%BC^9Yjr@o#b zv_l^6FVs~hgJ7{V_a5$*yg1rXg~C7maO1@0=npxgf^@8S+Sx52tv$M|KYe2{Umn3- zgQB+Xegbhdl~H)s{n0#aK$an3#b%%cE;BkVE;MBQBNDm%_N=*(9P==lD!$7dvbpRT z0TWII+7)W#1^_{cS>q4y@E(?Q<8*Fk9KcXT>XsJE$L!{@27H9Bo1V=c2ku(i!hA!JFX^6jr8YF4m%_!+_ zCCmlP?sZ9G8w8PYt*j?^^xLrtgN|(V!X}kAXt`alawJUs04 zV{(l8d?E;ZYUN!|p0m#{0qJPDl&+Tz+56lw2Owp}sBe)BkOq-PMZNYe81T@)x5JSs zAtQ#Z%}u;%j#|zfzRS|@#vQa|nv*DNK^$&R81+xlHd1+=#)ou*2A!Z>@Vli$Tc&(w{*U~3#CSt1ck(gPU!;^u|IJJohnO-UjP(>Cb8^%9}uE^2I^9;Q$YowgM)D^KVfP%LBgJh4Y^|1y|2KKFsmFpMiNZQ!N%u;r2-xf9SJ!`hRaF$?sWdH z>Lj8GgY#tBYj@hy9=*)We;ziWG@-GB4#0D9)&GXTcJpm9M$gE*9Qn8>M`K@fQs; z4YRTXVHJc8OVJBhAfTs((15BD!(lcvn%7k?br>2uwllgL&k@wM_$~I?32RYe4deWb zdNRY*K4<034hsiP_K)c_!{|?EjB24_qmS*48*&eJ#_aT7-r$_xh*ZclHfIn&Juls_ zz<1MLkF8eP+ovY$?uohr5E?a(Pg&ztp;VB`?}Q3x*9d z3v_V1xQ}@a7VvNnS3!q}xAe@`{?U;A!@iJoQ~Jry@RjkMA#SfY%xu?v6}tpqQfOzt z%87QII5ig(#c*}?vX!?2tG1BPO7RJcg&|$G_yVo0z@3%7g`S%V8TQL-nYnNj#>UJy z@_61hlqTNds;n zzIl6Ag_VMPEfVu8^7`m*n^c46Q)gTA2*6J}-Wiy+vB9y(4Tn>BR+vLQ&}i7l{1YP# zJSW};)*17qA~juyN|fO|Ez0hn}U7A8BL3P^T@E^07gVlv868?kiLO; zU6WO&#qVMP;R1i-jUSLYTb@rzZ>ZZDwrVuD2^29{cu=@Yi6t2e%P@9+;_YRMf;YG3 z3TLek3T9;)OZsMjVXKZYW`XNu%-$ud34t>zHBxTFM4--H>I?42$oEk><1X{o271>V zUP#PeVQN8^2J0Z)nX&L~8#uytZ`7wWwbqn*R>ASZZaTB4Nmyl{4^RlNF_ZD9Y`V~t zLmqJq7~{$@tjR>~iCdd|GX!r^e%C_9+z0U!te4li1BTij?(Y_m%kM_B+m1?B(jscq z)9@O0cQmFdsbSQ#_6k3z)!fk}%q=0q6let)niiq7I_b=l=%I~TR1}?zB_X#U34)KU z4^!kAlnLdKZ~Im>TDdHDwD!h6JfRxN_g^9_<5Ki&PG~2n_RG}Yz`0B*br+utQCtkv z2%77KXf4^ubmZJ)_8uI55M4MTu+~Y?PSfO88D-IOk};xl?$ty)wUy=|TsMy54SE$oFcZGDjwC_uQpgOOj%7wY8*sz1A+bsoA9THQR zY_=Waoitgv`VfI9^I1_p#l$;m@YpR7Gu zzT^{=BA;o<|L*X=xFsYfS2b2E3e110iZi$6 zFdrFAw%%%h@W2E4XkYEMe{sbH-Xbw;a3M)>-yUKvbUnP>=%m?{ym~5ETjY9ZhUXqF z!l&oD_1hXxdp+7z$866G?DIW=x8=36??B<6@TfvC5fJXgVLys^=>lgzq9-u79Dj2u z6Sh~a%4Ro|^A*=N$x`Bas-Ed(f6z z5`(*>egI8HAcCOQI@I;PKcDJL)t@3j@kv_%&2h>Jwdfq%+r);Xfwk3kCx)2eTF-E> zV{h7s=#gVPu>U}h0;-df#b$6KllLJjvsLh)%0E!5O8aQ0)OE`ttooTZYEunEU~q|(NVDww%9!PPzp zlNuG;l!AQOv5vk0_aa#I1OlsC4LXJ<%VWQ#RaFSAN<4;oVcM0-GhhI5;E5@ZI@id; z>0gmgHsuNEPdV@WQXkc<$CxXY_;pI(_*W(>N6mhY0!$zHZGXIdR&qp+ zx82*vWoaK{crDl@O`8NlD)s#uvdQy7wZzbPTE&iejM=^ zXQ_K3uV0Y}v}g!Pr~au_fvn`*5(w8Dk$iX9cEHmesC4kiz!)%}LN~|t3QEdf+JMR7 z?gm{^J&8(;961_Dn6J|H05t6@W>YOZ?g#xqmZz?OyF{fz=yr!})XNRB>*?N!ESAT< z3JD9LdBe{;>H-}hYn`hra@J!LCUP-YaXaH~hC_`>2Pqe&cW;9|Ymu~fzH@d~`90D* zVYM(MiUqGtKF5%?v^rM!)!ao-B|h@nX0yw<0(ms@sjys25$MTiUU=$9(e?oKgo&WBP>q7;FVoI9Pd&MYKYOrxfO# z|DL0^hBu*!!_1FypynsA6(~>;Ce_1(cew$P4Ft-a#Q{022&=Hy0|)lS>CR#DvxuGI z*JW?GKW~6#xFzwLnZuordyKi>R_SQ>95~EdU25Kk8(RGcNBE{1O_TO$jdon;kW<~! zi%eyjeoVm%_6kR9L)t#6r>+);WWnr~lDzEU4#i`O(aIPiR>iWBtdK<36&o^q_2qzw zBuwE6%Ni_#*$rLPyBr>ok*wT91bwdtG+dHeCCI+TJH5)eL#i6)G2$ z%HJ*2VGwSimb1)Y83YI&4VqbE)`+Ye*6XwTZf_fc&j_o+f%wh4ms@h5OYk^oy(4pkIVH$FdEgeDo8|9n$pJD>B|*w>d%L|Lk~1M*)$?0 z2a^Z^Ke-h2vQ4^il9*qekEA7+fPNCfrW)-WpvU*mKYKSt9PATPbZNbnbOtk+!0zjn z?wyo5%NjwY0yosWYHm!!CQAv=^m=V|kAbcBd8qg&qUSmkRWSXktSw^Jt zd7<#oXizK~JjRTw(8OG>KSTOO;i!Krw2Lf*^}Td z54Ewf`O zf0TAoQp%pu5*PF8I{NEXP2NdyM4YY0%+7%l-^byMR~OD(tki(L%2lySC&U`Ap1(|K zv3)>h{$Th38XVr#VO~oK%v7mw@p@-_pC}jn(eQUVVZFIq;}6Pf(z^Uw3|qr3#uoJ_ z)SvSKoSJj$Plr^@UJVJJ-5}VS4R?xxAl9@~$;5Y*f*b{i;kFZzyakl% zrrSj8S01W==*3D97x)q8xFrs$_W(t&PgH8%i6TMIMeZ&l&8Vdgmp%w~yIWKc#&lSO z7`BvGl80Qdn{M;rCyB~$3$iN}2v-%8Fakx1sQvN?5@{z_a8;_Pmc;fR^&G0{W~_#@ zejXO8c!0(7DB9^v;i@+S%>$+SZE^Dm7pl`doX}0VvMhv5OjjEDQMY35Dqw%+LU0UZ z3g$LsN^X&0P#a^m6WmTQTy+0dES&JCla=vak&>_XKkQ{2o>v~)tcrZ|q|f&--5j8M zKfYp2080)`1Jgc(Z!!Eyuk^?+9b{$XS17m8M2V~2S5Q5RwT|D`N7W0?ftQ<4ToYD{ zjxGN^hJ}-!7?y(STX~I58q=;6W#5+>^XgL;)htXw)FMT^RE+VwAVr0n2?VV_<`ADa zba1}BPe6@oUI3Sr4(o7^+)W=?w&WurJd$Fl#SXp^MwRh2Bra=g&=Ccr3Wgfa@|T7A zXr~_=4GhzPfaYjju}+S5V>2=Nm>>>Vx=R_thKpijRS76pthXJKl$}`uDUsE__p~>h z=x}X92b-hzFPAS_z(*j`=R{i4Pg(Gk|ZlRmMqGRQCjdD@B!7BN6uTNA&X3Sf4Db1Zkt z`$6%>jlO3R_6L6q@!!$@4uiz zL;+QGPkd4VQ~J(nx!}lcYp5eE>(o1y6*-};mCcR_!B8;h%teZ#ymT7pDxpi?5;@^7 zl}rHW1PyTJ7})ROnszvprhU9uNq;Uj-rbgV(QSie_b7k8L=>w8j%cMnT-FPwD}s1H zRt2WD27NTfj{nr&@fdAB_?q{HPFr)*rw%SL1pjP3qa(S=VI?KsC`^S_d%t=2$U>Zw zi{rkJNM$@sedNjb#SI}&e7m3@z#X-bP52Mw{~$8=C8Tb#Vhb;7W-iy}#{ z8%^)rU51TJj6oaU+Pif;KU+uR6a5qwnz7Y^czU8}`P0^J{lgRoa_IboO`jOsb-WO< zap6y7?EfN;HUxotX!{j{I1*UwqT*D4uXz&6R%A^uryUa1*jBJqgqar>vMudsoW<%i zb-j;@&Zvwr!`|YW@GjZ_JmjTS;s+Q4GpKYn!sEKfF*3 zxB2<=Whqujso8CSuO@%7P1sb=qRP$T&z?3qAv-ibc{d&f7X;|oi5qVTY}2H#%;{kU z!TpF^a^aU=pos4I#m)$~am_NYZoYMi_G_T0g3fhFOJ5Q9XjSuWdviD62aR`%k?*z) z>EF}H!yz(%vy(zlrSRXCfn(Gr)G4mMlKg0RFE&g_p(a8qB+#(JKx2Kuj&m|I6go#U z^wM|?^hk2Lk4I^j4-EC%1CeoHZI$ffDf@vGBSr6p9fiakZO*~ap*#xHrv4%U*GQ`P zY5|+N`Cv8T(bBvtX=|shvl69YJCaW~jmp$1N=<=+;w_?rLP}ofns_&Bp=fCy1cJ!) zpLsbZ2t2|Mi?NQw;dHTZ#ZzJ?4bxi}Zb9r~w)BPHB|48}d^Tw78u$2_ndo8SN)L6| z%oNDVHX+|?Cku(LBk2<}d8}t-dVRNCbih?<_Hh->4abwP$uP1@7zj!oyp8<8_d94j zbe*1mXOW`00FC+2Hp_qEp)UrJ`Io!8pyAQC7$We5pP}2oY!yK-pp2uWJ;1cGd@rg^J z>W^iYThPFYL=zdPf=U3A{m*LB~~=X1ciIRyEv z$ZWs-&CN_w_B%~yg^mMnAGQsC07|~c7unP#LNnY0n`F*x_cLAov>v;Z>3%lb*Kw#1 zLkwBlT`O{6x^PD39J;-!c4*(7LfZoqj>`p&8;sp>dQvUTo8U)?Cn48N>pT#9TW;U& z>t#L}d04%d{XcSK9&S#iX zEAJ2rSSGQ7WRrA1 zeTj7Oec)uCh3GM@0|#d(5kAv^!$#@fOy1BZr4uH-v{!cwK%5t(Zaw+Qi%KnfpOz@Z zlX-{kea>pL)bSNuCuitSK-v6}e;b6mRdX45^I&NHmb+;^CmC(b1&(SO71`Mt>krWltx3QmQY*B^k?M+gA)2+7ysL>A+nsvr0S{cS7Mn-5^ey{)`MEz%?+ zJ7X5jWf=_kd6wLgXce9cc`EHGfkc*RNw9i}ITeeB$}}WLis;(z-Oj3`1hNXn>q63q zQ|owZO|AKW-dZw#&Xs0#UlmSS5IRmoc7#fO#La&a3TLP#&SfjQ6aw^eE2XafzRW7# z(bmt`{v+E7PRR6TTReLatf@(qh`|K>$)}ND@XhDKd5%9q3JZ;Swm%^JfwC}_4bKa~ zk0#kaCj)wqacb6N3E7p{h)69BRmkT`t;o!n=-gaS`*jTu^YwM6nhA02w&S!}YyE70 zZroWsAHlK0snmfaH@}Jh;u`OnFg$uW;urb57Ngi*z zHH3^UA_O?df0z0S>sAtBISj$H)+fGUvEswO%aaiZ$1e)3gaj)>?f=-~p+h^pA0NJ= zXTK1OniQis%3s`Xnt6*tBqfUDr4j*p0&lGuOYNboY0>A9WUUnRH0OS>$tZXnA9r^U zhnf^UpD*4e!s-%*x#A7p6-Inbc%A`SUryKCe&` zkXSn>2rL;U2-zw$oyVswCAJN3JgFsAZsni*jl`tlOran*s5Ut@`gcHBat&?ZZ}VG1 z^EF$}m;G(tptQ)!Be_br2Z>I3+HT89qtqy0Y>J22MLXiqc-tP%b*P9T)V>bc<1Lye z$NSF)K3&Aq#aJ!bP(&+lhK9Qk{wk8WYbI<3OwUlh6h?*tlef)!8*w#C)7E!F9CT@{ z2uw^tQZc2ig4cQkZVj@dMK=knl?k*_sgnWIYTj(+XPBZ?ny%Iy7mRC8)p;2O`@9MN ztQb}D^fI-z&c!yvP*DN=xBC`;y}WZyF%S@FkyX$fsjiBCmxWZ|rT+Y^UPpCOV=fc) z{`*=RdMr_}0w2oB?tVF^p=fvZvf@qT+(bGRMY_mfSEYq}UIpD=)`CG8za(=^=U`ci z4xM8*M4Z%iGyX?x3h&q`AHBY|w-f-*!ViSN0tyhE8%8dyuzRx7FONiL;tRhxG2*ML z@xxzoi%8cCZ6tkq0;Dnp2tHN;XaQevG&EFd3_6;(DhwEyswD)`+xV^mp*eq7G1#=> zYImsQ4{`2ytoQRRl?QC8&0H&+kae0>Ml{pF&EHpu3lDO|l~Ay7``X~C=EPr+HvvmY ze}PTDtU>Sx!sS0urk9TM9pG7W;Me_C^N+v2d2gMp&3#F)IW_uDOd%eVeS=TpkHj^a zL7$e>MxsIj@LG-Q(R>!elVJmHX;%=eLM?2gX7UrD-ZB@&Ag1jVoMr^L zpHTMWo=xbec+}*6hH?Q4qQ=&`v zCSz6&m-hTg6&~5!h8uljJ1`3MWjQS^)(jV{-P~!i#B~m$=!=>-Xu02i#P0DQ6u<0T zpKdakZR?<8OflsGHVy^e7dL_1kyr>p3%Of`NpzBRX2Tr!ki>W=3l*_ zf38GW3GHuR!+0vQ3u~?aF}mAi#Ln1H=5_rOUi=%#*7#U3$_*kk)+@LING?Cv+Wf9M zZ{ZP)nY!^u)M6v7%+0X#%7l&R`pmB?&v5;?ck{{%$Yhb_n~xfdG|Fn>v2Y{#owXU5 zyMWJyXK{;Wq%|N`=G`iq-Ya?}(R)*Y&=$ShflB#z@o;tG<>$>wgy$TNn#woiUHd6K z4>9fA3ww$MvzM8}tgxtf%O{eE0iva^;3hqyP8*>sf?SPHx#(WCj zSadO~{8e#Xc+|M%$op_kI?%(yO?`Vy@Pgb7LZ4O9l?e$^fp=I4T&L)>8fabT>yV4M zh363iP)(cV5h^|><}0!=|0O8{zZQ619Mw`AN6B%+3dyEG2k71x&9+>S)07JO?sL3{ zF4o)3X8?!Bo9iE(DNs^D-1oyor`Gu;UE4_enQ5~U1qtjZqO@*w-5h>X(xihE6T-UIWOeu-64%Mvts4utAv_sfP@)_R{8`a! z*)q(EdXca37YNE_vaYM1%w*p(4bEy&qN47%;+_D9?wLV6F0BcnCW+7*2s`@BJr-oT z+7sdtFU4k2FHY`+d~m~oOZe7obTW^}0MfH=Yyey;*dGXcD0B00lHZS+rPOJG5+a$; zJlGx$y*)+W^k0ea?kWQFY^690+8Kkp_$pij zs=Wj2hr*C5*;@Ql+#O|%yJfb!a@`uLSOw7Um8WGO{R#f7J#kP=?JqpJskdbY!i)>C zW3xUqZo2$N*`y4JYhorM3-+`CT%>6PS7w|4B-Og#8~LH-5+}w(WFlB znjK3<$LYk*cVCyq30hfirWoCMT#u{|4EUBUI+Z)zthGsO`mBWXY?@n*;2*Qak>L_u zoy^Y&A?yCv0&opkL0<(2M3nUmNF7=(rQ*(popszBKU@bt75%QxQ*D^EumbQJ^yO*+TG1jFh+;QDfATa|)Z9wu$^zlZ&RDZ46X|C}_ zP-FLP!Y1I83xyM#{Fj>&D!Bsw2KWUSNN&F<7*P5K{2Yjbh|Ifs|)rE-d{&F|rqUvDsa& zL1&dyVC`mkS>a{JqCNK1(^-`zb$#>BI4SOw@EhC6K%qPmR0jeHz?_Pa@62{&9C8@) zr5m6HwoI!AP;f;wcm5eizyw+^DImT*BupZ|R`LBe?0lr8g1Z+2y^gl{Ym}H{QeO*~ zZt!nM1V$n8XHKW?{uN3j$35=nn4@r3)H5Q^CoY-s3E%V9h{M)Ba%Wjhs7e*Q@Jb_V zlA?GlWrLID&8jTU{=+uE;2tQl3XFBN0YuuVUM)i8liA6=NN(%D^Pu5b+b4AjyD`&f zD+e^ZPF#4N(W+;o)z6|BX=-Ip;W>(xf+DZ023wvW*p&_8btwh~p$HE%u`DB44DH#6 zYQAk}>`a_QQ3n?kh&*Slm#>{d+8-*A`S>coSExQ8wl~t}0~m;wFt`&zl}h<*w3~@n zckzd6x@g3|UVmsfp9(;lm=6ZONX0-yQ@L^Hrwj3XDq_i~hV=veZ#9Z%&&AXTId0OF zziDL$PQ^tLSa6@XH!d}`bi$9B@0OM@aBy{px6xKxi&s<8DB#YH-l9QXP6fA%qxGaj zrCR<6h~pp?cfXI*_SF-xG1yrO&{8lu%E>6fQ&BW0V=-$*6q#_o-v#H|iE??Li=v0Z z;0QsCKeIgYj3U3!8k`Y*!#ChSO^6dFkalURyu&aYU*yN~8c~%a{1<0qf9`N8S?T_9 zQQ;K!@F5TJYwaQPsNUT5RtcJbEt3IRS>7#IL5kF8JKkUVoSi-P1BITN?m-c2roV8( z0oPGGyhv9my1Fr~6iNq84gRq1%)+cAy>Q7ogh8Ov;pZoYaz(IYvCig1%9L|>m=e$r z)Q?R^%ca#)Pw^3=-rSGrE-t};N>tA&3lCvYj6`z)J-oh3^iKoFp5`bW*+(wJ0WQ{V z0|h4Tgu{7gCfy&R8XX zYcEO9)fZSu@z4E|4FTLQ5D09e7$j%pJKc?!?{X!MOHnhaPmZ4Xx%Fuzp>N>7@OH17 zX1Fu5^x??4$*XuTL?}3m6zqV8$~6~GU1o4XR@iLXiVZN2Io*$cbsTqr70f7bYmHNK`uBQi{y23qJdMdX9(pd*G2ns!?7I0i=OE?f6W za$}CdBf&hp<<*=qRJV<#xZR=*o%b!cfNb>U^$VD~>_$Ka%!E^!CF3%cYe^d3I0iPc zV8~zDo4Ye?-c{Q>e7W|TyR=SO!|I8Iv(%U%4B*}k{GK(%$C zyoaSuBV5JIj{pzsibs>shj){Py~tls zB-P%;1}7XFEZ(p;+!Sg&(<%7rDbami5sF&-&8~NMUsTV9PEfDqfure^rN_V5!M05+ z)C!hx$3U3X`z`!HFNew)4Q_O`3ZEPH=hpB}OhS&?bClNS&38YDfPIVd>+9fE4t6Zo zIUJWI{AOS{7P;@OB!4MG9!G(7m1-pthP|cR5|bkB)2ld;59Rb57efoZr|3_PfE>qm z7yzjR0aqjlws&z7YCD@@_1%$&Q6Rp6{`J5Xb;ClmN5p-VfhRFFHEcPt)!`5KF$hgN z=^eEl;jh?|v0K4#H{<$0{L0$Q>%TmFtKg%w@hx1R`H(tJ%oVUFq)hmv#ZNzf3PLtN#+OCz( zAtYsJI2>iM7_DGsXKYN2RPZQ;7Y6ktu*4&Dhu+J-2chqts!#t8yTrPhVL;&1bS4}T zU@bN?wDNNFp1Y7c;;*>Utgoifo6;kwqoA)nCpwsvGiYAOiltt3{)|WyHhF@@Qg)a6 z_LGjqFvMsQTr1%LxqusW5yry_)PdmMTUgZvCG zg{j}e(ScmC3699;B%$CF>4MT@Q&QM^nb9CjggvnRz6gIKA>qv|Z?fO>cNcnAuE?;c z1v07mK0gx|p?wi=;AQA$K-JX&WqjqL`^&PG0x{Zd;7f-2CFr>CKjIhc+gJcNg43V& zbY#g6XtX3PSgoJjxnwUi0+_U2ZtFCj+Z>z5LR#Oy4tRMoE%(4T{6^uLxnVx$sF$?) zDrwJR&+_WnC*Tv9^6)em-V{-rtU2x9zjlF+@=_nN@q!|!!sB2-oY@Lz+pwIbdnZf5|AL@UhXzwj z`?+jri)CTz%AH%TBOSi7sH;ahl)0j+vy%t>s!k& zl=Kmt2+02DKA3@7Am~tbskzRms_!6C8CTTf8i4v2gNvYRdD)819+WQc6XHoxCcWy3 zivfdYhCq2tIs>DbBM)><>CM46CcjoT5l%-Wb7ZkFY~df7Fx@nMukVmHVD^R?Q1($J zdTuvbkEXk7SOE}OeI`(eRq3OmOQCg)?TORF5)L5Fy}HRs3aa` zYwRqlQt_v`1bQO!PkAUCBS!4`6YHP!gat`jKqS^?ZsQ z9L3^)@Pu@`@Ldv9OR^{`5nDc}FF#otpGrF7BnVX1&B}PcaFYAmiz)P2t9+8BJhtZ}`g-?di;rvwYO3n3kN?|zixek<=Un;(_Ns1Q3A5Hen z2X25qsO4W&@V$T&CS%$gDapBJ?)yww$+wEAoLn-`^kCI8G>oz`gb=q^KU#{GRnd?I zR^}Tcjt1->aBA|OC?E|ChyntyZX{<$j1p3|rUCwp7+1$QS4qvHh(;-!G9(D6>YmI! zg$J*DxAvgqro)SP^hj7rWr74V!bOmq96GV!ZO|_UmWycAcE!EX%B4}93=Ia;5UW1R zHeJFzE(lgfg;*Y#W|DlG)RSSu`sFTE6PgTeAhOnZI&M|c(zQX0Rus-q8@-zxD~Bd8 z%ZNU$sQ*kl$0t+tKT!J~2ivB;5~kK;9|tBO>yZ|fSIj)HKa5~8aiZc@$JgDQtNOYWfzu@N#Xxf@LzKA~p}qgXdRtMeaZF7=ix6?GpxE zo-d;Dds>rjt$%aG;=!|dKqo>KR}p4&vN+b8KOBm%?RUH5IGr!-fTc(Dg)J6ly z_GNxdsk_-5@x$?cKzYyLG3`9V*6G}Tb$W0bXgZ9+61;;zd4TOO3GV*MM1T=m+ar)0 z+pZE$P)Y6Ywf+dko>XGs+QKp1$rr6jq#YH8M2ddI=5 z;SL)MFRNNrLeXQ4>RuZcI3yX%ki-|o3m1+YlLPMK$Ln2oK@>k?Rs+2PIoB5GYnDT6&o{TiV*S z;BeSJ^JObS$98B0h8%UgM`@If$`K(vz<`$$<7e?9snQfq=804eDY|H&e)zNPraAj(&YYspML;)Qk&e^Hhpv-E|pj7mr#``v)|)zC<=t5Zl%E(%3k zRA-aTl{7q|XY#z?WQxM=Vaj386ib6vB&a^bqYrYx1p0W+#t(x}xauj1BI}9ci{*$Y zT-6fNbqFQJ8!!O>uVPZNBhp(pLL9T|4elPtzJnYuc{E*Uh-(J!Y>Y#%- z6b!4GrUmf-s@zNEKoF$OiLa2i+3|%1T=lcsPNv|f{YJzG*n2=SOGwUkMuZPb=!Prz zF)S_(BK@&usccwSwvIs{zEWRm#pZbIK+|ZWdL-L_+XHtvGnAs!rrCE5yB`wwUjh}N zsdu_cJ-Jjk#no|>vU3y#?UAsxx`q%>WV^{Ql@24P=3B-_RL4=mHONo#QBs$BcFmHv z%HZ%tVH@4)tqTML%vR7_=g*E#A(>__=j9hr8?NOk;58tUF3|b<#j%l_mixs^fsL&6 zD0C2e3PRPVEOukS?um&W*jqW#P#2 zk7{&a#-Qvos$xFEGm_lKCc>FowzI0T^-Cd&-R^_yNl2I0UtNW#W=tp-IZ-D6=}QE~+%cyHvezUvaRG_{9Kq><9#HorBBfNq|bJ$E(+b%L6$z!%bu zZ=1K-eNJVeySrT4GS(pdBhh?H6ES(p4zH|FCr}V$<*Y|MjDrB>ReO_R0!(K>nZ0MkH9~ujCj4^qB<0dzE%Ik^j*8( zu>mth2{{I!>yU}nY^9+U77I_H73zS9@>;8K)`k~KgXeaSlvVAoL+>k7ZrvPpse1u` zP=QkiwA1c;{$9>FK8Kf47wNso6hq>B!ha9>-8Qd7P!=Npvh6A{sEwPE%vH()JEj&y z%)pqF~Zyg?ZDM%Km8%NEodBsB0ScC>RrdkGaO%dieU5~R6*g%B*rHfBB4{vqw#lr z)H5iKt21DVC`qAsF4#(nJvncA2)lx3eMQyOSS2)Jq>UNO?6=U`9(;kt&^I_w2Z3O- zzqjomKe5|8J`l1J<7Fg~&|dsRI_WP0;eSVvILNG=qO#-fAC%mzb|Ff*#6pBkyIP?G z%tL(_C=|^*{Q8^)#u9TYykMcYNT&niR4Y#9)d;S3=0e18f#{RD`f3TdC<~9tW6?x0x%sA6Ey!OBzt-?nnBNP+KS1tL5Z%ShN34I>|q0(>yFYvZp z#afCFek|$!7{DV)AHTezl#FPgZsApy(7O1!AwZObU@f=bu6W(3P@VJEf1J$M!J%Yj z8|)nKfH5kHiJ;!>9?O*Gk4}OwtIA+H9E%;Qssxl*VOv++2{BSQu|6nNa_424NzyLFT&{%@#bt{&8 z6EW{{pDd$sBj{`EVzjxvJ=Nyi9p581|95P|&LcLd#QwaaZZSOL@4my=m`p_#&OyuL`<5nU^J9x8dQRX-*)eLsEv*~_EP z8ffz@*(`7Z5Il@*>9(McczuPF0R-*b%x3OoO8v{~q|lmDq4dKCuKmTVtL=cGm=!EE zbDe6#tPv~{?FOcW&W`*BMnonJQ~7l@xqIk#QAElmx@mTaYWP-!?Y8jw>eJv_kj!zb zAuk!MxFUPG*^mWLTz9L${t&?Qx;@%M+w?T&2-8ZOwE;}SPf6BeAz$HJ$fIZ?%d%~g z$r-n7IAXKwJ+Yzt!Zq``;ItR(4XpZ4@1VFCoUEivPGsnx|_@nrV+cujSp>+DML`-Ya z^KQ67ZIgP#@2a$3CSl1K2qRn$dK5k0xMv-xI{!NS*^9RX7c!1fzP2%ILz6CO|Y-EnVwjA-KO>+25G(r`|p!E z6M^WN<&@-YRQ)nhAanu9GL9|JRo zh#c~o<4pl=sFpmw&VLk|@{!R(>H&Lp7EOG1e?2uVPZ~f*M^Mp&3MpA~YyCCoYhHRR zt_K(*uZ?dHxJTeAuRjk}m#8x9vR#(oT!@YsnI=KCsKSZ!q**a2{O{FnAAABW4IzvE zFH((0!egvoo|oQ`2vfk$G-`X#%eeOIbOOdI`@{Z_B0>2eh)uo<16$4n0VDXN8gBm$ zpZ$Ze@2ul}NlA^JK#Cyn8Hw$Y-pHqu_p~^PocVysMoq{qD3D>^Z7le>igoj)*oc~x zi9#3f_UdV1^pnBaL7ud7bSN{A9VK26dJdLbKOd`o3*-*@yywQPT&lzWkYP>IYxri2 z5E}BgWpx5J`@=aLW*HKpduh!j!i>;=@;``S!JzsdN~7oectTRWx6QX{4IjA{d;QH^qH=~^y7vR6f6#Cp+zpClm5{#=SzheWOs}M)YWv5CC33RM` zL4tKMqjDS8u?noh5p15UiUJ3YpCZNjU@x z5_*-NTe4sblvCIvNp&#uuT05%V61~6^{y+Em#JIm{U?PF)?Mij^kV&c%shupg3v7b zx;^&}t3l^18#ViCgCnIPPLCSE?kLYXE80`ja1o$--ZMH_2NHM4(6YT^(5^%bVWJjg z_X=2U7z;l+pDL`9iM{nY@_zlObe6L1{ z#B7{VtZ$rgn=>t;IEVhISkoxnf=GZ~Y+pC2)Ll~bB`22|lv%)Mch;&eSEI|fMdiPZ z0Txn2cOTab8@2FSk>KZn1@Y1DfNE9bt`Yhw&yR1BcC-FY3jtDYwdf7QG+gm1VR!Rs zi*G#ek}v-=V87)_fYFo2&-Lb2GAt@}{~1`kQR02@>Dw=Rfcya|m2l`38(W2iKQ_iT ze_ahwRi494&aLFN>E4L6vhoG~Sstw5ScvzLYOWi7b)hQarsH}6yM+`#8xu>YUDgW> z4TO}M*{EU#QaZRn3i|k4qhjfwhzV^$KwUi}Y;FuTd;QO9N{ZWik(xC$w%LWAtdPA* z64^XY-0i3E#R3ql!;;W*$r*5Ull^d)mjj}YSu8M{X4+|r=T|$+v=6AF5=gmd3B^lh zxf@-0?n~?A!Tg$Z8?)_H8_-UU*p1?ZIxw;zOH7fphq(go?NX?a@@vwv-Ji!6izLgw!P2+Xntyv-# zjKZ2INEzY%H%fXjDFVC8%WAhD_NOm|)S@UfjHAD>5Zv^2cBl8T>oHLY$yTqB3K_HF z<2;6zqU_av`hI>ye;z8Q`~a^YBi~jwJ=J86V&HlDkJ)dkoWg%#UMt zCoTZjwt=QwFF=?wXnRYjBMeeN+;!%!xa90)y9H7ap^HSy2`;i^Kt`oYHTg3r2ieh< z@=J7Uw{hL2T>p;vz95_F=Y@IVe)1p$<%j<8)ut)?4N&+vr8ynaUV)dZzX1q5p#xb6 zd9-#iU*{jhHBfE`wM3wk_qbWBx_`e~bW3x??eW;e;rl3_KBJxh3|%~FVjW<12yXqy zJ-=DHD$6ZMbKG|($C@lI%i}Ab7r=Tw-8v0yD{l+XsKPl7bi{i5VAMq42l;fcsuvqY zzhE0A=npb}^e44To_rI(%$`A_f)RPq;c4Rk!_d*uQS361;pL*JP7{{#YN^8LCzE5= zK@g@@3!K|66In+8ReoEy=~WfuITvb$3^Ql*UVYVk1q)NwR~MbfWT>uBZU#(dQVa^s zT+|_-zcASFH~weoACfoTr-7U*{T+JM5eb{bkdRXyVq?q{?06ig=60;koJ+n|6mTHD zn8xATlLTdXOhsRWiJ-DqAD5ck&B)EiK@fg@4fP%$l8&#si9C3h=YqshrmJ9RfY5B6 z4i@Fyet5PQ;)P1zHH{N(DRcOU!0P{A;Zmhs-UJT~S35P}aF!d|#Pa1Z$&ZWD0XWij zjPD|>l>?-Uj@p2vxbtx&?$=FWpJZe*nxl&9r0KnMMqZ%m!(sqHUjZ??Cu7o)jw9ro_n7FYCABYg{JxI)uz@yFlUnTp$W5 zf5V1{KX&0cSfGXzC`zUO39tmC_Ukb|ykx_W&goWI zD)$RIv$rFHTobR#G2-72o~gaxODnNQBJdm^0_KDWPjSlsnCc5(ps(vr`9sMhQ6(e- zKVZ#|ZcVlV^__Gh>42QxPTyA_G$|IyV4L-s?3U|KQ@GSHwRJmdHJ^*5oiKQ}pV}#Z zkX|4)SrDum$_#V<6u@iQQKq>ig3k7c6Ct0uD1bhdY5nGqS2KjiAZK`I_QB4cP{|Df=)2<;Uw;!v%;FPGat zYF3n7#Dtug*H*@W1>!{IgXiI3hg84u5LsTbuTyC=y~e+{vE|hOtw3_)2cdGs)dhO$+k^$how{*~s0< z2oA^kpb7D2Px~~1fqGy6*QyQ0EQbGU)kdO=s*0Pc9Tcwe2ZMjEfZAw6ayrMsrVNOy zzXV25_K04YvnH+>V|FG_{cFH5po1 z%BRuoW(3j+K6o58{8)PA$)*R);>yEb$!t?rVvJE~8=|i4{DnG5?YyLGrBEge@?=)w z)#V}{`*zCE^VhNkvA}UAh=LBA3T3azad-Z_x6`abj$kqj9z=B21<1|0pn_^B9-yLc zGeKZcn)m_c_ksUzI~x{=6>;M4sF`nWnvHNBCC;)J@c%gl!GAfOQOXryZGy;QV`?xZ zrdn=WI39@Wguip|zJb`ihI(DLzcxK&tGhi!5G90=#VvWW?yx;~4d`l|?Fj6TxA~l% zcv&vKmij>s94sfH@dZoAx%WVc7NboA+7RYwil)m3w2*Ac-1G*p`$(%GazC1q*q`FDJmmM;d$VsNUAIf0W9s2PB zd;~5$Av36QRV8{3mOcqlyo#0jrK8#CVA9#t_jNwiVJD*hJ40OrWIC(F-MoSD!(K=YY%;#Lvy89z6o$|w5>Hn)#jWv7ax zjhS6+KMT%AOUTbYYR60;S@EEC?pK)HJvG6GO5dhSJh_9$f-bRT{gcpfOY;N+(&+KT zPipwK#1WT{o7QtN#rI)6W~yie!S(T5-*QKT@bVb?`xN-$s|lxJ@v7vsfHa$$3);$n z10uDptC`u0A=_CWvKgy&7^Qt%($4)2m)z{t0R9PksOy=|QB$)`L||(RyQZ69KogXz z3EZ+Ryr>&vDEay!s1rN9SYdHkD7NWORpd8M2v4#B;?f~~ZJ&L_hnXvN^2uJecM3Y1 zv>1BMY|w<9Qdfke@}?l)hwR)NTNVZ-ciO>ztbZ)sCBbtR2+)BBR4kwyTm3ei{6|Pp z1F@M=Y`^|O;camwP`h5Z(*V%@jX`djk`T!XObg;jEpIxzxsp}4hUtq1LElN|_QGM( z-$XAu<x&&?UPK9;fse&0y0e!pCrl*)wfDqmgyFC& zUyiWNwsDp5zPU*;N&+Ju%HD=Jh2M~kPL!MdjK~6zjRH5@vQ96!{H5X($wzYSRJcy& zBcg?CW{&0dv;VGD<5NLMoEIPSu_F5DrFa0bL( zsm_oEm({QSHf)JR4rI^ByB7QFavTXCKv3&ad#u(5=#zsD@GK;s2Y0{$4-S3D-DNU2 z6==R$k7FnlKuI)DRZ1y2$yw|Dd#QVdAkKVdSXmLc#$;o>i@Bp>Dv&|zir3Cujo?nW z%`Xw>EaaV(Z5vQ|P<1Z)ebs6WH~DpCGou~%lp#hWB=hM~{V;3_KeD=04!=w{X(>^C zGPouWO>{^WKb2tV_GDwnnP$s1i${9}KOotJw%Vi7;8YV!_peBC_9|;Y`YQLTjbie` zcN~>gwz#vnuk4H_1?~l+bFx7Ky4sHPm0LQL#lr}ApC-bb2#C+1nlL@dkM%aM-MJUJ z+I>58dVZ^I{jZXZggk@)W`7tN!Al8^h*U?Av?w&M;oTZfts&9D-7Mc@Bc@t*wvwh$ zv@ZG$9>Wt2IeWH0MnFQ2$&RfESVSv#2B{@AC(98$U@iFBXB~9lphan?5W+o)8|}a{ zRc_;Zj{ZJPPE`kKk19XLIyyi4n^@UB-T7Aa zK+^XDx^5uIXvMw+3G7O@uyE3dtpU`(q8Ecy`zH(VZNMA!?OC0)&~x4 z{h;FuDhTS{am7eheBvs6Cf&&IP*8M9<`uEQRW;Tp)b$z0jhm>Y(p^7bPP);mira}3 zFRpQwhcBGXxH6Y$RuEj?spu>YKl=pcx%)s5FAT+R!`*5-5fYrzyk#-}c765vC%;R2 zV7eQ!`Yi?K{#aWa(DH+7-!|v$Paq-zcc{01)RKLBlLf6MT?XDVzB9E0l8HTXJqQk| z#iSVAG7+TP!S}@t1=Kz&|KG_tEPORNTZR5?zZn&i|5K^=dILOn$d<9CEF-xF-K{c2 z8vZG$!;li2d8uSFZndw0+E1gBKb#O|S|oexAh%u*I0^P!4_n%Lzm5XllfS(UbaS@< z{14wC2=X6(!Weqb<@-3Y*-huS$sa$_?SH~()n=rSsxy)smWh0ZDBT^OP8r#Hl&L3S z4_E@|UA{B@0B9?PdUpui_-#LF+uK7Jxp!-G1+1@|)wu$} z*>y$%zROo&(PL5Y=2|ti`{SxacU$@)lOxyqIesXwgsj1v8=?Q7R%Wvi+0&#tB;8Uj zG`)dUvC%JgHjCYuDa|3I(=Ftg4%4Up9;FMkbwj~vPnLYVlNgMLjhS3b<#Q+x{tcbO zd9c$R#+y;qF2?(lUn#t9^B@q_c$rIu@GT04SWrLz$qEPkamT4(kO{Dcww%0 zl();)Vh+SRYzRI$ZRL zMkqhW7b|ugBcDflKCU+~(&E3Nf<+)Z+XZ^!>8eLuY%<{ZABM#4HZd>*N+8K;iL!mm z>9G1b#1+E8>i)>9#sR|-xr7uaF;b4pyLcf!dYHy~$t|8)jByN6q$CWvL^R?24eEkS z0+|I#YwH*bc#b@iX$-K%v#wQ&ZlAoMho9Zbh9n&KsZnif8{K`BI65?^C;yu^7`2B2 zxDp{hi(tCe7&CMQxY{tRsD*d_gMdmSt{@gKm!+ho!(H`Dr7TY=f#a+qN)`PrN?9Xr1*a$47 zeO365oRCtwPxJ$1#T5bpN7<|Bx%1ANxWOeyB@zs`&jgn`OsuMvAMWm?OMZ)9rs>3X zBw~0+?`#n#{Le+2;(?RkDeaOxW=sF#TopYJmo#Y*&ldW_-G9`_V9yqBi_yR}F9QFW zQ|d2pKn5Z>BJG0le`(?Zas)Ue1{6k9tfE!9ZZsbDf>wn*g4ct~>FaT>#R%zs6PB2C zj-}eTbo_{_<$OTT=1*+&ej(<84#QX}Y?;vn?%H2M&ns3SPILuc%aX;X^DHmw%m7on zOOZv*!6_?NAPeDSLNSs(T?u7%B=Rijz3jdhAv0jYHHR2XLW(I=gEo!~u3AsE0Xn9b zkYX^+vi9KTQyBux-_E4&W-YRKP*4}>VD;&_th5Y+n%e^fu5jo4b-R-1Bu*wT?q{>= z1)f8F#2t9A-_FN@Xj>2r$T)mpdPzDJB}2!hdoOX2Tk#!HErDHOIUDmaUc^YfCQE+W zfKQeDr)dLPWY_;mP5d7@jCax1G$TI_T#*s{lf>4}!x?ujCI#&hX^1l()HuA3m*mKc z>;f`V%zN4B0asCuj`GqSn!pXc+nGiuw@3t@^Y8w0ci+TcCtn#}D|Ue1I*>5vGg=Hl z*Qp|&hnrc&$Q30;zvV2ALCShT854%QTAUGfB$ub|d=_YIdhs|RG3$e*WBLdlxm$2h zf5@dgZ#a*VeYdie-+*^cmdx!L_jIMZ?L9>3SJy9!R%M(aR&+)5`mV7#$~1R@gP6R1 z*aHwa!lC${8Fs}mX1CFUVlt=Elq*7b_b0lei<0hWQmo&FNEr`SRQM0_SIHO&i6oDlLQ*+b0AGJ*zK&+=?!vq5Q7O6~t`pdm9jr zQ(SMb%Q3wAN9M-tyhN-P&*g>MD=)co{#zyWOyF|VLazW|iAnw?^uwDWbQ~Dgu*3h~ zNesWM^Odd}GRtqcod&XC98PF1(%V9+y11!s)UWY9MmxDwj4_*xZnkq4UpmB&4b$Gf zG{7#pHaDZokj&?WeaCIprCcAwjrd@M#gh>gYa0_aJ#@n3-jmXkQwwPes?WkX{>u;? zm^+7f<}tkz6DtSpcd=Afmt%M99z3MMUwxrS^4$D)$_iMMx!Il%K3^s;G8;r~_>wxK zfV`u(*BMB!$=Urta4Z+vH87;c+_-|zvm21%Ppv~qc@P04djg}v0{!faZu5C;i|#qE zthE58=7vkR`v75le^o{nqyyt<*@TkR1O7N&wW1cx)siR}BX9e*`BFb)$~VQwQQ_yM7WQg2&6B~e1{($(}9 zGZln0a0YYWi+kN=@P=zX#=N-ZhRHG!gND7Z246Yl^$x9mXHRYj+$XbApPBi{C3pX3 zJZPfaV57z?7|wXBz~VTYksFfeJ77_Muxv4Ua$K#y^oGptpR!dTttl7(?akh&En1o| z>ms;n``YRM1Zn)!XFF?~B5l^c+Z{UT1XAh*5#o=nIUzd)$&lIZdZ%m#BYWHADn!8B zxPE2h*06QJL}>o&zQ)sgVIf!OuFtBYg!uIIBw}^j;z5%1d}+pnM4bu>t|`@hpj&Xc zNnUrwB5eCXn*j>_Z58fCB`di!<{*3eX(?ZE zI^QeEq0@;fr9;V89eu!r(}Z%m^G{jMlLn1?qjjd#)qFlpsEbUH8ou4RlLOH~VU%l(_9}m6aBqW|t!gP94?6G?ki6M} za9MxbL5A6C&=f8i-H5hZI;dxR!L=#;r&iC9NV-X!YgH@xy7dKg;Sgpn>Ari$CH2=o z=4IYDMj@>~X{$RgP$NBTLdvA?yzlkg8-(71-T^FQgeNn>IS_*U2QeeY2nkiAr} z^?3S?4BBar1?z?8FPG*n=vvS-=F|15t&+O^l9Ktdn)bFH4bWR1q46pphR*5$18#uBRoKAjPyq zZ1gN;Ey@{- z6ik>H2hs)T3=@m>eeaA*Q3{oy%M()@g|H0&i-_jqkL#q}nz`KF+`y8geG&MLkUo}m zO6%15WVkAarmuSeML(e)b#$D2lZO&#Tqote|F?|#2`2~>K5XSae(!Ck$l@xc!sT?Z znihsciEQ4Q!B0p?fj!!jHpY#ORj>OlGYu+R?XFQnnkB2j;|&Fbtvec9{B zXObe;SM9~=Rx);N#-U7I98xsHu|y12W|T>slOzRd(KJ8lGM)Yo6TyCI{v}mGcQQCw zVi`FG?3DSOlDUgz;|drWxBm&p8pRMON{*`&lF6BY4QVV)#wM0qy&USn$rCrSkmEw4 zxj&aXdv>UbemNpzLP%z~t;s8u!d5$Axo47Bb{iPIMzN<4T5&uf7{HC=LW>i8fXE!a z+gzHDoalG&qQKwCgU@V=W|1x8L(IwychDeJ*lR;jU&HOU}qDIoaxoE0iL@yv6&MEJ?`ZWihPpQeWFmq z6T>)xDcZ8aP4*Hc-ge~Y+EI_+Y^J_tt_d~QPk7KHusJFud+L@bym4i~S+UAZ6bqT@ ztn2EnPgLRaJ75YyhRUr2(y#K_s9;T@bqFR`i+$lRobo8<(PGWB9$td=d}|G(_<|?; zAD8e3l*l7?bG{O^Y1bHF(*y3G%eJ1+-F?NMc1TK(&)ku5(?LK%>2;%{w)055b##)c zvD!GHDo^0{BU0lt(2QjO!lGG2oQJ$|%L@1aNWwz!`Anm40vY{ z{DOpd&4ij|XieP6)->elVVQrP5=6GMgP*#iPS)5NMVh}NuUh}Tr(H%V?Ji674wkn% zJ9bI=;N9iQgLt9q& z!CunSQe0*fs@%r9hpQZRMBmaK<^5cOG24X6MMrz4g_T5Y1#7O7bldx~@*|s#5P7{| zjJ1XH_VMe`hZ;~dQr;C#eIxEQdijXsfUS1t(YdDuD&hr6KabbF^F-Q3Fc%#FW z^B8Eg?8nl5``6^LIV2*fQxoLyqxoxmOZWyDRvKuj@YLYey!OoQ||uMX6K_yn~ixP+rKw@aQ$@I0nD_#5(WdDQx|X!ZRe!YE;J zSn}ITE)zWpr&0t{VGC*atQ&G;M8wtgJ_g$eK>+5NDshJ)C_Wy_!;h_zcyX*F7B~vs zEPV?Ok={jb!;4O1Ma(TZ#olu1Wj~FS-|-qMeJ&GphPr*MCn*%E4f?Q zI__wmD%nIbWu;J$!F6YJWr{7sTt9EwWjNq`FOEuo5CgUO4#4J}G~7?@xNKs1sbY4L z!gQy*ky#1Qkag9TWPDP>9Tyc+`jNN-Y&IX52IM~HHa|N|-j^5X7Ft{Mj$6>HG`J5M zmt)WvY;Bc4C0ZNJFM`X7R4|{NUw~H<~0V5<~(f|8xV(Vc6iId z1LKE{a*zh?Lh`SPRW4U97w#q0(o+UsjSSPllAVMnrTmDad@$WZ%x4Lsc>YB1KvX*U}C4g2duU1aHjeJQJVaE|%>pH*rV zfnKs?3+U$IO9k34%@4urFyNp&rTdO?$<-(K4*rfI+Oi7&a;glnBru&=jfqMh@N^&y zLNqn_)yiAMHWwUE_W*3vr`-r)xN`fW6+=(aqZ^;>v~>ILh>Mb~D;F6AWB5^#RW&K}OY ziy(CzT6jrE=DUFc8jirMsOCW&@t+h#l?wzVP~##Qj=j&x-8oVF-&aDWSI!45ci^4; zI<_87P85GGtq!Z9^sJ0=PU)M@xh(v~0tb=E4%D58z{-Gs?-BsA9;!fg5uQvp)o-Z= zwyIjL)3$w6Qw*6D0CUj=tk1&FQ2eaVBEig?0!E`&&LX?ZNeXrkA>`zt(Z9!nccK>n zCvV6xt8VM&vbwo5*5a!fB<~`-9@ofvlX4s?1NSjUj&ga!gAq~U>3+=$+uv6Uxx6Vg zg(jhl@|VE7N*DYxU{kPH(bF>n|G4ff$Zk1kOj;cKn{H{4O^2Lb_T1J;+iYD=YgrH4 zYeW7e6^-RR#A4gEM?NG7P0E^vx|<5Gi`lb`JIbQmvfyw1eF}JBGXuoQW;9-Q=2> zC#r6MG(Um)fkv#~3%*FWkAv@UxPv)84E`f#{7P&0NiPtnVs7dQcdqfhYEwYd%Ls3^ zUb%9rz-Qz5f9U$g=*YTg+fK(F+qP|WY}lBwr$(CZQFM8s{6Zdy!+?X&l)wx zsoHhUUUSVo=Um|ON5y|SU0LdG0@mjhU0cs7!fQgOGuv%#^#{y56$hFpyI2d#2t;b= z7Mn#n5K>jQw~KB+O#RP{xSZgU>kYZY_}?GCJxXgm3%`N@Ac9Sy_n zn;t@{nWc2cv*T$=6&>7%C`x452$A9Xw_xR80l4!I3JNk{jJ37%15)300TG2JYB*{a zVM9X+ao57;XdRU~c05|HaUuL7l+mbn4z9QJg~>j*kb{e1{;5`Y^RGE=s0!q_T)*>; zu#U}^dYOkH&O6W`!+NRf8xSHS)J?4s_!4KE5DkPOe@E8^Yj_}OSS`*NxACiZAgcQYHWiJ$9JfCs_k;Kso#1ygQuCa-BtjR{R z+dzeqwaT>$0%^Qr412gj;4uZ|+BF#*Hz^J*6{oq{Y5BHJ*MEOY=du^U74`K)VRro( zJ`Bpv-=7ON3!6T zOXBoyWK`^xm~+Ms3i`~whAUwSELUxXAc3qhb5?r~9dn2Wx3I_=9gWy=q3q!**xvU3 zz4cW*n)wQv!lJyyp+deLAD#2m;B%TicZ;or%p*EWFW{LC?B1>7c>{p3zqo~_mHZEj zp~5GIqvN(U{UE?Z;+=c#Hs3P=5fB~F;--F78ZDJYNswBW5Zd9Pd9UimvDMAMX7m=N7RsK`JKi5I`iW0=pQ=(}uTw9b!>%Ot}mqNKif zq7jbgo>>iD%bT7Es`5#gkNp{7BHTz?t?Exc%sRtIG=tWQl0y5?;-fCy+~{QzU-S-d zbUrTLhdgNl`k}+Vn#JYD=Q$KUB{!dO;}VbS5iIUSHm2i?h%l$wc9ISCxu!y2lQ`y_ z*Is8O-;(s(b%>`=y;BAdY{p>AMAIa5Z+8U4o1d=;;S>rUN)HCj3&o8sU~F>B@ZG zj9)SzHu|vNGBx$d>7B#u-Yaqk6b`YhQ0+r>SlcJKJ|ob%@)C8l(#QrcM=Us>Jg~dV zIo{Z*-8!lR zek#l0J{*DWV$h^|!x@R zOKs8Gufv(GsVSN+Y@w-s*Qx=_Q|z1Q>=&pHk4N}EjK*ix{$jx# zUv2>Y6Cc2~1-_3Xw|CT{IX8Nocvi@xxh~Sr4nt5PG5Ix8B8owoyth$9NbEhuB{%El z+x%xqvsV1i)W*jOsX{T|@J7g#V%gN~+t^A0eYF0ysQsT#nhzL&BJqn#LGNnndX==QdELj#dnQ4^b*e0uo*lQQn;0!~y)$-TZUD9R6G_qWUE>}f-Z zJ3R7RfBdXA3Y_*kRMwMJNF-CI)Un?LVox-TzIQ;UhtB8i7hnQldNCS+!xa?}PA> z^iYh+3YHll44GzfII9Kkmdj>F8nX$yzpvLMnPLyhr!6phOR{j8ksH%OXH>~LcNo<5 z48cn)HCiSCO<>{)pO;JSgPAM1OGEOfjX#vZ5a&+mCT#xH22ph)F>RDr5V$u?w7f6WcXAEfwEmn``LO~V=Hy$n^9YJt%@4JEJ9ciXT3Z3trsE zoCAFjW?^m=SGq`R7?AzG={Wz@BDd$}#!Z>^^r11C|YC3mf| z`|XPb@IRR1682ndn_9qJvk-%uwD4hn83Am{KvV7!_H8I&oRLiVdl1c^}r5)54)CdmS5*@Kw$(mBqV9) z`^Ub$0D227{F1YfnFThafC7oI6h4H8o+A3nR}M)dkYyc5 z;p@EAA=b%yVtW4HCioMumkOg(Qth~pqNxQ3mc7`4@Sq>@_@<61jXOSdD=c}Fw=+N% zX`J`dE2E~*OWDy8VPh^*#XSC^uo7gVD|Tmi_$AL&Ozi_?$eLZqgo+{lwmmZhyH*vH zBh>rt1tVy?UN8=JT>ZL%TTeR6KT&K;YZI<0z7I_dBj|1Wrn?T{gy(<3{53wV_S-;; zQ1@?64gNd){_9QHbMgo1ta{Uos|tb6#d)Z?M|(~Man$7yIob;ACZ?_;YrPI|&=X@J-v`KidT8L<$UHL&m) z!9bRUWnM(9I6TrH(zt{Vn7a3OFZg5Q50R?-GwNeRN}zxTAQa2jnyYz!FSup%=!7gu zWM>H$uay=hq?BP#obQd}C--RzBw5_q3S{dI9E*K;C7>z7+$!7!S|#Bu%U#URY^hVE6B~9u6h2w zQEHP)*AoKr*xv9lq(u6(kJR1)hrwrJJo9CvI!(CB{OyXA?We&{mkM^!r!Yr^9}|JM zxv@*OtEAF=&Xjp+fi#tcJT$sz8#?)B;r@+3!m^^0uz`8}Z#CH&sJ!HT?0jl8X*ijH z+&UhA7L3}IRpVjOwzXO4oi{Mwl8^z`f$tmR(ib5j2X^{NJuXbK#DpM{v-*9}DTOpde-T)C_710$2gfaEs~BkBk-nf7c7+s+SdjOe z{4?_9o%BZqZ+3X{B4jn(jNor&#z%}W4`h|^SRIG1h)?@zFsbSydpX+DX;Z41H=xqN z!fa{*I>Lj!DsnfTLP;o_>b~eJ6vbO2akCap*Qbdzm@cXa$Nckf(!!LyI)7_*ug_nv z0;q^OSI>DmaHT`;&iX)_>gb`{LWLA*wH~$$g53yHPEiF(qp;PbG-@LCt^Hjw2#Fc- z{LRS$DInKEKxCOT=8?*}t%t7;grnz<{^}0@wIaWD6!7$!>{yB$=a~|*(?SHMR$MbA zAY%Q}Ztt}F28u)`sPee>%U8|)@VWg3p`LVEKtoxk-WR0K2l1BCvrqrTSu)$jiIX?b zqp!O1d;L9A^wTvwuL-R19`5N@{XY!z?gD^uXb6XiQ?gj_l4R zbQ|Vqt#`9pbPZ0&O8-pmqquA#NK9IZ^}67;e8y@qjpCh8XD z*1i3V>C=DE~S(V7F2t0K$~_iXn%cM_X`>WN9HdX@)2(v(RgM8|d-D zG+PuP9o&kD^@un<)+$JLe`g{OPpDznbpFA19eVaR=-GKE>h)5r)Icp`71^%H=!yZe z{by8$8!vs{@o&1UPNGt~V###YAp&k*!wS2UwNHr2nN{fJzB$Bq*z1{mV6ImjcJ_|~ z`axKQY^*(x`H#Vt`0E=9@*)eohug4#P;z%7zpBuYyQ1bSEg_ zvk*-7s^zLM_78;Sr(HVNwnKr9E`nBJvu<(H@3j?Mh7KcY%=b_MiTh|jMbftpPlpB? z3{&H~z=D3s7}V`jQXg#ul(ExdBoP6k?&pqyrul3`W%wG;;r4WNqqlsxc4bL(2gb2u z9Dd)=x#C^-z#IbI z0r)XU1i!zM3^QXh1da$Sdj#h&Qs=PMTh5Ma;!cv-zkS@$)=TY#pdjk4z(m2;TV5=~ z6_Qe$*3-g<_P3KLLz&X@lBr6hnd2u&Eu6NAgp7lSyml1mz_pL;2%Cg@}$!#;$Kkfwo zaVz{hdt{@xY}C3wZ~2Y5xX_sQI~Cw*T`r|nGj#(7&q_$DK^8HvVnh42vada&p>zZa zs*DYzcesiWJx|kf2W|?qv^mb6nzk(=;ET?$2vIeq8_h8Yg|+9hdp{%~l`Vm@n%-j_ z9-wGIY@N^d^Xl@d8j#xIWUbn`a5{9rF@b17{a<9ssS*<{82?Q7Y^`sq7vsKEIQ$zy zG$%Nm(3CF-R(dYuS?+gamaK0roFc_@+dNhd{XAi{eXIg1@?fol}tk2UKiin`J`{2(SMv$Q^=;O^i-5luEn10u(U903*e?KZDV0$hT z19a(7*W>{zrWg!)%x9x6QJSk}XpC-4%89$K`!dF}FAf=$+GH0OgFpJ{n$TjIb)ij| z5yiMzqGcGOoZR(k`UxVmbh725l1Y6LBc+abwfzsd{@72>!Eo5PH~~7_M8ZgqRedhlg=uW zDYxJt5my=RyKYV)&kv%>P{?mo-`dVo>C}H51($*rKu|aQ*n{WML9uFlUbAXKH9mYA zwLW;Gozdr+Pe!$cF!?pDp`9#32QwLXz1HA)uKci^uOz2=!Sx78j#UE0j{vM9!avkk z)W06_t2vor1a7)kq@yzuUM9}!j1uIg*qYmamcn2*d~M1P;}hL&@u33j#ecQ5KJc55 zqiV11AnGqI+Zu%Nq+7zkOlZd(RlOfxmE`SwNR-;ndyXc&R-R)G%IfdOP@aj{JqJ&a z)lwT^0fW|3ri?f-S#AgjK}C5DX9&xY%f47XFo-KA;^P?q%L~F7ury=H58o?$KGfLl za-5SD2Ijx`-8YE-aT;peVP1%T+>N;rE5O}rX=k$XhMh?W*lspr=Y%exKe=uGYS(~0 z4FiA09(UIW3twMWHG3NtOt*IM=F_;-yz{TGSPExAathU~lM>p_?WG=wZfWyi+|;;y z{S&bYNtZv59ex82b7wT0cpeY;cd|pAx!?+|$AYbw0?y}W``ItJJS-qb&ef40*j_mK z2Q2;@DJ6RO{zzZ;aQnlU&h3OXMX0;>26hv(#ik-jEi#cmWmrN~f5gGRg`{ z&TK{-%S7w54&sgMkotr8gM7vw5bopYiEx3vs?vI8@?T(Q4r9?v5xo~bJLj*jU`-_7 zVXP#*lN!hwbA*IPB4TcGOzh6kS2k0kyx`IEr@)=fvtr})h@&>cZZCUd`xl_h3K&8E zSH&KRlTcNLjTuHqg9NY8-0<)+G{Bf30Bp%o0IWyf@D$adXlJA(A3!>OI`v1@tFW9? z6Gf$B=DM6@Iwv2Kly+IbtKX*TKQqYpmP3L7JOZjQ&kIi`#GZ~fe4;UQaX|7SKi!-x zBvfAKkn5+BRkxU;!Ffgl#Wi)TDp_9@Ri1?hnqd3WL1zey%zI>T z&oize9l?w_k)dKu`8b$hhH0OD3cXNw1KQy~k#rS?Me-%IY4b?8}~w{_CipKz!~$mKl8=dgdNxy1mb zsyD)_CK;jItF?D0vojm(euV#;EHw4LRh4fGkh$`pnnfue^iEdfdp!Uw0XmIqE`Um! z1)C?&7szW4e;`D7&LafEX6^e28+xzHq^PgT!1OgwDDx_kH3joyh0yA9ftuG(;5(5p zG<3_iDgQS^e$5}S%+yJQ7cW2X&(H_K?*}$38P&`x15xxbwnsB70BNERGME{Mn4_F{ zd4manTOv->FhzJkQT+#!6Ha{^JKAR1M$WLuWW7T-5^?L>I;1Q<5^- zG<};yNQ0qQMo?-XQ#IWvLF+qoPKu+82+yY^rH*2}sJ@BaoMVzGy(jKuxdkZP_3rDs z6!vvdWk-KX!RZTcI&wH~Kj|k!bD+E;{2*qDVAtW185;t~-kleCSNeQw3kftrhtLjFg_?Cv@t1 znbl;Hd;6Z_+wI^CY&xPL`Ro`e2Y@oAa=_qn^4eD2!}m3QY4G4j7`hU3d_lA&Cu&w# zIL+F(%b<>`YBoeMPkK!wynksq#V7xtIPiZhA-n~EzyD{l_?H`g2N!*_3!;+(;=3ziJLvsX_Iz*7sr#tycFvDRg;Q zvlf2WQ0)uPmT{Uh8~L+>*}FZ=kAD1X9oh21=d;Xa;HJq|tO0nC93simsv{)+B*Xjl z@vrp=20+=+>-n=)9-{E`#{#2jVu)YP1)NIOW#w#fA*DCSb(d~r+GaJwchHF%mWzPF z>Mr{}D5CjsWkqQ>!M?4#`r>e;uw%!8g9ku6!YKBhO@cYzL_bN#jGirdE?8ivaKW89 zmk;!;K=r@Ya=8A234~68qp&U{#-tdXg^&&PoAVdQho$#lFu}vd+zFrYkl8(Hryx9& zRl5q&c0d!z-N#wwR`C@b^{zj;2z+LHnx;@dtLea+xxjS$j3^G+E4K6TZM*^}R`kl^ zs{@;O8yB@=P(6{Ag(d8@Aa0f0s+=7kN`79!^uQ9!9XoAk?$pa%-dopmfae|8?dRex znO^ZkZ6XU7`6YqMX-VAk$qxz3EHO~)m$4lKNholh#3R^(^FizTxk2 zw{CadZy~hSn(MMok%j1F{VK1H6jH#%#4;~-ERB6%fWz&wXwcHIpp z;}Lt_)2ovjw+S@Z#d=6~K$uYE!GXisbk6_`;|m=<-vYFy)8@~;Zt(mF8_)>B7%{As z?-7fa{RNO6(*{E%`Lv8fx&ZrKQ2~R<#d=s9uEU9UYB@(_@XI)sCy6@U4q~rglROY9 z*?iwdqJfao4OY01>7Ndmlsbk7SA6JJmcX|>e>HY*pk{qR$ywkX)_kJ5&gj?84XSPi zOJ(k)>43Ub*(A@uyCNVZgp$I~1B!;)`ZWAzs@ASWnkNQz>2iHgx1+qI5YMh(4+1q| zkf7p)JbYTQuaX*to=@fuVfq)o4^9}1DMG6rG-F<-Ub-}0YdJF!gtfn0mj;EM0oydr zVJ%`at+{r{kuI#sQNy5^&SmkHxo0XT+<7_R%x(!=*2Ze+219WsxK$(=iD}*Ij^#Xp zN6F%$bFZ02AE>@5*%wPXB<>wG%AJEjGsn9}^9fg`2x@DiFSL@!OrMFjh=*6z{^Mj@ zHMsatYV~59<~)7IPezs0MDG4a#%oenAMU=(yU%$Bs21`G)=-yZ(2wAXKYpQp!3KIR zfLGJ9i#w|G(28ls#>NI{Zt*gWg5U4{OCM)6-vE;Pd!M0=w~yw@x6ZpsrYSC_^Y_OL zw=A?Q0$}>2*+{oKIr~%R%7~MQua6AoQB#3A;nwtXTeP;%3H0iF2w=pNFmIPY0;`2P z_5|LXu`~tUW8*LQLU%*gPjn@?s~E0JxJl0GPHP4Q@QbaWLA zpEjv*zVo4c3H&kj0AmjQ$us@(<(&K3ns(({ zybp)7x$26>ox2~@s(d8bK2Eea4>_g}7ThiMscU_$2Klan0hG!lU6b3Z`skG@#?M&n zITbdAcMc8oxGksO=3dc^7Y1>jAF-)I3OtmY?e-@g9;mTqg1)zA#T>*5Z5^=0S5AXs zWtdr~vX@2lbLTqFq1v%lB)Q(WJ8CMw#z#EPHS52@Cf4KPq(L2}JD6UgOiDlSsK0Q6 zzgDFcSQhJII1S?CnHETXj@Aexmu%{`$pdPV7?HqqelRb|sEbMgt?Jxng>IGIxwPCC zSk`h2{MF#+w+{Bhv!r^4CrgbXt2|^TiE$`a6W3oUkpWnjx>U!jcWtlU!CT!LBhRE8 z)2&HSV-1!#RH)+;dAG&xT}o@H%f0dmm_!@r@gT6J6&k3e(?s5MB9p%qRQtLsflikP zF>cP3DAmW{1_y2UJf@eG-sM^qf=Qfj)SFUM5rrvC;?+r~2rcyqAK7KwUxT#T8XbpsC`tG}3MFbM@^SVj|v6CWL7O?!!P52_c)qY4p0^ zpm#I(vmz=ycM{IDF#tRd+bQHGGty(5-XvkENUrev`q%w67k7d~%^2z}2tagv^w2y@ zHL$Aqns{gw@1m_`+v>$d`&DdVew)=EJHOj<(_WJzhFhjb`^YD`G7y2d5WFMM@eFkRA8W(?HH7}<63n=(C;QdHZ7QG>q$e_>abRP(NVVpKwiw4Jv zPd70j)txsh%(Eq&H<6OdwLfm_o?lsmD)-12*$cP-RQm1W%5UxPgt(iAlY3dD48BSc z!IHF9h+kdk;$*Kw(p>cp*UFiQC@V7#U5(sNlFy7puI2adx&1>l&vp>}{|;1r@i&M- zq%o5_4R9~5sOrRr0-VKjH!0||x}vD8B;6Qr_ZQC@cqS=&^;Oz15946xJdjsY^vN15&di&; zhd9%n`Z`%1<}l^630jnW0}I7ppA@!lF<`AI%hFX3^B!r1z8>w5%%#wN|I+mi)Gb+6 z`XhI)1kqG_7)ldew>*Z{BsHV7`H&vnpH^JO=VoJSAJtl`wLZv-k^w33qLYo=Qg3Rbt}9PBhb*q~xq7C9Hgp;b z`gL1igo??0(*$`i7Jan+_B+tVn8WF|i1Q*=Y&w!!WmkX?xT*|ZdXVKt4|5u0hy%lE zLn5u!O-)yylX$SwBFw;0t5>9zS6%uZ5+r-kg$r}R3 zK&MM2GjoWE$7eesLnABl0og#?It!U#cQHvkszy|X!>0$ulUaS}MF+TBXEAM+@+{H= zQOk~O?={!>n-1*-jFUrb9bq1j=IeW!b*zQZnl+W0=_3|-BYe+xMqWwiJ0>YsL=YN*e!-cphp^)Wdx`ip~Qf z-2Ozi#nb+2%J#dQPB3hPj`CG-ouMc1eKifnAhPID{DfF7rsvxa!zO<=)+QJHCfq1C zq7k!Hm4Br)sNP(adsk5w4c^$3dF0-eUUU#fSPG7DOv@^DosFB9V={2kCU3n?guI`s z{9av(VAoDoF0gEQb=f zeZJFxUBbk^QfH*tT4zy$O9{I|CcUe8-ufCLT3aE8jzLN{*j>m9G~1$pTlTIM5>l^nrQ|VYUj>$y9o<)m0i*nWmtX7wIhl z-O5VZ)hfTBB4o;UX+`?HG#A<(e@LK}6}aG$b;NwKN3uP@AF= z0i~&Tn56B->}vEAXriIgrtyLIZHW1IAP+gY*9lK_=e-6f4&j;>@Z{r_F#n0Igt_b1Yw-U2lmswY={V>mJ~@S+9R@fylT zv-kJ5N|@0@4v$q89HW}0lp1G@(VsQql|~;L=u2BJYljqhk!vV$l*-$zxlxCA8eP~c zvCdqk>D0S%MKiJFMOZHgM-6Mee``j{Fxe}v#fOX_bH`Wck6wX{h9nz3ogls*_`x%^;kZ(5$g$=c+@47cB-X9+8763fL z>q8UJN60~f^LE^tdgQb)NOA8|u98t%^s8BC*C}@|;lABMaBp>bi5om*AUqZn=PcTz z)DfwPYUn^k*(`3jsxIiThUO7_{#Qw7WnR}Yz0H6T;0Ukp_T3$N%`@Ufu(W?AeYG4q zrAR8zFk{k=At8LiAx87|taU$05R()6anZhTvBo2wS}D|Oa#RPJNMI-`O4H}<6js29 zA>HGFV8wx6tdH(QBZFC!GZnFj42e)%H&2tz@Szqb*`#LgSCj<^AJ@=^83tWuSL|tl z)w6qSBWWw^tiZ0r^nNWUMwQe+rxBC*czpIqC}{dKyhz+_gj$mP{UD%teJ3ze&=>J> zir)wvDc|BF<;7p~U)Ht7#R1z!P)&^~bIMP%&v?eF%S>^+!z_D=wTiIFfGA6B$5Z5l zHIVT0jPyi#p>H(M`rI~aFr&amL!L^W17`6b(8k)}C+ccm+a`Wf-||2|Gn}*BAggAb zdByP(?Kfp?Wu$GCBq&fL>sz}IgThz4Iiqv;0!KYiZ1`hJ6iBk#3xfBQPw;`n*y+;y z5U7QlTCFKQIG`^M+)R@18L-G*5uN>$jqVJJq@2LeA!^@!e7?STD+3ksHe|}O$=UFv zutqqNc!=u8Z9!xgFn|!-j6l#CZ8O|Xe6cG3=o@rxDo?O|jh`WYN;`h|cL3TENsU>wKPq z8oZoxZ-32$T%i78PdE+kV2Cu2gT?6A+edC@F%Evxi@h zE6xy;86bCHzW46TPPaaYcZSy|-5Ag=8`Y-&B3z^1RH*e8y$ zE}~`sGh(Y*BA0gCqYfF*J41Fwuurk-t3znL_sXA1y<+asAhOp3_w(g#kL%{UwIXFf z=RdOM^A3VP?nk2uiYuyT)b|v|X{SRLYtrCvRafQV!akuXcXxC8MU4cjuQgF1M#toB zvrDpM0*K5aw?*L-9a#ZD6E~__hZs(D1Vb#}i<51zm$2-5`wa*swP(Z-J z5Ng_h!*s>i+;Aj~_A(%{9)nc6{F_ehn0v%da~1PqCm+joVc%x;@Tg2Y%i;$<=Y<#c zquG+4729=p**_Sx%-WOf+YEiQDS7RjZoMQT=%klx504+$BMInQrtc6BR7jtNF&{$V zzX)TqV^~|de!HZ+#WA(P@*0=!+MXmAN*~PFV~5*^4pR$^|K-l`BmVy8q$T9sm-~%h zTPz8ULkq?giQ0N*3_Qx+96Fh?{Q*dpP!rwfmc{6CsahNlX_O_Wt}}FkX48=3N$J^_ zw?{_Fa*2Ic2{uw%y|ayMpHqn>tAMeVvUJEXcsBrhumgf7CLea6`BZ55sa<%OHz&Dv z3H=!@5%xs(-T|?9T0?MefpF|D^2iD=o$TWVp~oeDZFAz1#!#su1);8+UB#66=mplF z%gUHP&Z|;?%@2I+mBCOg zYFQmw>0ok_7KBd|&D3zC4u9dcc8hDlUbUNQ!M@PtTGv8XK&s7(cx$PC5wlf|%}%jk z^nxl^qji%zPs8LGo{Lm`DAb?>(JHY9=p}TZ(8*rWx#_h6AR^x53W6aoKq`gt zV}thZJzw+8SC;SnFu9&E%{{nX30TWv>{qv==Lb&iCsfz){7rrb+IMaQ2S3sMwWLQ(+|E^ zo{{mhjJ0K++=fNUH)lGNP#bGnIGb`OuNaE3mCZ7eFz0fkpHnl))45QEpS%(Bvz!^r zUYuxl@6NhiaV{=b(~YjP@H2tV4=rk+fV5J0#?WXisUI|hbR2Q2!JuNJ7&&pyuf%mNVBe5=a3>;`;3Jl(H1T(GZJP0I`d4>g9FO z7#cJMd+&{4>4NI4Kx3RAjfcz@8f7(QP-Rf=*1iDodzI~SyHR2VMj0H&o|I#82KFlm zARJ2iZd9?$FU4E{9YQz244y`**QI{~2(M>x3}XYjt8nKyE&jBGBAQIfMHQ?;#h8EBL^ z8p?(vWLH8>x{c_tZ+)uckFHx=<=vlFSuoPM$AYJc8UtHO2NT9gd}erD#>9NjYFc4w zVvTW-&fBR0bZ@W=;udYcb0FgVP}bGg_<5%IHMYn}0Z6G4n?ROknKm&6}PF>t}2Uf<`$ zhs;&-n0&-gG}8DIP6KBc>VMEFVf9}#_;^kY3s1FaS@WTX9fKn)8TCKyYQVyr2UaMt zNls(LciHl>GY_taQ3f+gwaSKAhc(^U{&^i_n#W$W(HZHR%%d0K-)@5v>hh9FvhJXW zRu|FHrZVbLT|q$Zk1Pm_r!i$I?jKhPAc8WmT2!wOb6}7=$5v~tPmrK~nL7jC8!d1} z=P*i70;X)R_imwW5o0{5O(W=!>64J$) z5ceSXIg*wrygRTnSY(3zDni!$z`bcSq zR%$FZB@mT!KaMu|MCXcQW-cK)>63dZ{r+^sf^aX)abnS3K71I8Q_E34$p)&yu#^&| zN9!)IeIheO&QjY#Y>Ut>>h#XtNJhL|(_uj-Dx{0<$TthS$YVAs+_;4~vFo%mj817^`})q6a(I{T5D~ocVF&lTCcw0h4v#{E@MnJ@YyRD$3=bt_cLh)Rnl(X z8BIKGVfjspDeI(=k897YKGN~8)M<%k5jx+dNS+KF!Gu(=chIN3TxP%PJvaxpD8Oi`M7aN#b%Y7Ts)UwE|uMfj;x~2G{%pvnV(h%qutWi$1 z84HK9C9J^s*Hp<>6_T?n5&0UKTW{`%$J_+X5q2!q+SX!)H13b*f^>!attECHK#x&; zg`0{Rn;z=Tze5Ebm zdDS!G8?K<4@AAiBd*2FW6XnSbIdDb%?7G0lVn`7#y}HF|?oYv9GBe(Ii3@B1H0XJ{ zjY4KBpsG@a^fypuwL4QVuj&awp(Yc3M2;x<~kR^M{3|KKq~iANyg7cfH#bBZj|pm|5~KEI2( za=zm)nZcUcon+~Zk$h(_bYh&QrOnKGik;jKkp7%)=gBHRu`IX1q?%;AaA_V_l`E5dfKbP)zVzzpNz7p{j~^4W~S+ma7$;Hh8%8`#@bl5 zRgp;GYskF@qs*L(C*z(cLedZJQ^kz2tgbua;6tk#R-Z2faDBVfq*i6InFm(G_*M>H z?;zOq+_Vj~bP|yxab`2_&|??CfJDHJOFq7pJ1X%g)z~{s^~6M6rW3^$daJN`P+&=c zD39$^bQXQ%o5jd;Jlx6a`Cv~|71_@vO{GpI1Pzdv zN}=mbCVQt=LrjtdKAi8FcR(vge1*1ZD)Bf)X|MA`CaXqLb<1{*qFA;0JOA(2QI&C7 z9FAJ4^u{)lt6?;bT@!0%D8KB8;S}Z6vy2azNMq4mOz3Kte1qXXKS9?`Ts0(hEKe?f z2jVO*SzN$b3lEp%ioeQfn7qC;WVziz$TIJGYR8!qm?$onvC9h;QI){PsBOD8376E;nHu+PGDLbc80|nv?Mi2RLXYjA{QSJJ z8jqgi+LcKmxs778E-9Od-Cjg8H+QL(fg>sljU}MPR&y`^n~wd zHm&^H-$eAw&tz-5XQo4GtQTc>D#U5$HFkQ&{wQ*w(iY~uU`n<2utI2i`PoHt@Lnkk z3MXyVGhryiN(Vqo^qK57Qc|cFlH`o&^v|+nE+qWE(Os}%jqKMU<-Md)8tWgT8gXM8 zo_L$NIa0>G{d1xnc)h*r&ZtycPU*3wwZT*Cyf0V5+q{6CtznIQQK^9%8)@hYI>A}y z0V^3DXQ+@1+N6a$bC;2^3KJ&4jmINnm^MH8w=M9b`x0Zg;~A!gvcFL4FdF=iIExCvqS?+{Y1JR+>_MKeZq|y9cY=*Bc7(61C9ixo znC@BghNba0))YXz2d5}qdo)BFXbu?~az#T)lQGnt;){>pM`-%&Dv)t%Zwd}l!(3lh z`VCTND!G;N@#?@U5PyMgLkjgPpOJ(%L^3=8JBJ z#aN>jdD~vX3TV{t&g7j)Pr+CoTW(45$*nt{278o_n=&`gDj6E&d37%F1ZQNh&^4re zPbV;hzb&MvU$fALT|Hcw&C&Tlmkj-OYEriwNlJ8nDsYgaeZ)43pX>owcK=9*xD*nc zS>7Z0I+v}kBtg{(e1ZDgyT8F3kP7$KY_JC|T@oaFxfM19*4+_WbI2I&@uLNH1m`~N zaUOGA99Rv^{-MhEFnD(Vgm5G^8WthURg8RpMR_s^)bhghodnnByzq63K>p+NDG<gWuup!7AI8cHZ#oxVm)N2#)aJmn{E3*auQL>*t zveN^}d3#WQpcO$;FWgHN1LIyWY=jGs?q7kN%jaQ=smOykM=6jnH81TG9T_xs5f>Zq z%&E4XHEg!JV*wkmm>jONJf5}j_G{2rT0Io_In8aNN>5fA!#4@wxL&)qlXg#=g@7-@ zY~OFNj6$E{Q_n{h>{9avbFZX`J)e2~j!vg3l6Yvgo+Xa9Rbn$!(jPDxzci4A4gHB; ztS*B+9y7|Vq8B?E|Lz_6fOAxe99Lg0lM2`a6EiH$Vh%cKU*VNwEhi3l`5*7S2l17= z!eMb6BaC@JE;POMGOa{m6MbZ6UQ%4MHvFF|-tt@5hHOwue>)keT=%QCbmd1SG9D-- zVZ?c|8(n!YY6Xfah|h9Ck&YFYl$Vxm`&UKILvv*28HHc`>JA{3PsdFh-z$rM_e>uy z+&7(Ex8SO!HxG#PJ6=lt zJT`hJoIh{>PMhwwL5`1ElMFItU(WMWigfPTFuLOnXpwYF>fgo+E-;?|ryQTQRklWR zDOxHE*WU7Xl%qfGpUCw%?;+9YqS7G8Z^rDVHM>boG34Mhd@UMrYcmDKnIuG0euDUi z+*k(v1Sa@_5q7-r9%}( z4A6L$eKXFdwF-%x+@3^zv`MWKI6(~u+hk_MA@~~tMC|f~-_WKmb{6rtPS_l{XC$$< z*F4a?8V~kQt^(t^*;33>8T4J)N0Xhy22+>}?umR++w!Qp`r$OC0G%IKsY)9sS(6vv*stcpVSMqx|qT=9yvoTZ8z} z2}~4rW~-}(NJKoHqv-C!q+KvDa5e4ISxOJ)mpx@BndQ5VZ_^raj>(hxe$p8HAHv=; ztj(@V1ASYHLvgp_?(PLzC|=y5xVwAt;x55mi@O&M65QS0CAgf>cV@nsbAFt^1adtI zd#`=Vy4MyuR>i?eJBOa(_^HxqHqD>>sSY>=eFzkTecn21JzYaXj4Hfw*d^J>CSwbs%|f#JXPCM|ow@-Lo(KTkJiGl~ix% zT4&%}H^iGlILRprdg_evG!SStt+_ByI%ez{cy#6AAd5gShwr}(;9(sATwV!IVTPC( z1igQ{5XV^q-frpfN4b9u+MHoIsf+IsBjTOygu}virv%t3{Z%-#f>7CC;kF|>&c0@Q zrp&rgEq=c{U^{h3Qj*H|W@aD4XMHmG;y>rqb8u;nz&zRX%)CdOtES;7^-JE9n)S9H zN~%{^k`tS_=-NoWB0}1m%Ifd4`h0*qtC4}wC`C`{0Vap)jWLaBOB7YB1eFDUqhafw z%hL+fJ$U}R!FQIYc~ltHtZ<#piP;Ih1VSo9Q$6Tgwtb+`2v5!!&k5qB*=g+DRE>j(pusAL{=I!7T+D(NqZ-&Mul}qv%(>OcVwZs-?A37NRVsy>3^L>-1p%cl- zQWgxFNV45_8p>$c)8nFuXeGlC{VU`OW09Kpu(^ZE-Hvbn`8toGq6^GNWh27r7S~n` z0=-fwA$&L?z2AzVJy*JE=pCSW3IE7VJ)~kmd3aQ8UgDMKjoFojbzK+btJOEIuGG7K zXdxcY%Al1v%$;YZtIL=(tKD3wnPhi30&bON0WAc#?onILkIVNsR%wZ2aa=O%w)HM9 z(t(ko-xl88$H0{PK};scFspD!B?)FOyHp!WIW=aH1`RxxF~tDO4A%l13K>{6Q*T}A z+}%+qZ~|Nnh;@12An<~pcS9t$iHJ4-oDLfKipsX|Y?8*oh$DBk5N?+1yAax8_pbO< zinBYCl*mlI0_W&s@MiT9(ooI_H&;SYn>6XQ)liM;Egi^+#i}0mE5bbc%Ots`hK2hn zrcba3J-QrG_Me3=mFv+rQGC6Kv=<}~{B`yGG&5M5ryQ=>hkco&?*Gj>&JNB6MRqkX zG@YPBlKfrPc_<1d_sJieLQ3tDy!E(N6K}&J+$T}=(L{btIckna8rXIx~~)tP^wv{OsDIa{!h#z4@^i9Nyb{f0BWGN7075rG|%z9exJZ zAur!O|8Cm1Gx&e)Udvy-&fCy7pkj2jnrbn$A?BvfHsLa_#TYBSCA_VtHqpbv>hu3} znjF!_t`L$lvj3pR<8$M5+;x5yc2D8zI6eZEXj+z7pBtXE;EY5AGbBpu{y&&Nm9M$6?W`0NLbYwM)nhDZ(CgrlsgJ*wRdntwau98?HgT&wK2la8yq!5TkYJD zL<^DJ!(`#Mb~lsvEAJD@=D3RnPkw=k#?9F?B_18u=Xv61`IxmZffh?6XSei+?>o4q zFE-}x69hT5Rh*jS-_bF8|FTbQgZMMTslJnfaxn}D!JL)7u|*EpghJ9YzxkH6`QtuL zp-fm0q6MptBpQXo8(-C4v=d5U8g|SX9;Q*$w`7-6CiO{8*tVni$iL<ot!8P-lxKz)^B6HAdL+pyzJ7k~MiRJ&-ff=r z$UspVq9$T8HnjjPMObh3%8bu^#VqB;E(?QdYH?-5!MVxqt6Z`(;{#yOKVV$B!7|M} zT=HtUpX#mTgxNejq`*>Y$rh56v#U`VM(yFMq;-b|Su6BI)%0r~?&7`tT|A_!B zlj9UR;#KlkW9!D|-nh@XHL_5OR%^YsUlK}3jO_n`>y;THn50mZf#KB#O5|&2{mq4x zd_a_6*s(31*#E_t=G%c-TFl^@<7f#2UI_8`aDbYxUB#}GxgLg_@%K!GMqld7ZU>ud zt+2kISUgVjp$=|3?zYTE`oQLTP_jY$Nwc;Ct_c@690H>xpoiU^HJ_K68D_)l7#B~t zT;70v(UE+PZ=|lWHqedaAc4o3H8PilS4BLWQYfLk{xUh{`BZDc@S6B*s#frOuEWk?hnTik>iA?xbU$ghCP&798 zc7_)-FZ#1lW#c|E6}b*A_ZG~cvz@>TVU)_Kjs3j{nEHx}hG!I5Gl>kYzlL913dM;1 zK2m|FJC-T}^0r`dADj@PN>Dc+S^D|MDEb2{Nt4|f?V0NAmZ-AUkYp;|;i$D-r$>?I zNn-_TJ#0&Zwf_evFV?NNDn zJjcR4^?H^1rkv_{VG0hqlXW;_SN2T=tS3xcDqA>GYb~;%5{0%ar5N+Q?+BSKBEgkw zFnkLocDHbiYQWL%%p!8E(X`%MRT?4t$9zO%n>8vc4abgwEzbr2SsRMHVMS-E?r_m1 z`LZRj6XgUEmy%6|P;$5{@MKp?HZ875?a@O)_3~&cVll9fu>Z?k;N~-eXlEUGh=%pB zO1Iw0>i1|T!BiHynl13zd;T=}MU}(D1VQn5-#x(>5eJqi|M=;P_1DoIk!TvvXRfd# zrHe--4cTFR<^zYvd0jj#7-QZRdyKl{bQ3-3_g&Fqkd^XNUzTbi%UF5IJ_Uuhd*JxC zy1_-M+@gK-h#7a5-1EJCY^RE^$^5OsHsMJ<7V8C?y^#Z>gG5r$)-(GCYd+o_VPQ?X z=LcTvt77ZhrAM5nX`_`894lRp*q1HWEfTlzLyfDN!wWHo{evqFMJ?dN62|fo`Uv6? z8ag`NN|CNolNTT%^04$7WM$kpfeO9D7T{BT=f*omB3KY}i07ZLohc;M(*8umTL8Ix zn-CFjE_o@oG~f)dr;YTAt_Uh=>*74EjsVe+XZ7UGJWlxM6o^vNbf$jvMe_@iIq{vo z(#lT#DjFOWi^jK6-FW`{FlHjSnISY`R6kH=#WLSgEv8D1b$h=)QXbggaFsmBlX=_A zQf~?|RdE-Kty8aG=!`G}?;qlFfcT)!Ql7lri={S?U~>iVTx9iT0aqT)Z-ioNY!Hxo zP(GgI`~xE}EbYUwW>218^7q5hdI~Z@i`UP(ruhEWU+FRR7sWCAvj?p6qz0uTNG)qT za*vn!Awrc=(srCvjd)r@?T>z zC(-!3kq;S3Vjk;!&drDYFSJzjvw&+eVIzWa0kun78p65v8obZajss0Hij+1Vp5mgl zz+(=!E4qu%i`*p>#nQ)MkI}*xE%jS7jkuW#DBuQ{5q+7(O2Hj2IK@?G>FHSbGM%pe z@`qVW^nL;I`AK`Y(2~RD^=$%5BKp^JycTG=jg!J7r^WjyXIaOe=3*Z!wGks*Emx?{ z4q2CRYf?pZ5Yf(?KQupZ?smsq{rc|p;| z;ITlP*;v$~1UORP-L zmpkT+5cAp_qiQ`&>i3bC`xyABQ6>08!D#^iQ91W8`NvBnb*e2+?H8tO$&>cw7Z&UyKoE>CHcu)ppsc||2~ z*sBxib#n@dR z*)i2e1z;~mUU|eLh0c~*sMn!`l}s$q-f7`}Jwh;ZY4Jy8#$hYqhjS2erAl~P{FoiB zOPbcZLm*FI9XuW-jEb3hZ*XvQhfvsLkFVZS9-~GBwzfvLO#OE69RAn-n&NM5q5qP+ z&m%Wxbz40xZfPcoO#%u4y1th8deUI^WKZl^r@2LL@>-j(q4P>Mr4PREKbG#Wff5l- zol*Pa^1`HF>9v?8cE{6@R8^Z+l|3^p%OBh{P8A=`$IYr1SFgn`_$RBoDRVL>nPsa< zFEr-TOqGX`=t!YlsBNe(W==HyLC&TG0E9xwav+3>$&1St;o=XvYeI5_tXX?l32&F$39eC>0P~LD{(r^ zsBk_^Z_P}vEQd_D_pLg2K!XVr`o+iJFS>cPEfj##s` z;HwSwU%XA$3+nX$c6@@MKWkMWo(>q-qNkY|3czdhuKzgl!f*C{JjxSu>muL|jU_C4 z&yH~|k&ph&oG7*Y3vVjzMqZ&W`&nZHdH#aVx1b<|EQZQ(+<3s9~wO-H8 z_Sriw){gM`%p8((2QT?Q5Z^KeA3`kYS^nH!c&m)J1v23AlAMKf40a^k*ZOx9^mf2T ztB72oJGktkGCc}NxtKM?`R2ylXKr!l{if_;ekej!mJ?sTlj1 zYd0r)7n0Q7VufGG`bv!6$sTVp-j=(qT^*ji0~LDML_h%K@Tz~36}fsL5hzv0YOQAS zs^ANWn9LckKO3`EJuwG6^sMd1e?GSrhnzp3K}3ggUL!+t&2C1AG6jSV+Vr=EbKc(2Y88H zj_vET<2t&;(3U<+cH1#2lX`Pd&DC7}YVQt0P?Dl7`VA<8-a>NN+tuCP4F&9ZV{$gl zI^S?Oa@t{h;CY8-!kuIvJe0DUF{qHd^R$^OQ4Mm}a6VyB!?w;DTi%d7<~QXqE?P5H zRUR6$RePe)$BNWAeNWhW`gIyikl=ikcb!k8I&*1qcQs0QV4B=3u8$~jv%D%fVnF1E z|ETB?MkDlN#tenKMaRH4cI_Zj{=qRqK&*O$eCr4|HIKeTArEvoUnAf8A|7h!s{CH% z{=FS2aZtcRHJOlf7@n#27ekR2x`HRi?Fw@oy8(vFBeUab36gOe)7FV9)E+(1eX5=# z_>>=xa0c!ugFEKr1o)^;UJa2!6kGf>p9&}09jD4kp&OZZG=NDwnaW{ic>VX6`fTQy z+`hMoy%A8!8N+e5OFnFOYhAq~nbJg!3RcSRY%1e6xEgiQ(}b{e2HWjXWhBqa4>2sac@I1NhF)9@>^cB ziClf*#MIG_+2gZzpD|^FE)}94j)-pqw7?9H*1Iispase6_B1-6F>tMYvT#sgz{!xX z|AAVG^kCp*mvAkSe`-HHmVpS6#CAe|inC*Or*TnK^ZR_Bhh{(}m~GfIoZ+pWQNU~n z)AGr;IyE~PSfY5*O-)El1z)%^q5{)>{oh+ zS8upJs;G4w;3qbDfv@)b^kJ50Y;;I;2DTqMWz7eZK0^~RhL5i5VjtucHeOM+ z((XtP*d9l}Rs3L;At@JjsPdZ%00*W7@+!(m$ zm-7E6-qFw>D80Adce2@p1q#@CdJ$+Ql3gX+aa-_xe~pjIFG`1H(02DUn4HEr)8i|u zf>8~$%lU?eDc)?~>Y=V9U-@AH!6XS?<$F4TL#*ai; z-~=UH%xGSLA6nE2CF_h2lX+kE1;Y%R@9{wX-d4l9(-*-6UB31l_!JFt&6cZuf@bYl6Xwj{5F;~l9fZOCQP>sk=EMDP!ercO?wa^ti$^@b{PuL>DKLa|78-yR-W z!I^kOqi&v3!!(3im3^L$7$D1$o&LCB{QB!}3-Y=C?idzdm=Md+R098dvQ&(Wvl^g zS4Y5dpJ=9?HXBQ!$!S@;m&^I{`)a3l%qeQ^B|;X~wXSQkqWj&uV4>idTKdHvW|ztx6}% zNW5_0ys~!y3)iZ+*&TI~Q}Jk}XN8jIG1CmRmyy*6F6a#0r83+hSoEI8@;<6)B4dwl zodc0pl)?7_dn0Gw4TlAK7VvXN;> zx-kXW{OBpe4AhNTm{g3u5N3>?RHscaPrjckoirB^j=Bj8U~XD*k)DEVX;b>Hu0-+=J(RZG8IWz_!efn+6VYRPtR=Cm-iO*1 zaI9&$t?m<%mN=ZJSO1Q0bSAEv+%)QxM?8Pf5>njD-;gki%f>nM$Y-lQez~oRYsqhE z&9M3MUPATR?nA2|D!DJNu*xHmfAT4zv#kYz{7-<)=9oLh4k z%z)j4ZAt+FZNulEU?5)1C%v{Y&CFZL?>}aKCRgH{S;ZFx^V>qLDA}#XT*(Vl4OqgA zD7`4_dEeyhQiVq8#mXVVAJ@esu(%us>wWvZ0&{C9?K~q&l@!k{aV`L3Rku2ByscFe zerL`gYbS*63zB`LL{2S2GEqNVJaI!@7*cq6$Y^R)7*S}F%xVJfP%CY$Zhv{4DcG<6 z(6u`R&IgU$k*<|M7GITa6~+;!)gji=H^356{Ji9VLbSWKju1^BU+Vrw)xDX2+wR3s z^KPnz#`hAD(hSvt#7gAkl~Sv;7Vib0mCp?yu#e@-0`?E4)AKw&&`8RJWeH{F;;=GD z*>7Es+n#Gd+9ePnaQ4MfTazm+BieBD(qoj!$1NR@0&K;tKQ{34lan*?$UiYDjITxD z5(dTls-*)KhqGQ*n7nXWX6wK4HMT=oiUJ%f`Q4a8;jNP*z~z!T&vGshz@GNB-Tt@r zI`n@Fx_^K2>DwISFCZ=gBom6;C6ixr?U9CVh8BujG6i;lL{13b?v5o8AUHem1c2!lv7reF>G9k*VU~q1-e8vsz zVLZ7C_0?Ybg>!QIU7)!W;a-Uj6uG%v^oi$%1#=Gx%2EzMLz-5cWc)udSF z4=`9iVpYet=g0ts7li8hz^x?fvlA1VT4c#Z)1%*Nc7Au=mmO&|o?B#sNU{ z=Ul%uDm2tj^RP`Nt*9W+)FRfQS~S1*OkS|E6X+&8)3O&R$nIL$WWQ|92$FG8r5W-9*`11C^?`mZM~9^ zU%sDQm|YU_(V1O34v8(_fZc5POVUeod^e24^$M_HFnX{ytCsQ4JG%0M?xzstsY|nx z*?seY2$|3p0f`|>EOt2+dZqTW@5?~B9IMnDy0?XTCIa~gza(`}J%vN~pwE2_i@y$- zNvNqUbY5W*dA%3PK87FE_C|XLe6&=R6B|S7?`v`ee+v6q9+8MSmH+GTV~)D6XM%T zTo1Dx8g(#Mo!3#V` z@OtPCw{n^9147;FBI&HD&=OZ7Yhg8|8ZUF^Wsd#DuF@3mnHe(1l@A#5oN)|nh0*o& zV__*@^Sa$6g>S7Q7ok&wqztXYlIyu z#rmYDEPL(5XkbZe=VC`ma~z;bK-^fN1fpZtLulxKbfYGVzUlux!8gMf53q*!oFF|A zZ@H(fVke=(5QUFF&PF&toG zdBc+NwMq%-K|(ljx)TK&8aw>V&^*dtJdua37Vvy8 zpI>L_|GPx}o1clPfUuy9Y(lQ5{1sv;O1DOr{q-3TV2*RaI`f23KB=&?FY@O86$ns3 zF9~ChXE9st|M-=rbNziYBinNo;`wchMsdRn>ui!q@kfO_)3Lk&Qwm57Z|{$TQ1TvvclR_cvIuUK!(n`9}9@ zbu3TIQ-%pTVVAQMQx)R{-La@b@$h75l41cu6Hf+KGG*l=zpZ}^)XmzsrMr#H>)hfh z2yMB#p~)>->@<^P2CeKx{UARGKIwEZTIRAfIc@(8#h*u^B}0>z6?wMvJs0FEk8&$iVnn7nTlWd&1e*% zZmY>Yel##zCMNN9PiYMAo>i!ox~|ul*7c2)ZJzcPWWC)*o$zE7>O5qbuO~#dF%y4L zxwpSSqnbSh}-{O9PLJVGs^SJ>Lj1Mk84MR^^$@XeZ6cdV}a zUH3n`!uJv8Xwrpl_rOIf(Yw}}rnP8Jdvl7};nR&YVT4*TS_y@hFp&cH4`-q4>e`_Z z;qo6RUDQPAtQlx`(lF48{f)OG4`)33;8EHOCfI8mBoGDGVD(cWv-IACFHbasT|NKm z93(L!a-(4JFEl_ig2Ea<27=5y5Z+QV8BQ3(#x+Y3g~~R(e+><$q-vg;gTM|GNw#GX zYu$=Rnj(r*Hs-HpbquwlF4|O3RPWSp5|CxCeaC05cTYDBd4-DKaFdwoIIWS za9_%>o;9Jj#F#N@H zsvL_eV_&I`Yjv3t>Tra4mH;cMi#zi9(;XfVRJebYimcmmP0W|TNWUs+i4lsY1KlT> zTeo;Gb$x>T!Kg&MlB=MZBsbe55B|FBY&2&_a9+q4Ho&wwudSDC%z7gri+!O+)1tn% z$S|pihrI9N6J+1?dfqE3IvwQi|xhWXmM^_Q67Q>bn1 zd&l@=_+ZoFD&P8KwKLdwYR`tVc|^L{9Y-T%wDyN@xxkqADW9$qN4-?+R2hoRXj#aL z^TFPHapAX!C*1rpBFFl?cU>-UD_JLBpKV#?4Wm6T{V=tKl3D^foC0~jVXh} zd(7PFXJ(?=t5l2<6ynjfice53C-xbOm^6deux4Pfn8!i5^~Q#+mUiSKJg6R9sUevfAPXKkdL=! z9%O(D(vGExlI_mKgXYp0wtKkr3TvIF`b5DZ2_oPRuK`)!h5}a_Sbh8GGi9Q3H@E+J z*|!pp3}W+2ZmltT#W-AqQS$MispP894>KlJT@xH#I8i&`$c7KN)F`ETda7v^+&i?% zZpoj$G#VN?zH+s@XqE9Z;7jFFo0h-e`3vs(A-Dwb+TNi=E>!b=(8Yq~l3E(hs{sY* z|M)!$Tk+!~hb&Y-m)AfDR}RL2n5uIOT=<~WNJ??G0e?Z@lOAf3LXs-Xq!bkl51N?5D@ z8lf!4R+B_EXgKB5M!!T-y+yT6ZA`j}7&3*q0d605_mj&>+O*km@BLjm`4J0Sx5MK< z%4B;6A(iKMCr#TS7_6r(JRNStK6QYHAOW-R zgyOMS-DZph%)g=24p@lAM}*+yz^mZ1>m3DdRKe+6Hq3h_^B3MLD5?jP(#Q|j-_-?5 zpUMeTdL&0s^#{`Pe>O;97xT?%`HVeB9@|@ptqAF-+K6Z@s*C8Z25Yu)b9c4PYTGcF z7b{3dGt+Xj(xq_ch;P??5AK-?(Hi>4%i2KgkjyieSk!y%=$*S(k(Cs^M}t6zr;gNi zA5geMZGR;kXS=E)s`3`RPJ_wAgJY7l###!La{?RNO7IbNj#2gCf@(_lfcTE$g4gW| zCImMh1c1F?+#A-PkM0(lj6E)t1SlG4|H9)pL;05ir_au1Nt`NeK}h5sY#ic>m#^(-w{7PEm zpPz;D@5Yk5zN5NzOfpi!x4N;PQj~r>?Mp~|W%xd8{o!itkiIx;<)|2~gK`BV{Yd+Z z@T~mb11N9TI;N`l&+|>Pn|rxB@c__E(R!0KLkc;}+-;8*3C86-{vjRYo0lpk%j4?* zT6GuhTTim*-fI+0wi~lqt|HG{mqWLT3AkLVpTYBNS2z4LSM~lH1l>JLF)_CbEf&zTYzHeD5z=x8__y%3F4Uk+iap!DR^V2$367>K9=JB7$IU

;TiUGXV-wbL;;$Az^t^Qt8>;1Sf6w?IbF*v+o*E z;1UqjZhuX&*geKhf~M7`g$l2vy}P@l`oE}Cc-`%=sCO#g5?|qQ?^=Lsde*(>zTHCGPUuYUY`hVVnZ`3 zDo6AJ7AVvLGtglY2n`ej)RgezyVs&RehRc0Jt!UqRi((;eSU{;Iw%5X|>o!US(k3&ETKBi|$iYoNZ+ zHXM2F8YImn7|{skt30cv9S+{3aqM@g7ziSh<`D$ZDg@zf-%lF{r6W4%7Qh;%&?d&} z5@!l{P*I|X0w76ICOs-4=C{7}AQefVD3zCDkkf<;@)#EzD;Y!cpH4pBtv-!;3RsBGy=a`4FG;uRJ)*bQz3XUqoiNps%Y3P5cfV)QyPYV=VeA$x1B^L^LQa{o}P!3ZfC2+t)IhI-a>P~>W?r%o>B$l zUlhXwIZI*L67mYe*;oT9tG~M16q{y@avvUz8xXZIF;2}}O^3GP-yg4_RNYvLQ*#Si z>?NTy-7!TlvKRLTeWbNV`%yc`#X^aMY59N;C8|k!TWk&@l9jiH80shO(cV@t| zX4T)lhcTO<-+lcgGWzppQLA!EcF2XuPQ?d{hLg0I1-8XO)kH7;&oZQMW$@swe7sc* z$g~FtcFPC2EIlh#z9FyoU9WhgCNEfD3~bflYE9@lH$j1`nj$5t#Gs~=GG{XvP4(|H zaX!?~oVqQM?kwR!9%8sww-AJ_t-0rV2uCJjgcUOGox5``l)jy{gQg+=^hb%e zzf+8GLH9DvC^CIa|Fc)ObuM$VFYQaRAU1>_z`Q*w?)u|h2c4O&XwtuG--%f5)VIz1 zv)is znpHvJJ4uK-n9FFlkq}m|;Y8`PYkfWZO_Yj~-lGHoaNO*9@dCcYJjxeFf=5IlQyYuN zFR18Tk#uLzXp4&p9V;XjV8dv)olT^G43>eWLwyoM^$kDpOW~i+xJymUaJU$l21xO4 zH>sWiD2aR-J_g zf>x*O=Gi`Uo}2)3aigYIZwO1BGl{Il2DEIkOtHDMou;hY+64t?o{8-^Hp|lZK2A(8 z#nMp8OhXg93Wx_x%6->lG~$~#(LWzNil9+THMG@>FBm|5Fjbc*cV1Grn~H=?A)KK0 z5LzlF)&~Js8A^BMM-R)Ic*@`sO$ObnODI(s5UU?f?MH1orHbAiN-`)N0u(+F=KlwV zQYphxPuenaRqV}=pW|a`l^jtX1MUj~p*gwMjE?u?K~@rRTlMXyUy;)~=0ON|b>3bz#&tz#}wnb(lxYSmtbW zyLi~a$3B!oLIuU9+`Mlix%ohG^=BIt^M#X$%AqFqUiPc(%<-=34%fP~H+?ek&ykW~ z!Xe=hwzFNwi4)ggexJ2DmF`S{3!rvGsF81~fZW66MOAk#J;h=S)Rdc4x9pmX6LR~# z)6`Z)qqSN`{a&-;fdHcZ_zJ&O0VgZB=311p+G}IbXPj+jRgCLP9u+!bwTdsisP~>( zKfDTjUgZdpA7xA*8wgKt(xW<&r4&ss#l=P$YVt-7yBOjw9jS?pqUKSn(^2QU{4(~N|g!FWN%RQPD zPBCao*!vHX2{Mxum5v0LiuNDEdohz!Z7E$xy!(%|TdQ^X!Ahu5K+vulN;C&iR$iW` z-E;Im2=vrg+%)nd3kA(p`s9}Q9h*;ycBPaHqFw%tjDQqjW&-MjoyerE#Ca-Bi2aOk zwC!21Dz6Qh-{V+t)tP7#$;~bz9UWowa+-3mKc4@`G0{%O>ygv7ygwqzyUY9i*GVUi zYzHD7Or`Km^>V^iGX3?J+b_qis^ymIR0+bCi3Ua!VavWGqSc|~6s$`BTrEl8TLWm> z3!@S&f-LKo>{gjTkx0c#mzJ>lX*`g`#VM7MuwE<=s{O#knAV3 zLP;=VJFNVV>-@WtW$^El^NZL(SDS#&)3?s9;Wv3N2C(IPo9m?KDO0}S$~(E{r?@3w z+gz*CE%oKAm*j+u%s#BYQ;mMf&NJR~+_Son#rsTxOSXnbY1P-Hx~Pm$k6$j^WjNna z5#|qyZ6y1B;(q>tR+6AzX13l`OAgdKhv>qTB)60^nE)i`=JQr3j00ZQ(ahse5A_@G zO4w}`A)DC2eBZ+mbA%v1^tF{A&|euKBdsl?ZFG5ch2l_bU<8tORLV&l#fc=F{>A)r zhiM-#I{up=n10{eVa8S}KP5i3vKonD)P0IGvc%&h(=Ai1)N4}}Je2loLtj$nmQOA& z4xIP^X1!@+V0<(Kv+4Xy1!5(`rvie=)@s(J zfNqT)$C#&C_mb%jHo3TzgSMl0748fJOTGepTzvb@Phl%n;wdT}GAF0C3v6ZWHCjL4 z^Iz$+ktS4Cp-8%znHBlyP2`V3KD}OYxV63r1 z*|?aJ-j{MMmnmOn;XfJcl0Z>8@|EG`SGlxB4n?1BpG6MdYPI6NM$)&Fm1W! z?=MX(T?+>S|v~L#CZTeS+RV2}G+tZ8ixn97m@MP6Zx z3Sm9j&^C?xlpGe%%1r&chWh#K>O2_~SC$$TS!ad+F)i+K<@)zySTX79k;;rRrx`B2 zzcHH93kaJUFHBf+)J(|+=)uU$WQ2uE%FlpjySr1Khor5NSfS*-r4;!u&1^yVVcPhtl%!>Pv(gJvpVhA8T*F zk&KL}>Urg&ORPzY7jX&rtWo`k;n}Lv7x+J*jezyE-PrWdC5a{Qxae2==NXeZSNS!3 z&Jp1Cd}Sw9L)%97&=|Zs*vyY8sVLRYZj0J2@ap6liAB3H7HH;!amKcuXIpXlMkLU22s-xyFjWn}5^Y!+(;N5k2LLB9! zKB2xoib?}*e~ky=FA;)MfHOOiB%GxzR^4`zppUQF*jkLrul$bBC3;>&WiV}CGoKA> z*)!!iFQFQiO+I(OAH3Dr!Ps_Y;N84uJMrn8^gdBJ$dj{0lyQ<1Dz3a>8X5}`RyjDg z8~G6*I@Seo=Q*D#FdG@ycq4y7N+vBNflp$5Ie_+o+AUSVuo#xp(PwKof~t?U)XRwT zKi|FnXf8^_1r={pDmwUa9h$`+V%29*WWT1|EV! z*C1KJ1L%9h*;QXLQy@agoGjFq2}q`WQaA-e*OF#^8oI2L?Ns{>%Dy5%j9TU|It6Fd zTNei6r=b_WQ?Ff5Kp=~fX#7cW(3bJ<*&`8@v`Xg8-gWi40BJ3lI9kJC%tl$_|ME#3 z@C(QhH8$YdPy~1YCe7OSf~6hEqsG0lj1*FB<|ome+qi*?yHfQ|%x^ z@A*TO$ot$Cr?lr{2-pr){NUmeRjORQ>FNHo??5LP6x;Ypnc4p_d1XO}8kwt&qSjvA z$&xV~gWXg>bJFMqD%C{M7Q8co{aYHmm;8>Bmi6UR!S(y%-R;0idkwEj+dU^edi;ue z8cq;y+6(nLK!a;AlYfL$-2802)cElI zs#le7PN;{_{1qS=fd}aPBrVi@k$c648LQj$q8s#MYH0bS1~NI>+6nGVm>_ON1__Au zCe@<r-z1eA4mrecWBLz0snCeF9`kwJd6=)sow`1I>p7*^hz)(YW}1 ztmKQ3p#ZZhSs!;b#m)N^D|hknb$)r1YWl<@07ub8L%UqP;jiq8u-*&5F!ufJmcq&S3ft{=b>)ej#R0VwefOEIb$wN#g7cCL$ zMo!1yF1L|cMH68{FXUwI$}0d~8FpkHRE$i!cCWib$?GUJ$w^Rdiy^wC()N+2RGPhCwh zBVCoJA`A{==vU^OadKx$2FXglhMke<*b`J`l=d`MtAHjTS5!h` zygyOd{a@*Ch}5pCxAa0`AsG}1U#EhYB0hZlA<6|kmzEzwg3Q|26Rx%h%j#q}NhTqA zlPV&+IQFb=S};!0`^v5HFfk#mm(djFlL^7?(K1B`uyx+Aj(PrSp-_8;&!) zMhO)U$tO~IOP*NbXHohS2H#Ts?+c_r7^hD;@)Jy|C3DY+%Z$1>MQO0UDT1vSx&s#2 za}3kfkQJ@RkzVabVf2z33NiQ<4B&2L1qOL;0uNKms?T`}s68Ew(^K>yUnnzqFUa?o z0KkF$@rg+LiAkwSO5t)=s}InJOta!dU~3!Q-Q_`%d)i%#<2%{Kg%}{OYx<>m zlF;*!SSOctSm&qVT>GyUp8yABxNOHT_kd*B>5ikFiX@3cE5HQE7}TG^2MpK78-+zf3d)TLLQ! zE4peN88aJfzihgKs{Q@!R})x+kk(9FrVW0G#t3|8(?hnzkqC6USP= zp~JIrJTiCG#kiMd;?fYmFcx(4)DT&va&J~^`#@FO7)w9Lj)b7Pt~k<#sl^}BDl4wE zIg};&BqakX=e>JK=o*?0DYCWLnrAT0#aGZit`4uE*SxGTw!gG$m;4i_fjeV641{MK zsNa46u$YhznJYqrb12v4988eIs(C1`v(v?EilC};6HSxP#gubg;gc%JuHf3tw~ZYY zxhBP#z(x^)Snu2CY(rVmxcd2?Kh0gamT)1-n$pgI{_?k=e4L*Zda!%Gqgf`suGdh_ zmAjk-t}6w23lisesfU0HJ<&>m^7Pv5bbUTIL&wz&q0b@`DBqnYqp8$PQ6#Hy+1vgo z9AM-AAEx_tQ3{=)(7}a((X{K z8hPrcVJhnF2Q*A~=2+W7TU_HfeXo`zWqxN?jCxPDpay2(Hxfv?hmo_tAxx3wTUN5= zFCXVP%bCP>bv`M)l-|nT?ybHiPA|8XI21)qlUw*y%1lVhb$Vr@SXJtU|0>O61REyT zrpcD(7m3~&QUnGic(dPb9f{gg)P~#n;i0ElkSg4|*=dX-zb8ljIGSN(F-Iktxc?kp zoz;q|c1M;vLZFAh}L?a^|=w$R!Ct?x5v{ zD1uK%kgfpXKpEzjk@x>YS}R>^emn^z_B7FNfWJ}c;I<587L)I;-gr9p*@`myz+jQXbf>+vG9frgx2>RA$uJCvr$j@7XBZshR zx0rd8bhIi1lWP+lHkEDKyY{W5Zv7@cyM=1(BLi&Gz52d5AG0L8*AL9(MDdAefFty?ydXkdv)vm zM->gtZ}no$vBns4%)cGZV;W-4s;p&kkMrj^d5 zbZoRpu+FEg)jx$@tt4t%o7aMm>Nw^{cJqf;aiLMwTy5_RK*5z2ax&`=N)*lzXj7tIOKoHXLSeltl~%}a77Ox2plmMoGCXCzmqb;j`yjwIvOAp<`! z(72t?iRxG$AWUv1O+*8{)nI(8!E*zB_Rcw-Yd5~3`Ymf+%edKa>6^_;c#481xL0mM z3CByU-VIn}Ax(H#A-0BAtQfpkdb|N2@Z<^`XkzLtcFlNLIbWvv%SRkhEF_&H7N<&O zOXJPj5mHdDuEX4qDRo-C-*f>tlaH0OpFsb21vP%Ts zza?~qt7rj?qS7!?0UI~R_Je|Gu6~tk}fbOM3{BwqejkOCP&sD8m3g+WPT(jwgR>l z?zCkNJ2pXs2|CAPJ69Y{SG`KScTJsz2mq#rwT(C=Tso{O^4G(qG{ZBKj02@0>UtNz zK1;l~4x5#d^}2asgORUvfi!HtzkLte?>)n)2khsBW+$=(6MFv zxb9iQIYOKH)05J?T#X9*V|6M-heAc@r?=4i_KMx&RUJ` zF2|QSPoyd6QjO*Sj;~7Iq<*b_3Uj($0&AiFktQ8C#+Eh@KB!4!DD;bK%3}}W7P$L}jm{BqxQpoRW8^k|w@~{@W=uD?H z%ZV;}5Gq(v=p%Vs$ShhD^$?ts3N7XMKH0sgd+lB_bTB`iJDr${@4~*6nxNBSTbXT> zhsh6Hr|gM+Bxo?JbF={w5_n#-X-Y6OfeH`?y- z-=OGYqnqFiVf6YOc2>2jPI>5T{8-aK|8+-fX+SE)Mx|Y)2E{ms27^*ED; zy*tH;tZNXf4H*olL!G()5|uUTi^y!AtfF(*uoZm4o3>6ZUAgBsxgmJpkokm;Ahhj* zWQfJm+6MYIO4)(NUyF_>P(9fxkg|rI1@CDVhi6ad6rR(zLK-jObk(DL4=HwNKYWpz z*%IM~)$nBH^hZBYgtZR(!E14{7Na-cc%KIU^oihe3Kq6~r4oUaQzbtqM`$Z1;j^a+ z(20jFm$D-3UG78#n;gIvH`ldE^1cHc{aiyCRb_8!Cmh`@P~EA6b_gY~JX0 zF(O3gy@?97QQC7zE8gsO7_QBup{9iFV&!`fn#KC;u@#Qz4%QL7vE?RgGTVVkK zt==uPayrL*DM7PKUGET3!D*DmkB;HK=I2$7`C7$l#zc(ypMX3Oytgq#oM-Vog!gq6 z0i4Ty{nsRevS$gji;K-2Rw$OGzSlNKw-(-=J@X$fQ24-OsQ;F58a$spUQeztxZa6fVA+q&8IkuB0p6Vq5JC@Q!8?#s_#JiITuMW(=WG2nK;>5;9~X{a_{BbFYk9V0vAtuuMVfHyrn%P-sOUd%Ks_x~LiY zGT`LQ-WQ8^tI7yek~}0m@;Dt^aY1@_vfn$Vn^W|&QO>ua&%22y0RDPtg6>2hzoWdr zIB7ATRP~$euyy~SBCi!$`OT419_n><*8cfUF#w2BU*}oBOyBD1@4F=8K}}OIXbYg} zIL3}I;bptjVvgeKV>y*q3*NdmISe;D+_z5L_XV=0R!^O<(b1Z2HPHF;gSaz3CYQJB zg0RD-k_#a>Tp!Fe*9E5h7x~h8Ry3kpFV!8)99~Itf%=w~rs@`Lxatw<42JiB(37+r z*s=HS@#xtz#m#Gsprg^+8*%>oB4U=8Bi$dD+l;fr)4eANcj{xZ;K)Pbu|#`iwQY6? z3$GTpPz^1aEx$-?Rw6mKwz7qSREk@GRT)>mdYG^wkjWOKhIC77(JLai;0^fW7EV)z z$z1%_VccZ%70K`O3WdA5iY`-9;<0?l5bOL&Rrb|+4@bLwP8Slw0xxq*MztKmcB|!J zqdzAmY@C3G@?fq0#RB=lJbB(F0-W%Ufy!!?u-IYbS_2Kk0(#-kCM&dkHJZMIpG*)t zY_U8f=C9fk5XV0IgJnj4hWhhk$O{Bs+USN_lEvPLj55# z!-?1TC8@5Y*!nEVRW@xo!-h!0$ZF5{&_hf6N@)vn$Y&1=Vd;uOH9y%=#vHQis>^8@ zO#cZMGy6H7e44O?adQWU=cpqy8$VfWAk(L?EHbXp4^XYjOv3jZ(C<*q({EL;R}_yL zzgD{qx%Od+O&SZ5_3(faYN5Nn+uKD4QtOZXF`P#o)rFobG3c*cQrc1AF&q}G9T1C7 z&#**9MZU$I> vcDS$&6B&|k5kMY_<{12T@`(5g;S)hHnQ@pO$%W>uK=7xde-+E zhLgiZ;o0+#eqmJ>hBLgzV4J{Tzid0uRW~Q;YMh@V5#dA^%04(aP*gU=O+ch{_zbU8T%4BMUP)<$zyxJDi zajI=rt=xPglB%&iKZScYx+I^8urN`z-?b&pNY8#U8X(|PS8wi^*ac}M4hu+X_>N3> zZQ7mR&rj?Kc$+m^TYour^S<;5abj5*wB&qXX;2L?U!VJ)N6k=|x0PA3tJ}m3B@$=b zk7kP~%)sd8Rlx)H``6d!+&Vju4-pZXzt!;X5-fBpHTZV!QS(L7PLPTsvCh?;z;TC8 zbP0Zvr9ol8AY-^<9@#2TYioG=STK#DW|1!Xql!y`k4AMn%5_Q-) zi&~b$<+wz?>hP0!>_>o$A)ykXp>Z?gg zPn%~Hf3%CM*Pco1LWJ4ecgEZ8ueY4Un--?L;;KcX>k3XN9O?Myf=0>dD1Q^Z4!51kMp66C6hZ=j4&2gf3N|DTVXrmHB3y; zqxS>Wqe-3(RMPPIUrG%{QjlC2drN<=r6LojTFzl)Gn1z}sz5BMDw;2)YSBA` ztU^IclnQUOd7oa_JeQN-pMK!MNU{tzHuJIjmbPc=LYPE&sJ($7uOqX(#W`nfmT>9;Lc`l&-y2!>= zTU4yt(f7AFKlm5Zj1!ZT#+kP~w;1RgRtyBJZv2arAbfk#NqfM!_h11a5(Opeku7z= zQG(7trOV^O3y4{-x~AxaCMfYXw~i+CCU8mAfbr?P<}>wkBH0Hc2xwca@ zH!6=i`6c#Pdtnqg_#tVVLq^$eY!ANGn~gZSzOxY3;(srAo*%bST&UX3Obc}RSzYp# zQFzJ|p;cBne0m4bYd2+t+FbF&9X=YcfF6ExbrYWqJm=Ai_rvFe6H0smRvE0iUM?J* zncoJwP3YUxVsyZR`ffNU(U%1#@*1=Hi-SxYLsgd(bk3U!gMbFOO%H06E|gH?;%b(`X- z_nwIFHzmY6EHb%q)+qCqRXw)SCr6!9*lxAID3f5wkKwA^_F?{T1>61>kj8XW zEW1eP`4L`gIL1gtar-%aGi7~jomh#kgl3@3 zj)8Ia{Ugv?)7QsOTq60a*!d+PTl=Slrg+6hYd@SW@0LSn?=vEsipJ%ZqgQfa4hDvZ z%~zW2+QVr=I=vb(Nci|vPmU3FZ44S+oq{5{xw3~7qo(6@C+`y26g%Yd3kI7iiC!r4 zRrk=MMr(64K8_Fr$3v)VBtf45-(Rd7!Z*aB5fb^eA|QdpC)U|$?x1~*)k8u4v5?5( z>w-WV4t3EPvpkXaUc@s|WoJP+nPioma(4rJbnA1B%5|34CUbwnbt}mJw}#{C-gm$W zZl1#|$udUk4562%t0P}QLGw$|J#%v^B>vx%muNZCufqgdvt+`^5%sMkKK`&<{u&7|dQd%fk(Y}DX`FrFX<|)_ zEs&*SB)$=liXQVXHfuD93q(AiX1PV#2|hA2?|td)YdEI2T2f3`JCfnJNnD^1H6MAA zf)8ebCvY=1u74XeWxHg>t47#rSv%7G zr$k*xk8e`2R?d#T|3OwHTkNK@k6`4 zNKT=9zr}K*AiM?J^*2c9cr>qrhOy6|u$szGRL?~OT)n=&o(i2A>{8034(+YIAfhc) z=BY!#Qv(|LynBcLA$eTShurR^IAtXuS?2g`;X73TUdlkmNA77^3vsjqbHB^1|Z&4K@ z!k8Z1QRdF|ifYb@RE7>zrm`3$d^qz)4WFOno$pInS`1kX+g&@(_hZ9dDi!d*Lde(e zM+V^mCfDaiJZf$QYVHG#PxCkhmPGh@=H@8t)#GGHMiMYlDRTzlNIPy9mR)Pim3Kv8YkGg_(@y4B0bSn5?B?yJzR+ z&11(C7`q)+8i%v%jkUU6u{_8;50rdm(ttJXCgK*(=Bc{JcTua0SuUB5L7&O&*0#rf zbeezV?5J-3xc>n_s}}|YXg^~R|IFzBLwqTGa#;p}>cL#_06^auMaHh&L_M-;@MnoSsY=l~^)#Xus7LPHI3^(gN}Cm8OQRw8?pj&e{CQi?B+n;?^iB5))p=z{tke zVSfn@CNK>QsMO`;&<$edsY~V0_0f{=g>#Mzi7B$zkO;moP`&-bYc33wS7&wO*(q4y z1sNaIxmP&-b5Q^CS3Mg}P9O~T@E6$%gGXpT-OzhI%QF%O68*CT#4s2k1n4rAkF{~I z-QSH=#MxEfaK1!0NlScjLC?`R>!Fc)m_S4r6q$!c2_ii^Q~Y9G>{~ZCubKS&^qpPcN2w8!(vQtE&ZN$Pw~B=FK=!Hr#-7$wK)Pgx>5UZMD==$irh#3wC6m*pzpnN z1o!H=0kE`~2urni{wsVEY`uMGxqk<$Nl-*TF^sY zRZwu=*Gtd5gk46w+Aq*E8GOnxxAZ=}y&R?412=E4-kp+>#;hve25;^M7YxiF{jz_m z`XA;a;_g-RlcLvym&QZZ)!&SWI*gL~H-w}FW}oVGH|`LoD3ji*qzJe%t#s%=`a$;l z-&fWlj;EDpY3fcH*_R%4<}th)Okn9=-Fqeq-aUSYVFpIU-*s`Xyod(1{0?5!btiw( zmb~@1HQ2_T{mB27>6n4;3_1aYXgS3e$sJZPbBf>2MpT^Z!L9 z>wmP$?o^01e>1fLez&lHwLY!|y}dc47S_N~D%{pArA1lWUm1Mw8RA`^Xu*+1w{S4} zr4m@qX|5vrpH_jSz$DTi>S`rtBLj(uA-;2t!s1`dcM7Gk=-QL}qiaPKlZ5g{$Q3^O zoqWz;d5inh&Nu7SM)ScXXmScm_jXjS<}q1s`hYug+_kK!!HCiBp6LC9J6F&$Z+ydo ztUTkv3nc}II;O#XS$X~|UWVH|50rf~#4OvrI9-pj@fQ^>jiyNszUp-NV;-MsWSMS3 z{luU7X|^@tJYpH$iBc{{`=1$v*A~w$C7*f(yYBS*I`YJ8+DAJ9FaT8Iy`lNy{xH}Ij}S$G zyi)hcg~$(SbLy(TbYjEol+!0;C2SlAh@WUeemfi6#_hW!NLh7zwpDz#(@QXb={ud~ zm-#9H0X91GM}PDQnDvmp!CXV(>b*egamZ8JxA}CgEytwo_;NV?3KXld6V5B{f|A*- z(Lt0CcccYYI(GN>{y+GI(g{fv-KF@{p}x7hb6@zR#=hgdtq@erbKEBUwL}HBfd0gI zVYjb5tgBaGvJ$)eNFAE`TL4LraIkggjTGVY9_%!Dj?DU|B!bQTA;+!kQB$_Dx7Lv| zl-8S4W{;({m7Ul}z*ICatGn6+x-sq%pX_c3g?MpIn})D*%+)0dE&ROh!kAYc|M z%9E|Obn#J|<0o7D7>nQq^NJ53MgI5^McLOUuV$<0n{>zBWUx7zp_XvW7ihyIWC+~- zAUjr-y6pvA;K|K)z7Z0JupNdK25FMW)CGDO#VNGaAVrdsT!7@B`w4_;pMmv_bKJ0j zH6DK{VMjYcJc4WtU<(Y%kP*dn=pOipfRSc|J1n&3Ko=%lm9`M9x2fX(8ZR;ux26^c z*>9=)UK{{$nN7%h2rp<}^2qTm*oq-)l-Daqm+Wwj*oY<=Z{o0L;q;4;S6(f3!R&?g zLtX4)K{zy1id1GpHew#7ZBKV8y_i+s_y_@>ww z8qZ|XIIJrM@+rTVoxVs`c5S@E^i5*p>C#*T4^zFXdfrNici7UQ^iK`l#oA@|tA1B~ zdKdX-!~p3F>YU}r&-bIgr;x|utqCqW)nVF;3W3gN6>KoLsXf!{RL_=yW^Q zVN+zq0~MTcax==SGyC7CjL&|BO!S_uiNRrt>zh&~B{ys=wS3OW3oFB}8?InET*f2o z=Y~>i#H}5}Lo(W(^?lQp&|5MQCZPu$&xrcPwE&U%3=W zo?p3(MKG}R?YmzC!ILKCho;`ZjwSf#@1l~z!2J5KnQRgfmGx=y{7W7e--d13FVwKv z3~_0Gta|ofS*14ww%~M~?|=Wo_qig^rY_w2*g)B|8}AVZc|Tg=M(8nn+P~ZfQoJ4Y zskN^+pm>ey&D~Axb11#@WORs7-@c7N3cHe^~3D0W(tUy=bBmiHb68QgC${ zkJxx6B2S+@892*4V&MEsQg;TNBPIcSm*96x(4s_((Nfhn#;8QPj7w z1ei4VAZ%ql93y@pP|OgP&^L-5kZc)Qu+P*1?nP{k+?Tbs@5x6M6D?~`g>^GIP33u0 zT308nL$+=)-HPNsNq#{WS`h+{{${IjU$+;ZVZ#7(5!Nt-;OYL3`qYv~KUP4&8E)$k zYy<4ElyPyr36ni!E*$80qvGM?kBEuCEjqA~G8M6lpyfABdq9@Oan6eu5q@;fh#Y^F zP;pAj%rz*lI3H4*`SuyX+>`yuTLX_Q(;kttIOzhDO^t2qi0ChL$8@CzzIGQ`nigLZ zhC%0P5@syf5O>VgO?x8Esab2|5YWQ`l8^4&JQls%K}(j$VK%iR&Pc(>xN|ttQUy`O~?5nvX~yfoN6@4B9cAvhl=<% z@hCDheRRUZE#r$;ptZp4t^Vts>+1OE)EJ~=I|tuXwZ6+WX}DSC_DEo?buZvE+OI|E z(1bW|G0FOy$@%Q}oCQya&!CD|eH6O!8D;PFhA#&nKA$&7)G z-guu`e-oFK&T#Qj_$TMc3iQ3+@MKLLoxDM&Kg;g~TYf@&XgZxKW3h27u9r30^aDnb zmtLvVP93RvwV+hA>=Xc@9$JLmz{rCI+tN&CVM=ni+3}3RE>R zKNKg(x!U?+~rnH#M+MfBy1au`%7%%N`&M4LilcDX-pzLCt&V(FbL#=`VGu=+S+}pVEi(S`3L8{9ICZFgv z4%Q%d4uLI708c&wZqC00={r0Adgh85v25S#lPG1`+H{4?$;0f<&zTsdW`HUcuKUl; zz1v7lkQ<;_&4+-zMPZ99|8!kKl_oRRpuy(X6iKH82kor8sF>P5bF|SgB|C50*ZJDN z@#hovbJJ4fR|WA1{mh@AlJVFI3V6v|wRW_Nx6-^|bpJD`d+i4sJ^+I#;{X6#U5E7_ z2UX`P3|#wjlV(CFmm*nT*X=^wTK?RKgi~RrhyQ`_DBoE7|G)4k{eL4o#>X?#vd``{ z7a82mC>ijoZ_k=^MGX8N$lR>`vnn*t5@Ny-7WS#9@LTy;OlWaMJAO+{+`7OJ6 zy8EvYOO>jL*r|)@_bUYqE5N_k5|&4GuMwk#CV1}PJ=-W~c>H}|)>;z>G$H~|AP8%t z1)}Y9Gg_7Opp?wo3Exy=I~>&YI{kg=e)>NINL^HXME7d>oWh|q7>TF0AuVE8_EVJ( z)ol4HuN~${*8f+Z*|vY!KYeD&i%3dO`w6dTSQOD&{X+lU1m-t7W+1MhGH{=HKa|meb7H`x;QG*uhQd7t={zj( zB!O+2C);O+t!FvwxM!~PFdR@nfgFuKS&|G5a{eQX9 z6ck)K5IO`fiB1!8ROo7$e#HuMdeI2bgsIiF;yt#qLDR8W#R_noQc+CB+9cSu4rB%+ z@(&@fKGWV}GE4;H!HEVJ0xiwo+bb|kC>XM5qjc#s_U{mdb9Lq*E)9>IU z_xSlLZPHFhT}V()H9EWTuV%;@b&qA!Uo84;I5gOd7@Q%j!k%`Cw&TA;spKx7hw%w} zJ_k#Ei-HZ|zA|)4YLCF%^}p}6^w%dUknRN!B~CKDPkeVvH+`}inq!!`XT6%#4a%50 zYY>*&mtFZf01$Jn)e=Y%Q}#XX2^cwB{3f3x_F)mBGcDxwkG|(AX%(5Puy3@zR=A>j zd%*z6bzb$hH(vf1HTwxh&A!oLRUR&bQQR6?o~Ezv6JCz~B)y8eUCpmGk@@LAm^^%5 z{Da|=GujxENX?%Y@Y8>{I_Fwh7?Lb9FbYiY8O*5|bvA8zdBkn>hrvTI!O>a4U9 zevXp1^`e?rDn1HQ9;5YdY%&HWh1`_qKSi}e8*AD1VTabFz_Xd!WZNCo_KqdGhy%(f zamS}w-0@vwy4FDDWGK3BiN{nfbHDz-Bf z1~P-TZ~ltEUMV4t@4ZSW{JbK1TR6#d;u+r%hosZ{N=@+aQSVSMPi8R} z^E*>{)=guQZ$Fuqu0R#J8oLNKO=(xoAFqy8Uul8y`jP{CpB#eqE**t z-k33z@^9XluvJ1r<6I=Gz9@b;^qlR)skFnU+SeP@arcEfuGS?(&-b|PM^=&#CJT)Y z>^SlFLw;VME<2SLPp*~0Qf^n*hI0u%GG}q{W@QLzU2~DrcDJm*fR?_IaZ)rI=JeEJ?YgwvUs)2oJOODw>@IFRy&1dzg{Y2&h-E+m` z(XQRs-p$NB!^hR^8nik#HfFsS*fPU7JIf{AtdtR8HC!HJb4TQgwcKe*GsFpmf0VZ8 zVlkBX!d>Ex8Yg5HZnUM371hZ=%z(-SZ!0DKo!!$#s)ykH&!h2V`b-a{)S5>hX*W4)t7Th^|g z<{HWpsXM&DkQ?%|gPE-2%?3`1)pFKk#=}1T39J0t+7U=0xGM=Udaq&K(t5es_C(6g za_CaQ5DC?OF`n)f6OV?_&% zp82-NU#9(6%K-lFfvGe{$MZ=o^s#4T{F{^#ia}%S$6|MAk-LoFnFR-ogT}!ja_Hjg zbS)`|1*Uh|uDk}$(Z52y{7r8V984wqMK$8>cxF#fcShCSB*x2GPLbJ9eDnG(3tqV$ zfeWzyoKiFimXUVixG&ILn`8i{(8B`M;d|HxH5tQ-9xl-;+L+K;IP#upNgo(h*ufBr zvg`$$Ivt@!*VU~ycW(OfKt8U&=Q1z-iIgGG6b%M?C z@k@~E4nf1TOZDFmC{Q6whCDAD_Y;{xF!azMsJKxG>!0F@p94+ z@AgGhN%3J*iALw!!sVL2K;d~PJAS@pc0Bhw=R^QlE+kq$N(NbTykV*7i@tg$#vdR4 ziEUgf_&32V1RJsiJAa=qU`79ktDOq}F2%l<{}5-VD*q0R$o#i7dp`~H-}(u^zCFk8 zE8TlmS3eLCIKtFb9eMNMev$pX6y5WupgXt=#}Fg_<_0oG<+Hf+-jcZTZblSTc^h>K zkm!e_!KyHsqO>oxB}^tKzHxKIR!ZEX>8KaLg&o%;ioBp+S!Yva5`1UORMpQ88cl2}nN%u`O2y!#v^H zcIuo0?$@+u5pu9AN6<(|?=ud+A%Z;s8_bylJgd-LAmKxumI{^jnQxl_j$H;j z+|SAb7ZQdlmgMrRd$}*2348m!Ve#c*MfrB|JaorSB`lE>>41(%4K7esIV(`dO55=! z2pKqJO0JQ_n%>TzxglnScDiSbZs_u>GX?V?UCwqF>fC>yV@m@iMDC$mfj@+Wwv{I7o`d z?d=p)*opVe_?ma3O#~fwVj;>1yO(s4>GoJ_@t@{ryB((q7akG9o^gNJqBgzn&=z`i zuG>046F!sFhBwneJ+xB-@9mI2gf)%9KNOnq$aRC#!t-#hFsW5b$$t8IKXhhyr@u&? zqIhrV!g^kSrVH08nnG4LH40B9ScdDqWIhrko6+jA8>7}xTX=B6lL#E3?xUb&SnL{L z>CUw$=hOE#(LpYouXZoX4H(ssj{&?B2q7v>y@=sp8*)5c;rG0<1dxwT;KeW0Zy=i` z1RR^cTjtH6&~Y`iEA08@gCwfg&v%MKfrvAid!4|pHKAJ0*!vI!;kWmH$pfJviO2Bg zoG>|4cidvjZV=YPjQA;e$=k>;tFeTGHt?f$awW>-r%VGTN1iUVnv6Obf?&qtI~Ta;2At;!fxd5GwcNuX;n+7C7A2NO z=7Xr@c?c`!BWOZsv6&sYU&YbRGd_8!(;MB54_y8T<8r#Hzf$9FYsW|QA=}lEgdXo5 zUF>M?i~!P&Q-!o3soI*iZ(1cl8!=6bq%WiD)?%++Xwu&r_$A6C7B!6gN~Lq-7>!6%?Wo#`jScbagRE-mw#kpIVgdH`F{eJF2K%@e7)W=VS8}KOmPnM3_I5 z{!VVDZ_%}PzP&T%1jlh9CY>$vnTZ&HU%qvj6!=-PJVN$;l)+n1o)1m6`xKbtWuULA zAuWRAKV4sV>l0)p|CUlsB~?9_rmbAg^cetF;JThf-ct9Ps|ixb=<~%*cb>KL%8<1i zpv19J5kU*GD5Rc`F5vUO>HA~hGD|&oy5Y{M8o%Nb4W#(!o~qwO>6WfW7v3)6K`+QI zvE!Il?TG{-(-wVpGE~cDu2uEz^%5mYM>G+&qoN1PWVe-FF#)5D)%D-8mcmT8rpm5O zVkX%gYjIP z1hD&GXwR9Oj9UlW0FrbCD|N|GW?j4#JXKW6{Sb0u^s{-Hiw0kN8X2|&#iydHiY4%Z zZ#c+vZq>FkJU(tc=60*_9HjDAZD^5XtS(2j4*OVgo9sjh!xMQP%4ok8jqN0VWf}U_ z$f#?$(w^P~{y`gZD#!tJTEj~X%9E&=V6G^C2^(_e@5cl?fRR!#w@!ly;IqRTGQ%1m zIGO5BsFHpT>u6N17}gE@p5N-u$Trp8+a7TVbO|0N#z%BcjKPdDpDB4b+l4B$T$P{N zR=r|0^H=PhG$=>m}hT5UV3{KMi{k-2GM3DTe5Tt*PpGGDi;iKP= zm!L&n{K`i#D1?eTc()ARH zOHt712sG#HEZOd|ZYQ=10PJ5gJ)z6Hmt}o3rgF@^jL&mV*yD+0U0wYSU9#mB`ER*s)R*F__l*ay4&-?U7~u${KTKv^i4fL)vrMw)nC> zqVEUtaeS0YB07?j@RAzwt~e$vrb-zpmAJ77Wir`;5<|bAZ?#&eD$u&ofPQ1FTJ--x z1SNlp<9zsF>)1drkH!5^;Azhe_duYr z0r5hV2SPEz$urBnDed%a3IImE*XO&PTjaK?9Bk`Gf%Rm28#{(3(9zg*C!fmbR{vpk zEDg%$e8-PUnu$<2j~FypVpO)3;b_afOl497ntN8>^MQj}=g+i-Cnm!o=s6y?DH=PH zEri>t)j|lo;voSm<-ZKU?`7E%yBjV#$qlv&KdZ<19!WWh5#|f~802r&ZQPaVPjgpA zM%9fm_p{JZvK?|*$mOTm+qiQ_@oIa2CUTB%^}--{v`MDB$aq^>a-dh7s}bkhOfg!W z3I@PtYY<$n$*k!g&ec;H*UK+k^Ju6@3@Q5gL+A%g(xsK2IpmL{e^zVm+v)cb7ClE@ zf+Q?b?_FEjZN@2jmns`~)Tq^VnGub7C^W%n`#23(s=>H`li+l5o>2+Km`I>mW`e~0 zEJaVQU=%}m9bU)G_d3g(6UYCOb^Y?(J{3hQF$e1a_*TW?Oon#6F(k5>t%UeaiTuu~ z$g75yb-Ry1cQeD}8$Mp zQ~Mp#uXjHTaF7wUedx-)w5I(bqemFtO3yZJ|Bfh_yRG29dNu@uPo3Fp zl{78E5jc+Wv=_RR*qIuO zi0!H?vdAZtqZ-69{j=X;sU8;?r*{+9+k(8Wl$dZ`yMTCV1qF9l6BA-JG}EmDb>~c< z1hl0)ijH>KPu^izrqn>fXjJ%kvXXPCz083*4kweEsRtRMlN`o(ufZeprk;aKG2HSpGjy>|GXwE<2(NPLz$QT{l-X}t~JSPff`S0_fKBKYVLXI=s z4l~{FS2-s=)DFo*za*qvt~Qy8aAIarRY?Lwys8J8&gFyTSultJ4pt-W&N(o5NVf~!lhk29%=##Llk<}mXhU49REWW)>ieT%Jb4^T{O+KOP02m`R;&Un|Vucx3r zI~7>|q^)|_QD_FTP^-;!ZR6%u*Del=@!8NJ4+miN?=P3o`*3}R zex2(MQJOt>`6hG zBT@T&r|Gewm)U&wTv5Y}oDR zC&fO32V#Bx&`4V8S9C5sa6p+zA)hB|!HEz#REQbFaJtMu%lLr+R4wMF9m*df)rUW= zbruY?88x0_C^QnzjDO_4EB;lIS9f~iiMu0eejWN^EFtYAw7DT{W1ZAB_e4Yn1T=oW zZk=Ml#IR4{?TFFGHaSZxffG5Df}4-sA%kXV>t>z5!~MV!!*90WQ3a)@%HVULnfHr^ z58Zp1{D7Sak~VK2KuQh+gTeio!1D;wmz}7hKLAhf!V2i{9P`Lu5e6t>7Jt%Tuo|je z?TVtADV)3ft05|C8lZ5g#wsQ}cCY8|So>0sf4{oEN-YjkzC%#XVasWh4Nv+I8^WYXgFwa<$oZJYcX(tyqbU}-@za}CP=dv>MoruJ zH)L5i!JgR313UxSOzQCkh?9bQ#Bm;qMLUG`K8) z%2F9H@))}8|AGV*9nVxrQxsnkML>54dn7Z1E|!#3)gv5a^hK)DMFq|&6h;G?@*H=n zeklwJo!>pz-q)~jAQ(l>Ow$J}d8-6xZ47CWq{O5a&1~zC>FWE)7&-E7{26dlj-0>^ zjqpekGyDaCOqX#vAeBx6+b*q}@DcK+EWjB;e!^qvJlQIu??n8$IBl1bLrGvhA@>wC4mb$(H}No1&<&8AN~+=(6lV|B0?S0i$@ zni|1v-V3N)Bqp$}u~q=1LSY}~+ohsq%a^h0<>>;yUkbd5xALY!;Ao-geHw~$kRvzU zkUa+4ZUQx9B;4k9Yn`m^Szem?{ZzrW>0elpG5Z4SOlVFMWF@I2jPh&$Sq&7#DnoF( z1L>K>rPwp7`v0m-VM>VD(`0?yP`bG0^hx>i#Z^3r_N`4{L%%8?2ovuFrMq<$Mv2Ts z5eN9fpW9S+o1~DffA^}AGtb8RG7jnqB>cXPJ8mhQrWNAwRWK665d?lST*_P3w61EV z7lo%OG5Dd41qo_P@vNx$6F-mLMuVJl?Hpci!*8TMHjCfMq}XnZh08|ZtgHj=j|+ki z9?%2jKD3;!t0eFK=4=+L0LBJJU~BP{ zlz(K^xfpIB!aAPn!f)r0i& zJF44;p8zhMzY5@%^q79Q`tj-!Z;Tae>M`KB?GrDb_@C?MphRE_Xq!aoeq~o^S=$_%T{xbSox*^=^gU zEA#hQUcS3Hj%Z#qlgkpBOE7vvG2D199112ZvS%2wob+zqkvjMc7Y71cfdrEC)K>b!3}2R88e9d> zJ4Gfpein?|Z)hURE^BD;f{8cX=@dpo-tSsLan>Y zPs;9s5c+e*k!jW_i)t<31Fu$znb;mNZYv_Gx0zDW(e27a5>U*C`Sr^{c^LSiwOkpL z`9wiSii}Ws#)ioyx2rMGwq$*@j49Ce-kO2I`OehLawOL&S#z#3={@UnU>Q1znev*5 z;zv5RB+{penuH2Q(1(c8xZH_x<v@`P?nF&fgyO>-(D zQqNX?z)5rMsG~Skh!S~#@@)WLFEP(DW*H=^i+`4L5*=0TtXxHX%OY!XhPVxs^~ckN zM$Me?me+f*TX4}Ko_V1YNO!TC&Xh(9xkO9F$!kJpU@Q9pu^=1XXk+fXHoG9M0J>V^ z+cqLv%{T?78BZV6?8}4Y(D;b*EG%X|fz00%JQPCY6St&@Aa*OIfog55Su^76FOqYM zQumAC+i%!$7F!Z_dmrp4JW4qZAXzZE0??eOL8g=6`fT^Ufrl9{;Hph-M3bfSG&{Di zjz;4U@Hj>_7&iu>;}NzK5-KTao-<@~(^9!LBf|@}Wt9mVw31v~BN&vG&hy-hDdem_ z?<9#Ns7&%_=QA>;6NcZ>9Ep<7EZNGfJf6jB5=y(dt}_~I#MjDJJ;%Rx&W;dLr2yQc=BqhF767rB3bq#>wp5aN^j zyC?bG{#fJ?kHwuUhndQ&n=(0rH(S#aNE8kO)W?ik_8YG=N^%oH7@9kRQP^=`tDWr0 zmNwz1EjZ&ig3_y+t6pD#3~Ni4(}Ng!Ftp-XD3-_&9v>6(_xu4LL-0bQ)K&}mskTQq zQf%Nyj>30OCCARKuPalZ-a#wrQ#FhY^xopj4mjCi?_UZx7;2)t9G=gNyU;lMY}z-`DWJSu^IQ~4VdoC|`3KqR*d&ou@-!2# zxpw%jU;x5}^=8Uz2cDyYGYee-&>Ir~1xc2k9-rt^ET_A!{}qO~%Us{E(@b^{Cq`Ne za+plaxL(ctPv4t{xxS|r(=Ty)$Tl-n>hsPPY^jW)_19L*0N>`eh^_8#+EoYFeNi&i zdba8*ZpIrM1+~Y$37ChM){6ldXI)a!YGZrfyHzTG_SBj<*<$&8x^D2`V1X^o#Ni1+ zLuQXlOpY_#N|JnvAV(U7UMl)#9P@F{!0}){DkAFE*;I{lg*q8$x!%Lrq=9Z~k1yee zA}s2wtriM!GTfXBz0mWHyoFsoPUFc6%IlhEO39%%ezi<~$SU#9+}P!#)5J%x@U-{$ zCjY7305Fwen|>+2JRX;S?`7?2P~6P4LDvV636i8wwdwYgNSjZgK5<#5nSQZTQJ8hF zRqSxIEm>FJVTQpz``qh*l*eqThwp2+WUaZ*c{n+w6Wg=-)Ud}g)p|w z>Y7M{({tHa;!R$pq(DA$^S_<}d{3Ft?u+`x&Em9otv^lB2Bc(*s?PR06Mdv%VUv;w ztW6qSOj20SY~))AnvCc7z@rQWn6&rn2^BIv%z9LAOp0h@PA|}19Vq&Al}M5KukL}J zPnq#X^9aXY zgBbG5dwOaYZ-VmxpC<16T+9w)K=-F1n-lrn<1_dB`Vgc@sp^{AuQ4ZmZxw(SYW?(Q8(YagNDa-~DVU}7Bl+^dKQ0oT1^%LwnTErv8 zxKTs+eBzK}MyCpwrsOzN$Ufa^ULMgAG+beNN~=#?kOox*5_j`Co;9AJpA)vr&%(?u zO=}nxITyaEOP|mimD?mTz*ng_n0pCifOzpvO-*VA$ztSeRp6iW2nHP|@N4 zVePHL;@YCE!3cyPfrAGR?pnA82=4Cg?oL4n!QCm`-3e~NwQ$$q6z(ov*spewf0_X%{k_f_Rm|JcWm#6(iV$Cye12oD=UNKw|W$e4^mDK$9Y)lONNJ6J~SSG z9^LdQcXv7_UNAfSA{U{p9X%uhv`MdBlYy_~Nv4T(thoJZ&F(2_D0(1xN@R4F;u1|q zI;-#}DewKK64>3Nt4gY!83nwUEpNpBQdbqBt8|Bj1`JT7lQ8rEXoH@MGzgN5mI2}S z*=7CNU)q(c#jAjw4ssNBmVF`+H}kh81<;P`73jCFdni{}0~s{CSA< znyctNQ9+AFmi3{Wxx0N=A}I9YD$fXq3$(jUq zs^RZb$LJ|DQkcHEBOr%K6oL3wcfyYB3aUkIQF?TQ6Mkfr#M6zKcVV0U)b9HqAn0i! zG0RPBSR5c%qJY_xsUA;kyYDmLHr~VLU>3p#Bc%?4nWR`XK0~`pq7RArzw3t;Wnr;- zY+}8&ziGt%qzCY$6DnQ1cFl%Id(czY+uK=lZfwCkhLaPcub?TdK71rB&D|IppZ+vg zI@cs`gsUp%x#>_-w3P&BAeDM1(u7$vS18{%m@L;A+<#7qalioISX;+xwCir`?SJv} z0)ts*o@H|b7&Khru=$CvNF8(6X|SPrYxN{RH#QLmc87FMUUg+J8$ot!4%wSVI=AN& zHE^C;g7;hO3TYkpxJ;3Q*D`N2Wcm8+k+vowrKdLB|07oi5jW(XOnVSqqe+}gv6Qkz zwM2ojKReZ6@ZcCBT4mBU4Jt!)jT0-`vtsbCvO@{D&Rk!#n;S?q`a%66`P>3Cvd`pdTd6y?IXTf<7wEXmhImmfnXXneG-JAP!!&L~Mag{WM81$~oK z0QXz(Yzybswe<{l8C}xyK_+JQ&H;6~`_50jlO`C94B-B+dMoo8+@aX3jZMJJIeO-w zo?ZrX+DoSG4As#gqQ${lYWbZCGZ$COT)H2FM)ULWOp4f9!Xiu!;#YorjNs!titDKR zWH5)hwO5_~$7reX?tlz`)XR{p38TIFy~wQf_%&`pR^Qlf{@UUJRi;50JOfz0>74iG- zY}%;=Th{s0-CfH6{F$$tg_fN?h@zj&>-o8-6!k#qFE-6?eM}&ia2bbB zizIU;R@E9U0}t9m*g?@F+=EQOpovDJnGd$2jDV#C3a<2W_hTSbS;0=whE6Fj zVwh6;nPTWhx&w3YjZEI97@P1p~|lUiHpjGPYG9ttB~HRw=V4v_0VQ4 zv!jUJ$Bkt4TGd*Mqe=gRCAeyz$q#)MX=zN=8KE0fq%L@pk*9LWSoA+P&SZ0PdZYHw zaD{YPH=c>qYP%89V^Vg&S!Y+C0P5*1h9RR^nf~nxJ22=#zXLJlu$zz z-kKQ`uX=~O?rx8OjT1610d%Wn@DGe2vE~As>X8OWT=_*z8<@>ePQZ$;Fb<+yZdUjVbJXh{QQ0(9Pn9v0f-Ujlm$n=C_n>S34)5 zjQ$6^IQo9A%XBNltWBtKw$)ehubhw(nP~FkshFNhg)Jxk!BpBK2_i@@cE4zH1}M{! zK>xeYN;4WLEX!CHUgZy>P^K^0Mi?V1RzNi_+nY*QvjM{9;MVSXQS9GrqYcgZ9^gV^ zC5ak(yuocWdi%C&`t9?C0bXacxepbc7GEuNt()asFM4FZku*4btvKIplEYwU-bVL9 z@7-nGgEZC~dvKpFmh-8$n6A6+5pr>>2mvEAXcv>t35VnI)Z%WvYmcXby_ReZpDei8 zfzw9fYm!&$uXwpgFbE^2*Y!Dq(fB^|GD;`&MZLv#dJm4(trRP1o9;x} z8mQRke(IXay}dlw^zK;6{ugGGvv8OP!mOdX5w**vP^+(tWG%b(S4SXyIj%8~>h9sfl4IbBPwSvCwJIH`OW>4^}G~YG0id{`_yMMU)Vyt*jm}`b4qxpvJ5$ zP2t|THK%;7ILA@6DUOFRCv5##IKXo2htp*$)RCpXuAfZp}}ac*iSyaGIyuhBb1%8Z(Zx{=&|i7=7)A&M9}Uww|oP zlxdqLKBX{XNI>&xw6@w*XJzi=uiYO9BsMKYsYzyK=^G8m6n(OAk15)M7c^atTauS)WgJOR1*VXc%eL)C|j5SJKdPq`jDwGxV;`6VYDCVJdBl za&qlg;l8v=Gk$mrX9WJLXSww+0ZRh+@7M=M6FOF>$>EH)V#Pajto2gmf(ANzatAIZ zPgi~h8Gq1LKgSK-mab`QHu~};2Ht6aOt~EASB&kR95udWsnJ4VGD}r*x2wk?^rCFLVbt?t> zC^TG85r&^@>{u9@d8*nM#1^%NPS?i6*Re62?}lCfPRF41EkgpY+ zFY!MjBZPm_{Iw(~-$JzeN~nkOmJp!-!0)fm_IwEb%T^;4!Fv6{8R~V$QFUo<$Gs?J zC<^em!@wypqZsE?zW`k?7~O#k9a6e`Z4}wh3G5kTGa(H`=Ci{luG`+fw_%ntk8#6H z;zArQw!PtS)j4bD1Z-FFx)^JpT&PoaXQXN)wq59oo7Yjf=ttz`z7cM>Me+o2|G@{c zm%zR8UN%L^cNtZz!1HxeW0C7f>!KS()z0(?itP>+4H8f=Zp3ad^Ii!bERGS7Vyoa= z4ru~uST8r=N4-AvBy?^~&1CN28F+&%$oHgu>o4o9Lig=OUiDf`P)r5^7N^kc>r=VH zJ%oa84?WP6p}QzcM}0J7Xz*>Nk=^*&*%_huT{qs|!XI2Eg!y&e7Brkmfo{$lW7%nI z`uvYs`z&IFxQ%C37s$pZlq}cVl(QLk{!c(%B_Y1s44UX8%*2@6&13ce$C}$?rwloV z>`O8^-9QOL3eU&XbRrg(GdD)>wdI-ckXj#ko%`|&{oec_R!^ST`l+bsI$6g0k;SOB zsob)orCAOORzF6dS(j^^V9RzNyk{=03n%a+a867}84hb!GP`8Bw`=dUbBRqg2PkAH z3NsD6`2UVpjOXH25(`CAUY)_13FqL39glm+E%r30Rw(E_J9I^I>awUR`3GD05;Sp7 zm|jcfsu}{4;Fe$!WVg}+i;pO@rw*tT2pD-Lb&*r36bT4=Vi`-CpxOTK?oiCq5X6)9 zMm8PUk1VTd5xppZSg=xsS1nLXP+xv@eTlC!5xw_%%zx7_sWG*`Y~oGRLQ#V&+S?)m z|Cu`qDwqzT`-ciX?nZm>>}La^OH-CLcs5@a|Kv%td9XeA(nF2`>y1Y}bt?`l>H+Y< zU8{q?DzH23^-wm z*oz<6rb4Vz;AFCO#N9S3`a+N#zFx#v(%0TVT~Mg8KP2n)8$BQb-nRw!re#7fL4aIs zXG`X{Sgg_Wru-zA2Ghc@9xVyYD5?3FStNPV`mh9+Nvg!xaYxmeTC$SJ%+a`6L(eW% zYJM*T_kM^wYT%is$*<{3n{VHp)0zvitEzAY$}9MqT-spS7~P#_EeX}8P&zB6e7jtH zs2M4#c#*=oj;m{vcoH>+TB3aLPmHir_q%tl8?}xMZGZ&tG5$&)Q=z*ZRubE?holk{ zqqcEqmC{dIZqw?=I}L(Cny0YSDDh^6t3+#!LuiOwVgXF4nsI%K{Z2R+=e^s_u#9EU5CqnC~!5L6UIMS4L4360sWhb?W3{t_f@C*V3`_sBuRd&a89}|voV=_9{ zaCtk%!xXEja<8Z8V8DCkMAs5C>mM=IsOvPC3$<$9yAbBft4|-}Z0{jT2c#HRZyp>? zCRN2PzTHWl1LR=Ao=HzW7GvhxWHV$2#F=dUWnrOVPO-Jq*82gz#9sy8SWS5%y`EU&=+JxRyI{TP;ax7;2{%%w zcT>NwA{dCa(6FJeAX8niW6<3LN_vRkyaDE8xC3ZpE~7 zG%o>Oqp6tkvV*$#jqMSf9VZa7sn4Oxw0>gc34E?1`s}$n7(7D zTc}xWT5dYEm=8DCfMWQR_oe6dF7Cx4I2NE z{9Wm~T;i6mCYYj-}&5FDUmmne}_azp_iQ~aXPR0qO%XELRVLsmrjen3c{@&KM(7ID9<7KW)7u>Wc9!R( z^7Cl4g&EGc0^WnIiOvMe>p*i2>JFnQq#Md~BM-Jret-cxdd`4SI&N>9f_h;~1imgs z+9$&eCb#kQh}C+tYz49lRkD1l*~$@QJUYM;OH%4N>{PgTQTMbU=<1Ld-lM-Ss|AU` z=&;!UnA3fupe9#=x9Iwdm(twN;2^8T30r7mQKnI{r2I- zP@%r7lnNh~v*5;ntCYAw+jdsgX4xa*TqBw)+Qq@9!JXLNc0e#Z-U@-)HlmrH*-1-%2; zMzQIZi2Ce+-6ysl?goga%U5!I2AaYDrHyp3oRFv3(&ML|^t>?}0^fuKKmD?j$6Tau z5tW}WoJVJ{J;cNeuzZRql7$C@VwkUv1r7@2iHvIvNR^DIa8AM~i&$ zF-Sb4I;?jMY))eJ$l*1c8Uq^h($Yv&_5fcVtp=r)*SzB#;B1%DkBfn!lhZ>GthZ_>UAtIWDb4bBwE|az|mrsusM!hq}dhHoDg2@Ge=FaF;X%B885G>IOIR2WoZoS6y5h1wBW_k-AcnJ1z7D|!)^9r!rZ^>)(q7> z5_RPqv+(nnbgf;GVtL+CR}CXiIS~I0Xp@V**3vZfoOUo64(PvJvR6UpcQWI5)fgGj zHRIhq7xhEfJ=tPb)i2Mn6yuE&HsGgdtU~sBh59wUgDX*%g zl|FEYJsp5cf4@3jJpsOiZ` zwlA2)CYO~-H+B~yuh01M0)69|JLp!tQImsBkSN!G?Re~9>FQQWmfDs>po%l#g~~%(_yM%5!_e(ZV*~58PP5X)M|pzBCS1Lq;P? ze;>$FI)~d`5XRwLr)ad+MS2>sl=3k^boEuOQM`s4$y-k59`2ck^^qWAJ4OX|7#%6e zFk?-vM~WAUSaOgS$>1lOV8OMIZJY1p0a&+ISx6)F~$D%hYFYE z00js#h8{m>gjeXFs~|?>F_ONTS8d-52lO*ZjRCoCC_Mxj^V35wiOz+^}Q1g}Z4HbrS$L$@B576*beS-fCg>i&a8~RzMxqfML>QL#@ zD~wi%Q#oHprT}b$>x(?cAglbz(v0s+R`-@qQs2Lyx8V)ssw>NyrJSU+1WkxMs)Bk3 zwEGlo@38s%qMQjOK?nYgtdC?SrbPju*i@4`AyII5MHtnl1CJj;7$iyQ^ef3ZLI7^x zgX7m+Oz~7`+jJXi9eV&-tnrw2l^A&hI#J`8C?xsen>4EKot;rENVZYZ zNpkZ;!s-8SAgO?jsEc))bQv(Ffl%Qq{066H~S;z2!aD_3jFbq~o{T7wWFd{slIi1c%A!Kr5kh|t*@)+5g)ZAxD2kGkeU7HMh`E}eRiZhuG18nWG#@z zE#?~j$?V@vomun}W!sTcW&R8GMZo2TV{&_Lq4Tb|i8UB%JMQ>o^i8*m%m{P#Az+F( zo!v6jN|fSWb#i3zN-morb4N?&BMR_7>Ie$%Kl(xsg0UY8v=Re7sZ-((X;Yo#@NO@F z1v-fju~HG=33xqbl6hsh#VV&l_RkPjwVZp0=fEiQBp9ZGy~{i3ZnMgRxhwToN<8cc`bqmoaNZ8t995`Lq^MKWC?+jJJ5f!z!5aTiW%BfnMc()?hbF_cC#%rr>I`u+9%8*M(664m7hl-M!(#PwAvq?04Gt1ZF{b;13ojSTg+dHVX5#H+apkgB-)eS;iUtUd=+V)a3?Ek!~2j5rkCye&+9A;*qUCHLNnGy#C!^Wrboc+0w zN8lpZ%7^GX^6X)GhaCK7Gx8jT4T`R}Lx+7QC<)y?fG=*Qw%hEJ5f6<}rR&gg$%^`Z zQ+U&B?9zn+&&E4X4{3iZ9nre~kPN z_yIBgRT>A{i!mQCNsQ}05rD{6j*~tf>0-4jNBxdt==*3zJ7zjIgZYix4wcMp!=|M) zKGov<>iJu4QU|T6BUc0>Z(N=X?&GAfGc*49y_Kxu{#-)LOs1ie=o=0!Rq zjPkr5NW47{N#|-PiaKCumwUy3`1zg*wn|$TDX>Kt6k&kyRlsKCgYC}*?GRq){7Nh?~!#NYPcTaT#X zM>Sf_&amvOf4s)54?!yUQtYXl3tvvI6XEfC%_749b;9z05}%9a^5AAE1zA>G6mEh-(6zeDp+ zgB57Lw+nplW; z|CDOqF7`#1Qr4UljCVS?65&J?D!*#P#ejI!r2OlnsScLm3q6l=TXc``TX4ydGx~kQ zCs`%-TGi6MBtBBTMZ!KePj>0a1*;7i={zG8xzWJz7CBS-#yR3+hT?R6sr-_DCUxZ> zXnt+6gI3_3*hu5MHeOk3s&W{g2#>&!I@egaxJ$rCl(T!w4n?toTI6#XhJFt*xbyU@ zKF>vXUaLgnk>4?s4{F}|PnBOLngpANU>NZQJCD0_&_6p=8gTJzu;)$F3{Ko(H_bIu z_{il9a9IJkhJ3cID$I3}gAV|4vx%TvJ8e5Oa3D+e;+%6Vj z_!07d&l*iQ+;6dHj&TL8QSEL9IGucCP%9OwP(>!2o08CVppqNH+N`i)gwjqb05YUv zUS}y1Uv6dpE-j%lBk!5JooC%gB28K_JA&R6GN)Pja|^p(ZH7}P0~$Z}zQUIJa#V{? z^>zH2d8WSC0w(?BaU&hv`f&*N3-U}L?G?NXaVAc~T2Dyg>FH1QiaVkSI@%GBER8;- ze}XksB$)Q93X`x;-ug}W6{oxiFZ;6&e{r)>@)ediWi3ltJnOj`mN_p~`2imMr2Tn~ z5u_bu4YG!Ryp8QC+AUU;W8SZq0bYc)zojUC&s4#e=s1~)rIZ#$hR-{`6ZO*{je__b zK?ASMbo;=gTEP(%JEAHB@7(|ZNyCpt1e@(HLgT*!j&=Zm(1#t-)h$Qy=yZCx8ze=r{eyFh7u(58VxDTs)$Jvh* zN!^gQm9ItZNudjXhgpN_E1;!F^m(l}eA<@bi{R-Q1ZjS#VAzZZx=E*{YE!5SO;GzHRm?W&+RyPN#2VQl;7#PsXFP>@CW zFw>Fo8!;e|+J=GDjvIZ|*qngYR8m8^mu3!KcbllEy!@%i(zL7hql=g}I+g%Ru2Q1C zCHHnefEAi7xJ*(RDcf~SPgC=_r{h`PG!Wl+w`UL+@FsQS*3>3+?wQ)!+O)I$H0{tm zHItH~-lC@`*);#|Nr;K^WF=p{Z*1%Ml!t=SRNm`MW{0(EyZ2cE19A%IUs_T`*p}&c zWmZ{^ABseQGhW)nsyRYcO~wD+JJU5fe}&>YsuVxfQLv3ydG#8Ga!Pp!aE`z~ zoOy1sB7JV%6r7Mw9Q9DQ0d5L1&aC$5WwUOY&k?AR3;Yb1Nqp0ZXUw9sv6S=Stq)c_ zcRPJVZTN6nWWOLj`aB7jQp5#9$cv-hqUQ7YgZY1?XA0pTdeclKHA-v>zc&%}8+|#z)K$ z7?I99UJ>3(oAl|xvd320Lq~xcF}p<_`ve`n7GlHnY9O+7P(V#x=M7krKfrVoGJK<4 zAN@1pO{LkL`ah45OyoY9Nh@sJ!`$z!jTa zTx4JmyHG#BQ9r&IuR^WTDZ7ugEHd)9?Yik<-YqsbOgO?Sx{W`8MYhkoON2L3fOucl z3cFejYX4L)xT6EtEyvm=bLMc(~9VdJ+Qq-=#xsmW4 z*_%^9q=SEwIT7K+r%TKLcr27FIdo*(^V>x>1Vx0ZopE}@q%N4pqj3C$^&T{uY#5F+ zqhfo)k-*X)@9TMePUCrqfc9bhw7|8ZUNKIbTCoSe`_cj`ysK&6ouY!LpLl9&F&+npm_sos z1%GCD49ZgZnkp(AX?a=5f7S+S5#w;Cw0`j4aeT$2j3G!UV-a+aI z>RDA(C`|YaiY)TtjP7-s6fYyL0wgSF0lPbueK`npN;v>-)bVUiOpL^oMIWP=}F`si_-i)A4(`2Qql z7^O&8>NT?2;RVQ})1mSX;}Ty#*aATbkW$<5<; zW4D^a0y7k7@N3A6)bj3C5(sP$;2phj$;jN$G`c@t5?eFMR9EKnr?6gn`of2X@AW7_ zye-l96Xc-grM;QkU2F&?0+^F;yV|yzLYj+;*$?x9pVUm7n;9eP1!SQ-0Kb<*2fA!< zoB%lY-q+A6pbbgR%JJ`?f_7NGKU=1T{JBxjJ`VOb!V@M{d}-Xv({Gc+hXi z<5G~8Q&e|?ZeQC*fmc@(F{(qK5cwOTBUq>|i9xUt97#m_`7d_!0-d|B`Qe#`Mz?I( z(6y69L1hi~`3EAjRyJd@P_mTAsw+xwTq)`{`p{U!)^hZ_wL`NAp>nSM7D(#FU#$4l z4!SW;zQRik@mtBfTO%Oz(sf%Ec;*`K9pa(i4Lz1g19xrd~)g2R4_B(tk_e@y<0 zU;JxLt~_weOTZ`nIpwa%v<&lVfbLVtNuTx_)XuH>LYhY9FZ8?Y{%MvgjzXTdn?kO_ z_=d~k8c+|1@gvlVTHu9W#idoV#`=!-zUDF>sX4Fv9j9vXx4Kn-2O>V4hGcP#5AROa z;#6t!?R)<1?X{u9b_Al;Qi1ms!E<67)&`)x!p9T}+fo{Cp{Sx;_)CQIt$k06UJWxJ zo`bOzW~HsSZUb=*#mB$_w1+Q8q%17##!H6u?eu?QTS&)B+~cJ9Y(qDg187vlC){4q zgO5J!P-i((zxpT+< za<4KHpApBX2chyU5jt6__YuafKoM1vNZ`wZ8=ZzPNRYtjIwnbrapOZFpsYIn^fVv- zoRUyn7Q7!8r9sf9>jIVQQQ*$s$ZgBt?UnsO~a?U`r1!7QNzNc8WUnEEdr{(mg^|Nm6&fjZs}!-}09=xx$EQ4h2~5Le=1 zKNbK*+qg$PFD#v9Z)6sHIi2bmjYf0?g!&_9x%6h_2F)0yO%Dq++lUWopPy(=J5!1; zA*`_-EW#oe7KjV{Icshg)cm7L92;CUGCvx>RF>az{_2r=Za936%@u>nQrMJ<_AWR9 zm993sV+I{$3uPZ0B?bWqi95h(UzQ0zTtFjVSzqr(Mc^u3}xX3zE@?u}an>5^4u8+hQEVz4UoLmebELC&p0xB!M{pSqf zqPLK9r368WP_(+tdbHy>xEkHhCc}ZLe=V1ZqrGl|s~R$AKe;S%^I^uTL=Ui`Zc)p+ z#O-BHC}N57Eme5%fLFpMl}kcsCzba#OnmEA!=s$tFj#;31_4Bv9V2*2HCURcU1|Ci%)_2$&pfxT^BGH4#7Gzq$nU@~NBe`J%*eSx z;Tu2a?@M{Flwsh!l|qmNdkA4bE}=rRIx~15H!5nR6iviF8|noUpFx=|DV^`G(foKh za2af`bu)===DT`k!FnqJ8HD4#5z2wR<;RS*h##RtEXV9-E|6 z;Dhb`_?Jpm`<&aa6Dv0h8l5TUg+d-HlUyN0h-1rHg4N#6+BH9vj)fN*O%PC|uJR{_ zZCV-U5@Xa_?ZvnOykzsA(P`(_2i-1*j=CZCiW9aXuao<3IrxDNU-( z6~A7~7SPlSjOct?A&y$7aJ$VehHgbxfNYx3;9Yn=Yo!Rr^G&hFcmj`Zf74_e9G9`= zkN0-wiok!RkA_ZdFPA?e5#`P`sLf=ZmyyRPooRA()Ea8iY5$?=n*_fxLD1;U&_@okwX?1Nzl)1||9PKq4-VG&5yF{mq z21F^d+r(jH1;%CYPY)ANn%1|DjYd>Vlq<*Fgp@53sUe~-&VNJAN9fB}o+O;;_8!Do}6O95}e69nKhKr@)hn=!?J59l%WL+}fvT-_@%91J5~X`=Nb zhZBFaexAtyGX+&MjaJ}^-_+y#Z_q5!#al7}obO=p7%ll7Ip(b0m4Pe@PJpz5bophy z#3%12F(tEdd;T~H+Aqi{%{A<~gp5wcJH=aS9XcmXY&4V#v)4cKhDQpc=aAN#BPb1G zoGr8@;&xk=DI@kRd&61wXn5YgUugOUWFKS&)E=M#9>~`}3qu8(Wd{@ZVoyxg^zUgrs?OjwxzPF1+_-9I6M>XQ%ET~4? zj&Jy}eH%o!a@!}>0ggFg9M7$(7X(Jlz1QS6cly@GFIY6p=v_unI<}QijahY|&ql-S>mj=inoWu0t z#)V|;LWHZ?5(W_CFwe-gxWzGf61v$d=*}{iO?(?v&xAa6LQB&U$NigG1}bs zJX^Cv@nAR7Vr`CQSg2d4E|>{oA(PRhdZ=ZTGFf+wx$2g{AXSlRL($&y!~N94v~F1d!xjai2(XkC)8&|2IftwyFV1^VQf%}APP?J${%^&+(f6e?^6vWKl?X8 zTRpgy21kufrZ}Hyo6l2$sFACyg5|s}vGYsvjD^mJamCc|pz>>${gouKhR8h1y$#o* zcy*XPr_m!sQ2x0it!mVhOFGwl2@{AyE+2RlIg(_%q13v{oD+VZkW6`mZ;5(&i7%@) z8aq+K)WFR)p-#Qu5?!|YiHpZv|CbKV(e@lux_w5KL-)dTDPdC{i<}uKsdh!v05lM` zOm3-Uac!+FshpGLgev1(t|+_cqq-z?ZUM7cFUnP&-jFQ1(>XHX@FJJF7J)ToHdz|W zSDwC~h14q4A(T1D>VnMk@F|Wrwz^IHjR$u5Z%A$EtfISQy%@&h6Sd3~EP(i)K>NZ_ zHFgdCl#mCxc~KOToD8Y7TxmOgbW2o=)^?TZB}-Qb{bJx{dhgUH#bmPG9jj3%7>Y)c`)4;sDCB|XfWj76bWyrf4$#Pb>j@qv4H2X#ZmqiamliII$e!{*0%O{KOIFk;12sg&2q914eX*{oZ{A{9P;p0RVQ3* zZ_wDHXoW9VV3Bi3i+XsHVSAoTn6lH!ctq7nSkq+U|FN86Hg;VT_e*SEwV^t-kdOJt zf3oo~E!T*rm2fVIvSswo&QUpi*Z?ALt47LA2e|(z`grc!-yX>uYJu!c?imnx2APGa zuOH~4-4=74$^5>XsGlfi*TGy5L&_*nXxxKJGv+%|{5C|uAQAO5p{$^j+A*x|tmvSV zWX=vDDs~|Ar8ima5YDL@a|L&FEF%9IH@EfHY``RT^Y<6mRySZz^`P?58VF$>`;<%h zYhgrb1joj{L)Z;a3VmUN=0iyQLSfUVfu;jq9Fj2yFEC=L^H5BW=rw!?sh7ebBhg>> zHOwFs5mL)(jhyO#6TS>rk9d3*HfqBCFT|=a;ADJNqmvUK3N0?%m8QH?Q zW#U_+cRBB4v#7YaSR`;aUGZ3@f<&oL$n{qx&%><<@qDJ--UO)X%*C)Eh&)T)suq9O z$;^Qf`JS)Pg+VmdL84VG!8^&poSl{XPS_Dd{^X>=2 zxBU?Q*vjVT>0!B-CQKDZo~)WVtezl%NFN&+U79L>yxb(#UmnFYVWRw2QiPYXJ!U+D z?{3)#1!RQhL*kA<4zlJ}lHx%?$QmE4{aJ4A=NG9ki3E_?RCs`wMR)+hJ+R`?Pg zG>~So>ymPHen}>Dg(D|Nl*Z;CjH7R-CvK+6#(o?_Mu5v;qU^``5%?Sv%-H@-9YfTi zh^SJ!#VFTZ()~LD1?W@AGSAP}VeFn^%+979AoWSMk41r)Yi>CV|8qc4*b^1blS25~ zING;}=13P)9M#+pf9n1qEeK=BxXr8D{3x0_RA z$|J^{FAv8-t+v{yJPU}0<1r|=vm5ovSSulx2iVd-=w1f$VQlgy6x0{&9y|rd*r|Sz-`^USa%jcTtVt@-g zoY?hbStAHjWlHRZ*p1&8nG7HJ<~J zDc8%UQK)RZVDB%u-jA~Y>{+AP0;iD?$L&n}2I&^cr{LG*W5A#9}g@fLz?Ag@N^L`g95Hrt<^+6%kNM>CB?s~xY zn5?-PTN{;6M1oE#e;;Gi2DfWzlDqF>L^w0ti`R>H3egM zJ2>D?LdLBOTS6Z_@;R@4LoEZeEX-?znd#n@#Km4!!34!)s_hFk=B%y zLkz4V#|INtgQh|Bj#-ho`FW>j-hi~UJKzP0=?#8>-w?`yM+@gf8~WH9oC4_u9_|`6 zYVH`&rn|eY4C*0K5joa4;GC#_N1k-FwYg`&eV~GBAHpT67N{ZFz}egVZQCR%PuB(Y zWm#MiPPRZ|5=EOg!tqnH!QC-Mf~2zC#@v!rDGo#F=up|}2y?~Y&qGI7&*egwR>2Ij zinNi0NASEn4f=-y4G5DR_tWClZ(y&ZY}Dt9CWA_7F4&r}6})312T7ct$04}wwzaOz zPA^k-xWUop+X)$jNJpoCozA70%r{JjK@7>iHFjFiuwz<4AG5GxYh<7T7ccBNS!{I3 z=8Ug41GyY7?hZ_S-!|NDe;_VYySPp!x36ZnNX9?=ZCCV&H)NMb&Jy52VC`A)duv+^ z>H|4a#-HopN)zNsS7?*1fHCn=9EY9a-k4=9SttZ5NZWcY^o@#YfZKW72R9hbeU(wQ4DIao-55xg^2 zFA4-s^>ZOuSQCWDa~{fr{_Wh-rkPx#g=n9D5c7op<4{Cin*VaMpP&y4cuT7+IVoX~ z3g-B@^I;$3Z>t{8X{VafCcBVZE_${#N{xVjEoPGSM5m2&D2!N$27lcq?3r_jQ7+<1 zw>Flay-ztN=T3M<`t5{Wi-$u*juA#{IFDXYGxvlFa`+i{z?Xs*oR!8|o9C>yNYK1wO=KBX79*>&R{RYFRj2(==jK7$&c zhDn;_0|jzDW4gF)TK^9qA;yO)Jk7%>>UtO`%#DLQ2`=f|>P=JnTJ5B-@T)GKWc@5) zWvRQ>hhUHvqV`_tYWJ#nAM@DLYa+)RM3aHy(y*<*@bq+EoTZ~-qGUm4d;s^j(r9$1-hrb26|1a7=@AzM|LBcH3lj$w_*hRr~7saNg zQC;H(c<< zD416z&ufYYLDOtzi_n8B9Eh2R*=w}VP5wf&dw(ETL@pY?W`c|1K)nAXn23ZU)<6HC z$C)U*h_||vl;|Ai!%JGDM&4?*z)4Eu8yX+{^gRu%Wmc27DLzZ{G*CaMhkn!3AC_3* zkg3wYFtvf24LrZ>@CvUsNv$$lqtFx&DtO$Ju`Zx?I7E=Ulrn?J>R(N0kfRBC9m zP_N{!r(Hv3awbcPl;mhyUUY-X4@4E4Y-@T2H6-vO_-jH*firTOG`b-3;fueYNOrb5S>;ZtWOuo`nO~;2vH52cW6aJa!6NnxQ>n;oH2noS$!M`6cISJJ;- zOw8EKa5Go$s4qaOG;;_y6QNh$_-3R0+bXSQXR1sNn2G}aC=?0>aZ9wQ_BT40ZrsBO z3Q^sekq%iy{mv%mx!JnaCf`RC{$GrJWmKHY((X=>1cHR%9^7?s7zple!QI^*k`UZ| zaCdiy;4;AA?(RCcUG_fve0P0o-5+;;&3dK#?OxT@Rn=9`Gh%pKl+APaHCu17h%pC*g=C#Sa9Mfrd z;WV4eSm4vQl#{;|&);#M{|y~=v!)Q>t~?;PWIfU0t%xNZrCrO**=2fZye!3OXyziE zXye|!rR78;!>{XBRw=19?M9*j!FO~W|5i={#AkfrMy@SWML1NU9P;(#wE8)-U5w;3 zD%v`1!V*8XHyGNCgd7W~Qxsn=Cz_m;e2y>Mbaky4a75wt`Qtr_A%)2}T3s+h{%%{; zDoCoDBUP#pmJbsM;np%U3Gk8018wZPa* zq-!m6l1+yhJ?Bx6jmb3N;5UN1G^YSB;n{nn8s6HCG73OWW?fWsfDwlYCHf-N@JD=y zlc-tQE`5P~gM2uB23x1EE9dM;N?)d{$;UB874*ghs;=$Z>Nhe}d%k68voRi%TPqDjuE2$$fO86{ps zRO*E^uJa+}N%J4y-Xf@<5p6mhKOx_<^B?3bB@Yg>Y-zcaO6}g5+f3Y*9QhRA<9{XX z%bcL9pS-5Y#~#N9;<@F=%eyf&+LP9w^ggbUsArk3J#R%i8gDiif(Hs^F>z5KxzBqw zGHJbEGZUzz@Ne$*vj%N%>O`*56x5tksWy#>X$|W7hM(Dmp?AwN)Z(!33o9RZUD(|= zid0#$0QegbD=7!oh}C@Vi8p?hUPl`bjrzGS>m}wCizz5O0NpN-(%O=9MCsR$Y8Ls9 zfRDtSj9oYM9<-MZ&dYy!yxE@P^e139G7Tgf51^;D^|=naoc;m;1vko6h|C?+1N z@_trRZEP+Yw5PON{9zZ=)SNEW!bU-@+areZ*wQw~KIBGExlF`EFF5if*n|GN{Dk)0 z*EztL!To{1-)NrMlPMYUtEQgK0pW<9&>&=($-#qALaDMv!rhj<0!D}aaGdjD29D<` z_NpPd!G2bB?q>=zFsO=zGAk(vIRsC~^+xWy?qOm8zHr>xP67tH+%0iNw<}QY8aM4L zr6eKwWvO)PgtMfviPVuU0?(4&S&C96(aM_*(z_?7DWUKI_mG)~GdyzQ@rK=l@fiX3 z*ICdT!SXwoFe^KL&LFqvu8b#lD6-5Qdq(uVBG;0Y=vu)`h~1@y_;l%;o8wLVzXA%h ze7tM{tTv`fZ7cLQkh5P_V(7NwmW_nSD1`wUJg2_{4R5T`dh~AeL3U)0w^L&#@fG)2 zx^7&78ttli5TzeJjePd?3U2R1NNbzfeSi8=1F2%WC@Kt=Yo>G)#a*(70;5vSFXs&E zz_2THOILeNfHop+N~>{r*7#=8;4^}LOmJ^yBY$lFhTxa;EJMu8NJc611a9Lye8_M0 z&e87O#=6FWWoqtV?+D-!^FuExv77kcXRxnt2&s}GgQ+S@T4{6dh_^Pkxe-vKI9c+t z>FNtTomf`Iv9(}&EcEkqqPQHwlih?5Qt?OV7e8-zA_PF_XIC=7C38|O+))X~5&2>D z+;pq(Vry-BP5?XHCwRS_ws&nhs+pHdr&WB?T)QR(R~P!Ov^<`dLiawXobEm5ZEv)P zrZ2vZ>cfd_g43UDRcu9!AAU6vEdEA<>tL|_{DxjyytTv}o#r>wzy%)=cD@c7Xwu>J zw`1{o%5m%sNgnrFE?PiT?J|wmW|s>38^-dD(jMjQRQc=Xu_e!Svi$Z!mvKpLXcUQH zmUm=GNQmj<(z(6lvT?!0i)WGMKs{d_+nlXi@@|i!_?zW1XrKQpRGG+wb#1eX(at-NZ{p?Xyd*iAZ6;x>f*7UfkXeWqAJU!OK`WW^ zWLC!@kw7(XwH--;iJUizm^62-fMb;Cm0 zrgB9(o_~OaI9gDhH?-WEl=&)Zw?+}Cs2#QnjE`|pEB^);%9drPsDQ}U%luP$5d4P1 zfH4lv@K0jOWiH|mIxv~FBtvf;k!T`Lf#lUjk;HMNRhhsSczu|f>rYMOt;u>}yJ-X) zgaaDC(kd}{Dq#bX8Ak7leiJxiB0i5SN+cr)6E*BevU;c>2FEa!)YYxGUG>eYJyOJ9 z592R#^-*EC*#jap6ANO=3bmV)LnJsjzT_|HLdyzMb!aEnaQXq);K81;(uA#WEnLU;EI;v*$q!*S)djT~JS!S`ONQ zzuukw>xmh^lxtcjm-0?yGncDwe+iEp4X;T`{AL@aPLhq5q@70C1&=oq2k`O;g+rWI zx6wRkX6yjgR#T!O8<6*Y@JF#u;5@m3*KW3Y4KfGj>}ML9{4{i}jrM&UkJ99;%Myh9 zCEkK67>4^a`O94?uSs#wi@s{K0<&GJDhsHK?myW#UwdVS2R-f-mk?`D1fxwoxS0*K z22+2Wr0fJlkt_x~evn{BQdqU$oCMO}1Smu@MO|;1WZX zjuX(VUwCo=Nb*0XiW|bBLwJ^n%g zi1`@`f8Y2|mv1FpTpb-97z~Q+RF7G zSmuAe@$H@SR|yG;j{}i}xeiP19E&Y=g&Y3b=xY2s{SA18k+6=NX(uO9M#JuGNEBR#VR_y3#1 z^56L(4mMBw2jAm=n!NiN+@H+$#rqC+rm+1hsc+s$w5PHrYjyal+e*^#84+;lK?!>M z03D`_Y9#q}gb%6R2N9#{`B6@e!?xzQI-lsomvDsmC|v5F_%5yuLr$9msuQm`bJn3< zqD`qU-2tJFrsd0nVYJV8z_Yo8uZCx;Hjsr1+)yQov zrRlkR?nQ4a^Fn#(zUPw#flBfRhIE!!tWQ7Hi#mG4G*?=fM_4zw^UrzZ12AvR7ux~; z48FbhiDK~(+zxXxR9Yl`b;T*Wj7b?XCOpX_O$wTf%`+h!E6!1~4Al=6>Z30@ zqC*fz!hfZ$2rU9&L2guDqFqdZFt(&_&I~1tNSZ6u%5cBrxI|XgOkcNYS2Aut=s6JI zD5}}Zd&S|z+kKFW;A9n+YAEksY`AdsIw7s+CEB=dS*!!UxH$5Xa)tl-$c+oYH+sVU zT}nG0=E1K9J+l(s?rEn_O4_VinIm+Xe!NmycnMi+nK3?PC9Vh*nn1FEyv`m`1{p_M z<1YLTOliQulxM8WpHJ~OCYp@?Lgc6KH=3xtLbpNSQ#P!Rn!>>Q)8QoJDdv#~dG~Bj z8A`4oahx=RGrdU1ARvHQC}6k)tZ-Shh2}(b%#8X`x7aaQe8OOzEiSTuhl{v$6b!3 zUppAiMKW3moWxgi1%l2!BT0WANBDdb>rvM>D$T@j_h{+MOy#>d8WkGWT7pbsTvcWj zcW4$AI1jg1PGuEjHhpSYR;Zq-P0IfSxL?OR3bvVaUna=-5Z?m#irBAk^OJ%+o|h(t zols~z?)Ts4%B^khw|>rhU#OA)Fyhz{ZlkXZtDQ4k!>eNPJuM3#d*OvOS^>r?u;H+m zI<-!RKu}k!ddWxLb2>iyrZdYgCop+>4EbQgV?M`)9#KW|9a#!HT~d{S7-sL;5q2%V zH0EKDXU%CfG0A}=piB`RenE;ug&5S}h`Y7cn;<$Psh;&J@|G=0OG#N#VB`w}3Twa%KUgWdKUo!p)sMw*-tN67KKZ?)zJg-OEzWWsN01ZwK zimHVw{`Gwx&`=akQ$HhF85KTzv7xs1$ z@4tAB-Y*pjamWE{*OLwxa^NIkb%_RW9mi7f4JhLobbcy9P#p&===O%q1dSLkVczPK z^b6+DiM(0J^)kN56l=xc9bR4W>VEiFL%-1rJM6aRkPedbUSVMvhhscALt)v)mcQ-= zPGUSpQV=@azh@U0AeSiaCRg|EFDsWksk8TmRnXHEnn%_QtMIN^Xk*5`T!n&Uq-e^+lqx?UNU80#=Q z3{|b>P-3c(7$eXWio+fwI9pC6a)~WCzgm@>AY*P7*Rq|N#Q5wsR-U&k#Y+^mER?{LD@#Ao(bgLn_R0xxINn2DkVeuLc#JaXZeQ76p(=Fw`5VTb?x}qqN(+-v z60a|Vf?X_=kOr*#L5Y1jm7kApT0p~E!*2|=>cENIqi{HYqV2^#sQ zF&Gy=h&o?~f`)-y%axJ4x6Il)8Q8Tf4cQc)lhyn!H5tRVhz>O;OxmRt^^ZF*ne*jb zgMsf{ievk){;9}+vnSUA&C~8H1_xvN$Zy^)4Sq*m*rVnz?Ksm#(g8ajifD|s48IZq zwQTkd^LC#!AFMn}_Z3~VwQPM$(I&@e>jvEkswTJ5ibH zMqE$ANeKV7L~R75!`fS4q*l#UZ;crp5@n^k$_LRQ5%dpExh0}X#@_9XL|ia@4!-mQ z6N;*7YKiMH4bM&XR0<@NHs<^Eciw$2bniFKWVW287t!`I!+2EY=gJ+g3hol^x(Fxs}wg$^1Y&a0(RHVzdfAJvX};77>LXAre`V_ zLpoU+kq>5y^LDjEBYVN}k+sTdqt_(|*%$fDpS0=g+X?cFc-Ehzp#fS7EH_lN>;jl+ z&^K-@Bj7GJo8%>eT*{$pgtP3c!xhbam|8BB^9JSVa$cDy;|*#%9;ziUS{;aOEC;t_ zE{sTMbh4EK!aOgVQeFFw?ng&GeIqC`a$wHNlzv>?OfrG$BZyDhsQy?) zs~xrb?O#`{>>CAErkheaebU78V`i>~hEHO|2N^7TBf^&nCxYO&_5H9x@%%O3$$`94 zrZ1hYa6V%!;Y!r-jXI|J@qr<9xuPz541H#A2}uA~1k8~?hz+Sz{3+IkmzJgfI_dJS zyK_$V`OWwhxu^LpenuMXeH|bnN$}YIaXmvRGTDW)taH;TzVjFD9h@|l-=E2uP;WJ{ zeK^1EZ7ft<(D#XRx&b%EPfzIR9DZI9+-3%JFO)p!Dcnf?>4-y;y{}e7+=oQ2T57b1yQ8_SDCYR&sUq-sS#zuRGDIbIbG8e@-G&$>n>m63Wsb(Iu zB1;m4?IRvVhOUV&g^bE?fW@vQ^6tQ!4Z%cOq=vYRk?ll`##yuUIrhk18quG@d-Occ z!2*EUO(FmHpduUNVVT*%LTz7sK^^?_>v?H^AJoC!*<{w(OwWZAYN|ExTWK|O<@XL}OyUi0OR{ zV-=BS9FTZPKvkYVCS|w8qIAlUO)e`R!aNA5mO8k-gblIvhZ@x5E={@_o+SgKRXBgy9?GkVr(o z?IAe}z0%DyX&z$6_K&^G%fE|)sriqFn8&Bc$~#dKn~&{Z95af|F5~Lm)sTdrx!i6s zHFW4EzqRN>M`{&Ew&}fWm-8jL54JtL!Ztos z%%j;5@>Jsy?V7_&BxPW)Cq06uWi+?ERSw_{?nAzbplXw6KeV^%nELMT{6I^j( z+qjc)dgb4)RM$a~@{-Jh{Y8W}=pwjkMZJB9Ymg5b{RB{=7&6^(3Q_G#zbO)_Y_bWMGSqo#PcTu~LhZ`h%9A@c{D)$lkPt{ZO`1#kxuDEUAc7igtg2 zH6LPL&?^Rt;SIBCgFP@`apWpD>X92cIE-HhAoirOUl0;vGpf|#-iGyaZuHI?$X$@K z8m2C!SW2cz%Fi|A?w9n)YT()6?3NGIPCT(sZ?z&h&NUBx^-|>%8%Q_uSk`oeFes*I z*Ed!2KB|8it4QrIwzo_unv*`<6SJ0z%Q+^}U^{^KkTZo6$9x?YS<%urH-s^To^XYB zthvK_CfcUq;#U3`8Kp6gV`8+9j_UK@R0VmMpkS8}Kz{LG^!i!$i?bZAMEkXw}QcGJj2XUUnMR1(cKf;x754g*p-T{#E68FjZKMrSS5 zji_iVMe{3E3qNH^nb%|iN7YVXLc#HogepMk>e)NYuuLj|KTp(Cs8LJRe>sts0zNHRVFbQPe!Y6ag`YYrj7PP>*Q}3hQq-*OW);p!Li|dqxNql>oXpV#0k77AjB`DC9=z#O+UI9; zf&UHy=`9#|ew*Fad%iQHfr9}=D{uSQ>Du-unErK7?}g5UzR0xqrbUknC~~bF<@DKM z`bQg~{=t;Qq3>33`&v)`D=#9k&v4?zo@*WkvjXe28Z69JLG;Un;o%HW_;E_h+~nB} z#r+}RIo)YO#}8RPaZau$Ym|1iyiB~ymnuIkE6MINm7QERbZs($8f4@HX5|3$$h~T& z<@H=6{x`xXfcno@k}&mzXON62tQs#LhK@Yl!I=%-?n~Wn)FUtzd8Sh2Tg@KlZk5-xexm3YOjZR)<7OlF%d05x6%YDPH)>a}K+4 ziT)IvvbWR5nfl?Cw%`%AyhS<51r}hjia;u@`0z1)Ot!N=f|~1*38ZuMYz+AW9A@?{%=t2sqP~K-JP^ZTc%io0HrTRENFQ%a$Oq2KlF3zjM|H5yI^Lv9P_VTJBQB~_MN{C?tQ*7;%YLV_ zc%&TR_a{2y-`yUH*BD2C>EZQ6+AoOe0x=OBU$M8B@?Y!?I=D}33{?mrIMJMrPVqIGgB9?_FF@zteu62?HqQmj2zfj(3k z=q{zTEwaY*^9rpe;e3i&PF4@I1k>ZNTCqi>%eZ@4;{gZw@}4i^kX$5sW(vH!0uy&| zu_t2|&=(aZNkQOGkF4t|qOQ6rflKP~&7RE59J#zKrL)Xxt~?_0slBpX6F`p#z1)de z?6PvE7TdppZ~s;^FX?Zg_pZj=mVsYA%1vkqsV_FRfR!8k2O4VVV0!sq8*Vq31JVgC zSD}ejFvq?`g1PU-Kw9%grGD?%Zd<><&=B`omyVareog7+GaIsTsA3bxf~HM1COHa7 zThMM3j-BO)`E{c6NkmE3ny@Y01(2jj8mc&J5e`jl20k^AhDzyO+{c=Lsr%IwEWDj8 zOS87we8$%NEk&nJ$4(H$K(g^|3Q|9zw3et5>x0Y`4^p_L14r3!HHfM!bwKe;)DZn4 zAepA*g^w#;RkUQ(v1&ZXZp!SN9j>ajYJ5pamWRfSUWOFUXkH&=KaX8pOi2$QnH<_+ zlhA}3?F3K~WcR^^=naiGD#iel$0*STpvle}Ln8x<)12x9)SyO07U2R2Xpl4C! znIe@X6j8j|A>sW=cpvTX>|DkK=kAfyS9J{aJ(|Hne#PUQd7!l1DaixDA)aJ=T>~z4 z#>OM_`_z`^SSX@Wo9~#Fb&*-zh)a<-X~I2E@d&E4i7rpeNTZ}lh8FGBs8aH4_Y7`a zv!XAS{J``$6or=05Wm)LFZcwmz`G5^->JK81RHMA5XDm6zeBI>82A!a5~~?!J-#al zU3-m$$P~&399%TqvHGpyENhZyZ1I~wopvd(m(G1Y!*PV%5>3VJmCF2&@_ps{Tlt<0 zIx5VQl3j8#aUFZbC^lfSqdE^mP(8}($TBUU=x<>OT;%)#-vna2?z|60^QPe+-=K@+ znIO0GiCj_&^^Q12r_4U-be-+WIl;EYEQ36;pM(pHN)SXZ_AQY^?VOBtl54fg6_9+A zDI$)5*>Mg~;e#Y$sP;^F&D>2*!5W8VK{kxMab8`fJEV^I*|;cN71Zbajak*ejA83n z6q2Zojc_>aw?K&1VBGCde?rWG`8&npFM-$O{)#bKQYk9JF%EiMXB9@BtV8m=n0BXw zchn|hC96q7msb_x^!cjB;j4`{VG`b2BK@YV+qNQO7K+O}C12Ht^=8PwRk(g*MbCGI zT4}m&TU;qSNenF{ShJmF8F&8$RO440pJTN6(#}WgSi0?gFZFXj5X5Xj9F^y28ArF{ zLtYVAM^HKf8}4EaPL>a_PDfg^AH-g{v7eKc0%=KRxOaB53bRE}Ze+SFiC2D2p#9GB zc*y>wI+l_lz=ET;FR`?Y|Gjk^*2k|>u)o)1M@=ai|4lK7(_T$Zn7pXaUNIMsoaC|2 z4OILftVw5b&;JW>eL<^x@s!{^iWSNcvx4^FlQQ(f+PcKrG7mp{DDVpsQa;)JQ*v)m z>{u5X?^fZofJ@9;Xo0iCp{U-6m?7N{mfe*)+ldYyp7E15(rA|%>hInX<&$APO<^GY zS0%s-e4gMUyZZ!EYCHuHaWm*cn^)%{zLKB}3XfWL1DTV9?J!A7y1{iyt$TNUoYF=! z(*PkFpk#x-^s5V7k!SezWyjN@GHTco?qFsqLq77C$Xv7sS8f=_)Af=ykufPJh zVr@@gEf{Mm<4;Kv0T*wm353u6d?@O(s;A@kdSlO?g*pl0p74~`RAf+-_E>@!>-+q| zOK)4mS?%B)IhiPU7>X%7AA{RU`1lc$y$LGJ28skE?u+Cx(K^ZL%(Hp+*&aRI^u1WL zg8_*ky8`{k+R8h633<^oikLfR&R);9aD@ZG=Dt}-S$Sr|@wJ-I#xxJiBF~}INkF)> ztCVKM{Vy{>LPKMKRDTG~gUmebUPj$>Sas;;buL#8S&ISXLoNNSv;#+KvQ_F&DLJXT z;zaPEgqRy33l#9qcT(AXj33Q?R7I*Up(R4)Sq4U9N$k8KG7Ym6SIIjnZJ;ZfJ2N(M zi!@nV@3QtAhS@1~GROGm);Pzf9ojTYn)%DGu{Bu5OHuMQ11W)R8a!g>Rnh#ydFUmj zh2hjrn5sPDn?AZBvTax#9vRdP*0Y61%0>lzNn`0birT`Po(juVhq?PkZH#`_+!c@)uTKCyVkN_g0=W&-QNgO;>&P(v#g1eTdgQ z*1nQv>Q5H#-z7LRYG=M^9aY!Z)(mpR`1rJ;%KD1 zj|1(G-RrDy6X)>m3A^kq%e#$*9gH=%o~D^0bECAr8)!-~!qB-g-7JY>v2dKp7n!8S zoGT)5I$PU0?%q&wSndm;(qoZGNKWf3nedr5w_Fe-3ipW1KlWXSl*5g4gh=P|>V0tD zE2Vz$5Ib5`Pnt2pi|!n=IQ3D9U8dy?pmouoZ`$Pw6qwB$E@?$gbGa47T=6-Vaw8_6 zSoyF9OxgAd-++lyw7HGVP^Ovi>tk)ygZF!QF(#@`och*t9JEGMYH;#xb>^i4iH6NN z4L!?CG&6!WJ<#9?CiuX9%S+afZ&b(-r$K+{(}(I~cLjPHq5NW;-c{b}JOKS5 z>@C@`W>tu?-IC%{>QCQ@s$!Ne>ML}flFoZis4LvBWPvB1-&Irpj9Dt4O(Tp1r-&rS zcI#kQbsoJp%x5mN@08U(!5%Hhi>w26=-h?^KW(L*INu7k;xzc~T+W7J==!AxMzXks z#0;do&E`jv-cEm5v)`XL*Tf)+hd{$*tH)QNFP9uA(xmbVl>d3cj-(6s@2UT1{)5*f zegQT+sf;~O4P`vf{uIp?;#i}-Zg{raa*`ZHp4?F~2u_tng7C2mohCHr$v4@=78_|T zP3FkveElf5<=ebFv(?tMyQ6^-Z|6e!5f1BW*C!V770!`zr}*X>yG)=`ntf9A;l@n| zi1L%h9N(gYGYll6K<1H`O#_&^n=CsHVC$P^uIW8|tSwf!`8Xt{mYNf_9pl00$KZ7Ub?w^rTWFdGbt*qlkK+wwyVQIEhoIBqtdDaY#gFGc~kqD zUnRSm*6bAp-~HZJS(`h7suD7LXs-a*)j?Zm2Ml!HOI7ek2-ecmVRUgrX~DZuBOvYe z?3VL4^F@D(aG`-q=4s|v-M?(;zde8J8z-T?NmIW(Mkj|9WM4#o6Pua%!V+&Wuit7V z4L|uD7CK~=;0|x$uun8Nk zZ$ZEY1JKxVbr<&K%2|VE+LRuUx)+RtH2*rpZz_N1Uv5UUnV*!BmcYZ}=#K7483Gxa zJhxQ+Bo)OkeMb!h9AeF+qhe~b+L*ZM1qDAB)j;)U#@n|m*ij0dat8@V3lsYvft79V zndM?4x5Wf(vHv@ftZx(P$Iaddi7yzxumYKC^p3WSO1_xV=gW)Wj;lJwzJ$>N)>@gz z2s0eVwL@mz2qUm(`cDn%8eBEL^_9`N1I%$zAxRWxF`vF;@{R1U25bVY6g~=IwwD}j z3Cv|;Bi9Q+zbKj_ZdR!)lmX3D8Y~N}$JM zUlQ4VJTUJLO}h}-9_~k_04Yv9wK7S+@`&t#!^7j~6sx+C_wCVx@ z1>@fBW7q5VMG1ObUKZq)-K3ZrS2y`l-FUTM%TMJbev5mCPdBwGUhSsDx;Uv4EEOAW zdF(fVGbQ^rllr<&1KAwrs_Z2{&k)qXLTJk>Tcta_5l{rZ>9i1#EqpgJDo zNwT6Lj7emM(UPh_sM&B>z%DYXp5D6Y+;PB z0GuYN*Ch2w{XDt4y>n}<`T{%o)Er@e!TIqNBER2zbSq@Jg*qH7XA7|-zz*xYinP9l zil#Nds<~FLuijM9SUyL~NqM?-HAr3r^Mt2NHxl$E?%)h-A@dv1p~A z32wf-doW+NP!ZQhzw?no&Je0kX)jtmVK8b@@17kGE98``d32=ZL8**#=>}#d z7RZ)5K=d+4D8)eeYy;GSg?vA1rIRkIo+MhfLr=-1!ABG`)o~es|E>d?zt;gUq3`Qk zzAlEzsBxli>iZxead&0vinRE748BnHu1tCfCFFK0D^jc}b)?NdVOhjexaJ_2wX=b1 zM22g%M`b3%fW*ly7_1X_aYp&3zF#tNu}vrYv^rZcsulDn+zCgD<-M~kEKPIY{lS>5LY)XyxzBC6$f5AG7dhhnO-!H;g4o@3YPuH}p zkKNuSsZXP#FG0#{>Eb7NfF{f*=VV=7c;fH!AFNd0UO1Cu&RwI{hIm|Rq{oVZ<(aeH zf9)QTu75ML)`F`!zfdX}8s~f^(bTmwmn)_SSg3FOppjE4^h(T@!S|K}*_h86*XpxN zY?_b0X;yp&$(OpGs^dMB%B@qX{o5XRjad)>{E7pwlH!y8SPR27UHR4DP`ad}|LJG# zg`Hn`YJ`#$3=MpV^~(Ig1oE|iz;vYxbz=Nag3QIB1RBZ>-$Egzchya}D%!z&;7sqU zSKQb1@}c>K&q?B8MNhR#Bo2bll+iI%LDPZJ!0o9>wC&tZn)@a{7AoM^~G7|MGkNC`HFw)*%uIYVe!yjkp9e zyDUiVY9oXj!ZlxIDS7d$g8Y4i>CQd63RUAg>hy@E=OVuIl5eUf>d}~eBwmG557i!5 zY}?oe;Hx&qc!MqJ0hFfOa{g;2YTAyaQZIdSZI<)#ObjdbMd@q?3q{163r+mQCAL&< z_@$Y2!<8A8f0UQ$1l|W+`C7NZJGh#9I-VRyX~avH3{R%(fPq8mS#X|nYKlzFPbTO> zA1_`--z0(@>smF9j&sW#&8)!1ku-Tt+BUsC(zn?(UJ8F%<`@?Pex^7g<81dz3mGdt(6*kf{dNQH z40s96-G(-SuAJm`F;|A+@^^6pZFR#Ro=Bdg2iMsX99V0P^>qn~6!Qj}+7F6`!k;C# z__XyRQ5c2Kf{;PLYTSj0j&+Y`a#W?+T!XGWl6N$j(qq$hXJU~ZWc%NT@%pCPWeDp& zxl|PPeX5x+1rOE7q4>zHxMeE%wLVr{C6%*6IG(BbnHcssV3I`Z}Es` z`h8^_e=X^QnGJbpP^PIor`D!2xRdBaxQpk*;8`084O4lu+2ZpFWn0$hMqKy^{;P!C z`E^xsC;C+PH7>6WEPE}rhvzO^CPAqp^^BHl9g|>V<1=?lKG3vvNwMwG3!Z36#w(TD z4-Y1i#dMwM5~Wi*X5ZBYgd{9&r_y4TCzD7-Mz%GmZ!s=PR8JUWw=%PRmP%*s!y!W$ zCfcUsW6PJslljN`oV+ZIs>kmPgKxK!$tHZ{4i|Hz}QcsLJl+<1pv6Nm|1J(VxS;RLEg*VLJ!;vIbt$fsHcH1w} z_0%nPr0Q4U1_NaxknS(SPCEJHfWAMh44$4L#4-vg`CZg5=lUn``}wuKf7lKSQ;3NJ z)qA%bbZVk3eiferCeL;)yp^U&YyzcaQ~`m5(JR9#uTp;V-;LC$O>l0s2~aNj^EbvOp~du4-oM%)RX zWjqX`-mLc;xXceY?50UC2j80CO#2Hv^0!^$OW0&eHwC>$y#b%FE=KMTBU?oE63LLd zY`p?@d39#zhqt2eUrqzUT;d%uJB((|5s=NN_SeV?a-CF)vXfLQsQ*_BU(0}Jr>0?t zzr-`yjWybj$%}1zs^e(U@_SH|L)?ui%aNzsNQ6t2)g3@lJh4tV4efv!|gGH}FF6pL)-Oe`OVGn?cH zFVf8CjG-?0l4*hVv7?F6M!r9q(4^pd#K>=0Thl0$#%ty=h$X=yxYv|Gt8j%>xijS0 zrZfJ~L6vNjEHT1CaK?mKnim79nX2Yy>CgKp88+P7L|ZMbK4vR*BxoqW7Ho}2iJ((Q zrw+6hwzOot&N?m@jF-sxE$^b{aB88Wjox(6sp?Dh2)_<}Wd#xyG3t5nS2&fl|rEy9iZ?@rA z@t}7vr4^hUY5q8zy*ZR?W?ub?L3}oGzM&cw;mgK2N@@XbGmjfEQFPJ3*%M8^a=T~O zoLGqxSx#Rval!7Qf<4Ggoz@^u9kpG%k9o?6)*}*cC`rhJ8La$1Y#1eEj!xbuy|5=~ z>sce>w#l_E#1lo`dfnNs1bsKr z4jYXo<#yqX$npT5xZr)wChDr$zE}s^3=2v{kD8A?j$@P)`rcLchOtth2vWENiz7ab z&}tlRtIdoN7)nLMQUr|ft`|<4ge={xxWdSUVTjp9(cOyklWSz8fiTN|2PpHw0J@NB z4HIqgqr{o|9`C891+z(9cB-9VIqHQ3#t=Ub4ipP}Tpy!1q3ons#mlNEUKM!JOcu`h zNbK*BO{L5j;0MN5x+5*nj10zeQ)JqDoXaVvKrf=IKD}8`ubyAh&`7JPV-+2@`75H3 zwA2Lj4W4sk7&asLX8AHT#8Uiylg5fF>84Wp%0r9VOWgr z(~>Dx`S~o%WWV9CJKnO@o)mc#(OfYTxLcfrIY8i9#^(}=x&jD*HrzLFwe=+6cSJKb zO`4y#ImAJ*S_183?Eoq`_(sqkeih@9ScCvD^67rf;Frlol=T}I)WPZS5yjU{YE^3X zpRg94V4-CAH>PRb)s{YSo33&FkOvk{yGMP+@xVL;KE{9yG%*$tpbuksuHmz=%DgM6 z4*f`>A&6$+wFoM!qm;)eY4O-)4fG>+Ss=JLyhrcKL$WAMcCtFb>zF-}jXkp?&W96I z3xr*6mCxdEGp|Is26&%7=A4;hPHuhun)f*yP6_rE>5Kt;GJyPY+ahzN>oE*#%D4qt zlc^1;n^RZQ|F!8);w+BE%7yP|SPx0`*J!%VACW zPMfGosg&!Wgg1he33y*OgM?Y~A;Vv~iD=uIs=x;^zw>#87C>6wfa#@kO$3lRk5vSB zg%jjXU{$s=y`m#Fi>nXTaVGA<3G#M@-*mbqF)j*F6oTo%BVO%%5c%PNI7z`NwVt|_ z(_57SfGY`L`f$0>3~z?b(KGZm%Hct0#FewftUu9^xWOyD-*b6^%kC3lLS9rsz9iGW z>n@Fm%c#@mqsbu`-o?xfkYAVK$lR_Gl=qd9UIo5`3$1G7~8AHvONg-p_ z=TV8qFiX=%D#F!dFuEgtaKb<8UH|lV`=7~}UnaY>z^yJe_QwZuC)XKeMQE@3zg|Z* zROkdy!S{t8N>q1xPfJdvPzU(Ln!IlbeW_B8k<8bh z{DhaRd(EhbK^@1dlk9>pttDrSS*|e`-iOXVj+Dd1ZX6LkMCeid$6!VB$}_EzyXIJ4 z?>-TnBq1k6@%lOAb%z2P-JkkDJhP$1TXiP4!(0Y>e>|E2fnWB32Z>}bgx9fg!!6|L zv}V2ZZJ7DPg0B&D=ZD%bR%Uu5N(CflE3@+=5w6rqlh#{KQiN%Oos%~NO*gSwdC4>i zMqdGDoL!6^10|WrSE)YKs}2CpHs$Eb4Qe?(i$I^Y78jZ-^Y)0xg}sSNOO8c7FIfdv z-rwr zmJ}qnJdt?)?$>|kvd{$a3Zgog>+}TXM1&XBz<`5 z?sAe?Rg6l>ZAt8fHrd%sneYrq!>ak2xs!dbQI}$n>k|!6Mb@|4DoDl%;b6PKhm0+J zhl(DU_X#wTN+obNK~#oBllW5pYwyfXnfSZs1}Z-)r5dCavT_`Wi^7@;5m6kr1^hV= zKFYUDOUr(=P(u$wkCQ}uxri^L)Sz7cW2C?$*YOmpR*9prf)&Fdszh&^NqJD5&u6U` zg6gK5%_0-v5ZV2`?j%69dK!VNvN|n@D~i3sk#@YYF<6MB)P1~x!0oI}ICVPE7&$Q3 z&qxvp9VcyqPgkbBt;c9GDI+>*Mj=*cO&6fg2#7VZsor~s87?!`5JgP#g-+tH@L zw|~63Exx+++Q^3Ld__tsJ+NfiM7yDhv3Oi^tHqb8oAu-%l(k?A7&wc?vt8v!&~Qw0 zhV9t_?kJ^j&?acr6}=5qL0xIjd|WAI{*Zk2x;@rklJ7jrctoN=4Ro=wm0-j%=X+O|fsUBY zBaIpTN!t}V%U_CwonQ%KFrvSG@#iD^Ne5+mDaTIE-djZ=Ew zRp8AE^^}6cF=ItkgsssR$NC3#j7YVVuOmdLAt2W!shBE?D}x~F&o^Gf zG-eXGms;QJM3NIR{KX8p*#h5o6tRBp7WFzU7v$qm{~-;Qln26>m(492ZzJ#UrQF1Y zqT!E@N4gU>0Qy<9R>QTqC1y{!Dxf#T81Q#|A29Kxn#js~xOm*Bx1rZo2h0Wj!mEcO zliU{+`N*9)|1(*?1v0q3@-p7ODOWNw`?)m&*>73jT=;OJ)TOeBZb=ld?qt13*JPw3 z%KDt`)mOO8q96bqw2NKkC7`I}cnoo!R=qBZ_tzf2{ z%17+*qRhwkJ^{!{50D2}GVjjjK1h0rvJFWwA5Rc~ zU8yV2-E=ol=rG5o?Q(^F=L2eSU0?nFc>e}6Z%^wPi5%x~U$6OlW8*xE+0my&k8`#A z01vHH9D_RF>QP~)Cqly);NCNumDpd5RlSA2nbEP6dC3y^X^a$eCY)^-vXoJUr8|Of zNI~ByWe_r?YuSSIQGEL|D;{HVy5VHsu@Mq)SHA+CjRzq=wXy7=<@h6GN%sNbc_C3m z5;L>&$O!=M+(+OdrU+neVyGlnGOHm!@yfsD41xhFO0qESOi1+`t#KXNaxWeDLPH zI7g~w*J0zgi(T|>c7Db7ln1|A^bTJ2tqH6BTP=h@S>o*N%U=OfiIw3SPA}%DqPxmM zIMcxQR2$RL=lV|9?iWk={9%)H>T#-g%%L(HTNH_Myq?+L-Vp4Ec}xqpjJCa0AP;HH^U~E z+7(%=DD;~`WoNPPC%8&&>#CMjk2a?Hy75U7M~MP4s*4Zq^kLOLP{w-g$BlP88yvH~ z(S|efI|6%MoLlPjtnUmo^rZp=F`&S?Y21O9Lg@h_rg5qF*rJ^BrwaJWvn?aBxQmT< zZxs@7M&nDtHgdb+(;lxL;f8hVk5s3rsuar}-x#6LimEH|?&*kewKnc@13Y6mY?mh^ zNZH9u`OUbq&F8-nmprU}p=YZ4LY21+kDvuS@HRcMrbb}F3qXo21y!?2Q!;%Yn%men zLE|NExPrNF!puKxl_6LFhZ3yuOn|HL7p4sL#Z@d-#7(m2f+9$YY|qW;Y^@dqw@na_ zL$9w)c{LjnKn#y^YM7+bAYFr^ADGM^E3RAaH2LDw4fqpI6|g&tT&R~vR{&nzU^Xpo z@6B!Xhju=h^>!MT7hnZ)nuFF%y zWwbV_1M6~TIpdse(dK=ug6V2n9a*v^c985Zty}6cGUSNa=tUp7T8?7mp`ok9th8y| zQ5~mQ%AN%B$qXgN-&$8YVR+j^@^%3kr~@NIx3+eG?A~%u^fSaF$AtZ#MRwS+hz1=c z(%o7*+dA?LA?MiA(P_7ofk`gO9a5zZKlJNUvdQ5C_tdSyzWWUM9J-*x5UL!RV!)&7 zhLQ~3*V&nqAJFADOP-Ebg5r-LP4$;j5D7+_M)8kTew6F4P7c>l;qg&obde+- zD?ZlAG7XQi9k%XP!TpbSC#%!lxGlUM=qnt{lnO>gN|Ujie4w>hkpu_o|DeJZO`w?c5c|i0Pfk7nrkDrCK71@;&9`Pp9g>hmnJdK z?B@97_lr;3&>Zl-P2x||fA#~Iv4wiWi#C2INrozx^Ks;xD73r6D~^Kgb{r2iW@_mr zOZV~T#%YME6?d?84|d%E$W6nW5_Bg!_Nj)*iljS3`D*%FT?IC@eArTmOjjioBaqq8 z%|hHwN=-eflbG|K&seYI{w!41RV+E(A*pbhKYGx0hSEV=c$M{fgBi*+>5gLz~`S&cb^|fUD}yzekmt zq0R64%9|2NVr1Q?{%C=C2k^7Fof!S*Fh}L`^aj*A5*j$*)uN4H7jmUKoK8vd_WsBu zAWTtK+3n#gm)~li%N~=V-w|f|7mpMwG6eaJEzB#2TERk(2y-E~I~rrV!+tti&pP2O zPd}R;zf?R-g2ah4GjRvo&Bo!;eMKrPGG$EXON3YE%GNcCQ$BvREe?f#k0-ITZ5}~n zx{9V5gt4gi>mytawv1fsMP4@*%^vLPttsuL=GC2f6TqR1iQ9e$J#3CV%m}w1O0DjI z)`x(~%8S%Wi>CA-CDif!98CIYo*3IlTa1l}a|_@W$8HUAUA0k0NXUK&IyluBA!wOX z>zxLUV`8T~#~snubeU`-s#%~~P26Avs?eYfL`dN57#EE_?usOxt<bOm`MJ_wyltN4w>6z{ zsLNE9)-?}Tz|-dN`tffE91b_zbPEmP(BgV;&w4d}v;ia*4)*bz3y{twWWBfO)~ONR{vmpt~T9AUcr#uN9PeH@pP zB@%_Mq!8|3?IR0X<$NZLFt6QKOhd=ub_=_Y6FGa3fMpKCAVJ*4F734RavFWS#qIlP z++PDE#D*MwKFqq?!JmtAy!bpJa=_snax|!Uu$UlNT^#tRHTm8^0V7B$tRF8`Pn2WS zA>HQ`x=BWcldVtIS3{or4a&X{e2^5g776awQ;kxa9XvU@!mTTBXrG5!oO9?&+@@c|(QL;VDPCN< zk`P`47}t$xSwW|`Kdk}pm;x5cTI$QXJOz$!Sg-2Z|UNMLd$cAGRy(W5jb3Rx_K2p#9gu?ZagwKK*WuJw>F zX4 zLdVcNsPc-LA7l?td%?I{6Qwu8ck6Bdla4KO>Igx5eFh*uUTVT2?>+yPOyS;&@2$I0 z08tGPhe%@}6Te~Kgb@ne2BW(lnF|q_OHAl;31_7MMkqN32(sZ5dNx!yC@DQ7GBRta z{l&js-6hV=w;O3KH_=KxQMDRRMclgTgo#hKjK47o7JWp3{sCdWG~qsFGP}EbiASp# zO(0?quPIM;!7P$H5lV++6`Y+3++9!9!q6rVh1TPwN$s1Xqn?0MVlfCW%24Ob&Tcf- z#l_g2yD(wAuyq=nm^qp}Yi`sh1f7-0!-9;BdnqSvNuw~N-ki!V*4$`HHr`jPH}020 zhGv0LZ;W1II`mIWpIu^vJ~xCq#7$rn8i~r_!^+;5Z0}0yXxVk)81~Lc?bK!jmg28* z=ut`|s=mJ&^b3V^ItS*k@Pz~h;aphvCxm)8?$2A(;bTtX>RO~T2YR_g{EDBIEYhEy zOk4OAVe>E-EN?g{L7w4ou<-1kwdD{d7RUd#>1~GZM-7#{H#3@8`qR(5-Y8%Rl7eaYk~a_y(0?pY0??97!bozI^I7 zu7!m~;EHA{B;t2c9;*b2@SB?l0d?^EA+o?kRY(t23T$sO2LT~CohkvQvJk5d^|2F4 zXDmIsc1YoV$fB2ZKvJTuFICkm3?S63@ELeXae}mwjND;ssbcFs-*s}dFFv{PF-)O5 zKQ22+5w!MQZ9c%rgSnzY_S1zGU9QUW#wNaN$e?_YF5ptuR48SQPF1cA`S52vW0sx- zF9&kgP_O+3=NPB153Ulo1q;5l@iR&p+y0j;Qr7|`Bq5^AaaTh9A4!3!1(h-P#E5#% zPW)_D#w3?Z=(Oc2?9ARj)MH+OdlhvD@U&;lWSjgCbU?qL`&8B^b1<>_nqwLr-~qA6 zCtP0t2n1!SV%B~BS-;S-!~Q-35K}>)PVn5S*ihf+i$p&ygg5o-bSds?&Gsm~id-YV z#oF|flgfRRtD_LuBWqE$h6I;z|GZ+K_CkcUn{@{P6bS06zo9&^gY!a`+o*m-T{cCC zsrrFCF}J9{>X2~H!3RI};b%l9PLi5#>;Yy5iq_}$88kjVC9!N`C3@y?^UgSwk%m(j z&LlJL-)Ao2_4i--&CH{74M!_hjW-2Lq3n{hh?WW$--7EgT*Qh-_-Zz zf6`dwr96U;1aret+8!Yjj623xXt4C=oaQ9MSICN+KcxgjflbbRjhW))iKE=~Am zduSBekZX7s*R!s3ca`bYOoMApc=T81y;4t^*5IwFSRyaL>_!_nOikRF-pe|?syEsw zJG4)In;10<37tba!{UQ5-fe8>s@!Wz#hF41U7Imgm_fAVb<4RgfS$xx+0PH5xP zZg}>Rg{7z|htY0xoTvx7JqC1DH{_0a&?Qts=3GIl^@7`0xUTHL15FDXnePl>+m&ml zYZf-p2i-#ZVaiJ+suGP$R@h^cj3%$~Gh{>olTh4eC`u!2kuFEBx!-WoQiH^3o|)J& z_$1NzUqs2|nN|2|)PPu#rA8%a`c0~t@O&;c$*xK&g-3S?lEJ)s7;O|hW8riP0Br~> zC#fZYb(}DAA_S?JVb?a;$MaKFgI0)R%%JH%G6`?Lsl^a&9KZ(SD65wLQx{a;9c%YS z`1BORF+x{AwGYpUOI!`}K1PWoq0}|z-r|^Z=#qpk1LbfFpvy%rTM*UYlf+o$>t_$K zmy2aH6$jIJZCH!I&o6%%incC?sn=S>bPtS;1wFbJr*iWKKFU=oK_CG5~tLl=WOpGK;f>` z!j>^^j4W^+0g6#MMYUd()f zB=DpE`H|p*2y|xmA0PSOg#EeEzdxViLrKT~dFeXG3#j!Umv;Y|od0_R!9Vm^!3S7i zYHC*`j4~3A7M%H(tih^Vd?SowWFCkUZ?5RWljkL2sw9TKEQ!;S>--6e@XhtRRk=1_ zB!!VpfE_MUmSmPofO#>(Ly{viO;G&DMyR)eQSWmL>X#9_r;_v(TwJUwH(OW**o4WY zH;)CTp0$?UlMJ)Ehde0U5xsoZ@7}7&#GG*7cqs+FJhV^U&&^(%i{FC1%D>2<_6zqk z%F6A>UsR#~KI}int9unO$CO8`uS^Vi!iFh9m@*!_5U=Ss#cKk4(Tq&68-`{aImIFK zr9|A;y&|%X)t=v9n|Ea1jdhb!)g=LiNLlpG!C# z%wejnK;bbcz5dBAo7SD-Mt?fB_+Bz!{Q{3I60c6=bWwN}S0vu-*S@**Tu6E>IO|?l z_18T1wj!7`U3j_$GVHqs(5?wZl=Wb$92D9j8XewCjEJPc?sGtHVh{gp7_Q*if4AZ)Q zRA>QU{>%~fS>vdgDw zwyVAy=wSW0gQ#t8`h$f(@Uh_bhjO@d5I3Vr{bp?*Kf6O<%+|v9kUfb0!4?A`taR4r z3YmtR^@mzsn5LT+%A`M0o_fc5l55N3`w@0nQgb{p@}P!lc-st-do)xNul_W)U9SV| zOdy-zUKstv!74Qh0A=y0I%An^&_?%2z8B+{XwBEQclxp``W9n`Fw`8T9ih)>iGpD4H54`l#VInzNBGuAx=!-y9umX6SCJ+hXXZT@BU;&hT*XVvVkZ ztc>8&jZJ{mO9zmSx|u>CoiTv}$;t4SGi5%>`}2C|G`0o|PlDaJn2%?qt3S{)QD`P7 zP0O*!rMG3k3-gwXl*0`LV4%5@JvhSc@I^o!&Fpk4#&1 zAAiEc+-1%QGbzDK!pS^2?GVKW*-|P@Izr%*dE0^)2h~y?7dw+nohpcSdow+`Hm);& zzYXJVYH>K+c8(V+Z+{oA^V|({-CDBjj#5v!$hD>N%Y`RTj=%A>RRj+&TOGOnAmxZ{ zjKpx0DwQXX7^xWuf9WPVidncc%d3W*XqL^NnlRq9%T7+u!c1yal=!uSWMG@71l=;~ z(fJ@N9LgFvoUxr=RQbDQTdGUWvjX8?4*NRsH((dSsS{HFRh@y&45dm<<|ifB(2TQ?bp(llL&N-{L^2k_jK~ z!o22`&$me2_SqZCcv4blMnWL%V!&eB88k};k!1^VLCr#JKNj!O91UM=&SPsK@-_PA z)QT{>$`UqBE3g=RbCXb~cD~+05Ov~h_q_Q+O@?@^k`*Kb)O<6n1qw8uFGw7Hr+*%s zD9m#sCG{}B%nT##h+(+gdRS8#d{CV=IOFHySFZ>ZfqgKR$`q=!H_>jWegvSEx+(X3 zhCZVmY>?6t2B|q~2+(e5tX54%lYI8mr61WvvU7ZUj!T^lva6 zx2YMby0IObJx9K})YMU6XljYWE#NYc+O%z2kP;|%>v8|$1>ed$f}2cXJD+u!k!p!g z<}(rfHWY07-Y_m#3F|EOfuDkGH@S4(wR+AmKA|JXsyn(pQk`aH4gHWEh5(KTGSY5^ z(CO_PwYbq#<{D07{k&bZt7zNH2W*Y*C`M#Hy+bu`!&C&1fksZMiE)U47CfoDTG#UH z6=b_@zmh4%COtVavPzxTK0rgCWpeV6kFQPVnYifRm?y=8W~?Z&*Rod>##=7VdV)=_ zOI7Pk-*Y`T4cPnNgeTwA@Qj&FyyDe%55$Ite`+FAisx_WVfL_T_Zgk5 zLois|$o+m_IR3-0fwS{h$n3qXlR1q7xyfDTbI3ne*S1-U^u*wKmB^B1y;07DPj{I{ zHUFJ7Om0Da*cKKKf*4N%hgeZu-P>i`j5fb7taTchSIv6_Pz7wT2{^V~(>bXANxH!+ zLN8Ee$cYVaXWqwf{S!pL5X4jWTbldHF4LuH;yzk<>_yh@XWai63HZ-V6~}~Ac>rDI z*M$7g-~^^Jg>jt^<)FN9cA&*Y^UH~{@^L{M?n%Qmz6?D>4OOGsh<6Yu zYd+7-?k>rbQz^I^W3NxrMAL%}S7bO#XSb$c1>EzP%5kf%)WPnYiavtK?o>F$dK?JY z(Ft0j0$Q8STZ^RAcdio(^;^Yy3(c5~nfMM}v*;%MQzlI(dy9*p4hx$3&f8jcAgbmu zoT}Yr7Nw5XKMhYt*-T0&l<)@h?f!NlRW8iRIF`J079SN{oh+oGi3o%FoYnbctjX#w;#A4;u&&Ar z?_0I;8C@`&#`h5)aVn$g>SMUK%0xcK*=!b;Heun@U=!=LkKod-h%1hne>2~cE;OFH z1%7EOOQ;M8mF48xFg^+17I9hM$N{9X8O}a>Q+6cj=zbfm$`!BEebw5uoN1v;fe>3P z>8E#UF|}uEJ$D?`#SkwT*ZV7a9#Z||PL4l~#$UheA+}tNij^_@+~wXxgupda;Cx5k zN;}qR*?6}@d$auXnl~l~cn=3A_sBcXLb!L88l3|9|bRxr#|o~g4NhdB|?j+3hX)wGmetP&xUfR&P*S1jCjra z7dBd{2p=pGz^cmOEn=gM&@=q?ZcMYFlI^yOF#ICbQt5ZJW_K#8SXW#kRNr>)uXd?@ ztJwP$FC`h2BgXi`5tFAH;~0Yz5P0xBdkm?_koQ7;Dx4-KCB~%2d;|OTY-2H2m0hzV zEpTnQv=!#DyZz!+vf=7U8s$3rBQ=32g?^mGLjGPC=BFeE$zx}X6lG?FY2ASV z>qX9bFX4qlaOq;uQR@Ca+RjDtCIVNy#*(|Pn9<_Jr=hR9TMwB+Ql0c>v>1sCMr5VeYL}BL)R&?0hot`|7!>NYglpih zrMycP9j3|%`fB|8^Tdp7UEpf^+uJ^!Rg-IH1EL2p$-KIQ5EC}1-ie&*GD349kdQo) zoxEZ0{%d1P#}dH>rt%YIip(`vS>-9lsoJO&J7+!Y-ZH1Yu5-R8k@(Hx@wCU3rtWh2 z6fr0n_?n&Bz68O8Y)H_$+b6J`2Pw|maA0TL{jf+% zk>JZ?%2(u^O1sgtbU+}m`)HQmw%1RZCiF!-OHsfRMj8nzL zay1bL#$la(ys7;CS+T+0lMjYxKIU#6E}D})&uh12r|^3L5FWwQrM?U~oDW<`s7(Pp zpLA%DSzMZrFuRTjMOU9j`s?pv zQ*Dm>I;=0DdC}EgXfqHc{oYV>So9w=ZN97g%?2%`p}1Gm8>L7lElIw7+aA}Pnm6rj zl?IoS4mjM09zyw%D+){(7B|5i!q&iB#)Io;nSTqY&y~=V9IDqs|E{WH^2^~yuWXyP zdH%r(OYCnGhbH?!d%YWw;(y^Alqikowr@l%Oo280g(aKTP4a?##6JMCB=1sS36A}Q zTK8*KnnPsNq~&mvb&W6_eq$m>)C2Sust2Wx)M(L+d_VkKrB1(OQoXU3AM$LX@i