From 57cd0a027c3b5575abf2226decc64c9c23272fcd Mon Sep 17 00:00:00 2001 From: fred-labs Date: Tue, 5 Mar 2024 17:40:54 +0100 Subject: [PATCH] Import code (#7) * Import * Update LICENSE * Set version to 1.0.0 * Add submodules * remove some libraries * move docs * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * update version * moving * renaming * renaming * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * test * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * cleanup * update doc * cleanup --- .github/bandit.yaml | 321 + .github/linters/.pylintrc | 2 +- .github/workflows/scan.yml | 47 + .github/workflows/test_build.yml | 60 + .gitmodules | 6 + Makefile | 46 + README.md | 54 +- deb_requirements.txt | 5 + dependencies/py_trees | 1 + dependencies/py_trees_ros | 1 + docs/actions.rst | 3 - docs/architecture.rst | 90 +- docs/conf.py | 8 +- docs/development.rst | 55 +- docs/dictionary.txt | 10 +- docs/how_to_run.rst | 156 +- docs/images/graphs/osc2_namespace.png | Bin 221963 -> 0 bytes .../graphs/scenario_execution_structure.png | Bin 96367 -> 0 bytes docs/images/graphs/scenario_structure.png | Bin 57202 -> 0 bytes docs/images/graphs/vscode1.png | Bin 10048 -> 0 bytes docs/images/graphs/vscode2.png | Bin 32354 -> 0 bytes docs/images/graphs/vscode3.png | Bin 53379 -> 0 bytes docs/images/parsing.png | Bin 35522 -> 21399 bytes docs/images/scenario_execution_structure.png | Bin 0 -> 556187 bytes docs/images/{graphs => }/tree_example.png | Bin docs/index.rst | 16 +- docs/libraries.rst | 212 + docs/openscenario2.rst | 99 + docs/openscenario2_support.rst | 309 - docs/tutorials.rst | 448 +- examples/example_library/MANIFEST.in | 1 + examples/example_library/README.md | 22 + .../example_library/__init__.py | 15 + .../example_library/actions/__init__.py | 15 + .../example_library/actions/custom_action.py | 32 + .../example_library/get_osc_library.py | 19 + .../example_library/lib_osc/example.osc | 3 + .../example_library/resource/example_library | 0 .../scenarios/example_library.osc | 7 + examples/example_library/setup.cfg | 4 + examples/example_library/setup.py | 48 + examples/example_multi_robot/README.md | 36 + .../example_multi_robot.osc | 179 + examples/example_nav2/README.md | 23 + examples/example_nav2/example_nav2.osc | 13 + examples/example_scenario/README.md | 21 + examples/example_scenario/hello_world.osc | 8 + examples/example_simulation/README.md | 23 + .../example_simulation/__init__.py | 15 + examples/example_simulation/models/box.sdf | 35 + examples/example_simulation/package.xml | 25 + .../resource/example_simulation | 0 .../scenarios/example_simulation.osc | 28 + examples/example_simulation/setup.py | 43 + requirements.txt | 1 - scenario_coverage/README.md | 6 + scenario_coverage/package.xml | 21 + scenario_coverage/resource/scenario_coverage | 0 .../scenario_coverage/__init__.py | 15 + .../scenario_batch_execution.py | 148 + .../scenario_coverage/scenario_variation.py | 153 + .../scenarios/test_fault_injection.osc | 26 + .../scenarios/test_fault_injection_drop.osc | 20 + .../scenarios/test_fault_injection_noise.osc | 20 + scenario_coverage/scenarios/test_log.osc | 7 + .../scenarios/test_nav_to_pose.osc | 19 + scenario_coverage/setup.cfg | 4 + scenario_coverage/setup.py | 45 + scenario_coverage/test/test_variations.py | 171 + scenario_execution/MANIFEST.in | 1 + scenario_execution/README.md | 7 + scenario_execution/launch/scenario_launch.py | 88 + scenario_execution/package.xml | 30 + .../resource/scenario_execution | 0 .../scenario_execution/__init__.py | 27 + .../scenario_execution/actions/__init__.py | 15 + .../scenario_execution/actions/conversions.py | 73 + .../scenario_execution/actions/init_nav2.py | 238 + .../scenario_execution/actions/nav2_common.py | 208 + .../actions/nav_through_poses.py | 125 + .../scenario_execution/actions/nav_to_pose.py | 180 + .../actions/odometry_distance_traveled.py | 108 + .../actions/py_trees_ros_common.py | 102 + .../actions/ros_bag_record.py | 149 + .../actions/ros_log_check.py | 82 + .../actions/ros_service_call.py | 121 + .../actions/ros_set_node_parameter.py | 79 + .../actions/ros_topic_check_data.py | 56 + .../actions/ros_topic_publish.py | 85 + .../actions/ros_topic_wait_for_data.py | 45 + .../actions/ros_topic_wait_for_topics.py | 58 + .../scenario_execution/actions/tf_close_to.py | 198 + .../scenario_execution/get_osc_library.py | 19 + .../scenario_execution/lib_osc/ros.osc | 135 + .../scenario_execution/logging_ros.py | 69 + .../scenario_execution/marker_handler.py | 60 + .../scenario_execution_ros.py | 158 + .../scenarios/test/test_ros_service_call.osc | 14 + .../test/test_ros_service_call_blocking.osc | 74 + .../test/test_ros_set_node_parameter.osc | 18 + .../test/test_ros_topic_check_data.osc | 16 + .../scenarios/test/test_ros_topic_publish.osc | 13 + .../test/test_ros_topic_wait_for_data.osc | 13 + scenario_execution/setup.cfg | 4 + scenario_execution/setup.py | 69 + .../test/test_ros_publish_receive.py | 72 + .../test/test_ros_service_call.py | 71 + .../test/test_ros_service_call_blocking.py | 98 + .../test/test_ros_set_node_parameter.py | 81 + .../test/test_ros_topic_publish.py | 69 + scenario_execution_base/MANIFEST.in | 1 + scenario_execution_base/README.md | 11 + scenario_execution_base/package.xml | 21 + .../resource/scenario_execution_base | 0 .../scenario_execution_base/__init__.py | 30 + .../actions/__init__.py | 15 + .../scenario_execution_base/actions/log.py | 54 + .../actions/run_external_process.py | 135 + .../get_osc_library.py | 26 + .../lib_osc/helpers.osc | 8 + .../lib_osc/robotics.osc | 4 + .../lib_osc/standard.osc | 1227 ++ .../scenario_execution_base/model/__init__.py | 15 + .../scenario_execution_base/model/error.py | 38 + .../model/model_base_visitor.py | 266 + .../model/model_builder.py | 1994 +++ .../model/model_file_loader.py | 52 + .../model/model_resolver.py | 284 + .../model/model_to_py_tree.py | 282 + .../model/osc2_parser.py | 131 + .../scenario_execution_base/model/types.py | 2072 +++ .../osc2_parsing/.gitignore | 1 + .../osc2_parsing/OpenSCENARIO2.g4 | 759 ++ .../osc2_parsing/OpenSCENARIO2.interp | 361 + .../osc2_parsing/OpenSCENARIO2.tokens | 197 + .../osc2_parsing/OpenSCENARIO2Lexer.interp | 339 + .../osc2_parsing/OpenSCENARIO2Lexer.py | 757 ++ .../osc2_parsing/OpenSCENARIO2Lexer.tokens | 195 + .../osc2_parsing/OpenSCENARIO2Listener.py | 1251 ++ .../osc2_parsing/OpenSCENARIO2Parser.py | 10461 ++++++++++++++++ .../osc2_parsing/OpenSCENARIO2Visitor.py | 642 + .../osc2_parsing/README.md | 3 + .../osc2_parsing/__init__.py | 15 + .../scenario_execution.py | 315 + .../scenario_execution_base/utils/__init__.py | 15 + .../scenario_execution_base/utils/logging.py | 110 + scenario_execution_base/setup.cfg | 4 + scenario_execution_base/setup.py | 56 + .../test/test_expression.py | 153 + .../test/test_model_ser_deser.py | 126 + .../test/test_osc2_parser_action.py | 63 + .../test/test_osc2_parser_actor.py | 73 + .../test_osc2_parser_behavior_invocation.py | 416 + .../test/test_osc2_parser_enum.py | 152 + .../test/test_osc2_parser_event.py | 53 + .../test/test_osc2_parser_keep.py | 49 + .../test/test_osc2_parser_list.py | 143 + .../test/test_osc2_parser_not_supported.py | 274 + .../test/test_osc2_parser_parameter.py | 522 + .../test/test_osc2_parser_physical_type.py | 65 + .../test/test_osc2_parser_si.py | 81 + .../test/test_osc2_parser_struct.py | 178 + .../test/test_osc2_parser_wait.py | 93 + .../test/test_osc2_standard_osc.py | 40 + .../test/test_run_external_process.py | 89 + .../test/test_scenario_events.py | 92 + .../test/test_scenario_oneof.py | 63 + .../test/test_scenario_parallel.py | 63 + scenario_execution_control/CMakeLists.txt | 11 + scenario_execution_control/README.md | 4 + .../scenario_execution_control_launch.py | 50 + scenario_execution_control/package.xml | 19 + .../resource/scenario_execution_control | 0 scenario_execution_control/setup.cfg | 4 + scenario_execution_control/setup.py | 48 + .../scenario_execution_control/__init__.py | 15 + .../application_runner.py | 167 + .../scenario_execution_control_node.py | 165 + .../scenario_execution_runner.py | 43 + .../scenario_list_publisher.py | 67 + scenario_execution_gazebo/README.md | 8 + scenario_execution_gazebo/package.xml | 28 + .../resource/scenario_execution_gazebo | 0 .../scenario_execution_gazebo/__init__.py | 15 + .../actions/__init__.py | 15 + .../actions/gazebo_actor_exists.py | 99 + .../actions/gazebo_delete_actor.py | 84 + .../actions/gazebo_spawn_actor.py | 190 + .../actions/gazebo_wait_for_sim.py | 72 + .../actions/utils.py | 245 + .../get_osc_library.py | 19 + .../lib_osc/gazebo.osc | 22 + scenario_execution_gazebo/setup.cfg | 4 + scenario_execution_gazebo/setup.py | 60 + scenario_execution_interfaces/CMakeLists.txt | 24 + scenario_execution_interfaces/README.md | 3 + .../msg/Scenario.msg | 18 + .../msg/ScenarioExecutionStatus.msg | 24 + .../msg/ScenarioList.msg | 18 + .../msg/ScenarioStatus.msg | 20 + scenario_execution_interfaces/package.xml | 25 + .../srv/ExecuteScenario.srv | 4 + scenario_execution_rviz/CMakeLists.txt | 55 + scenario_execution_rviz/LICENSE_MIT | 21 + scenario_execution_rviz/README.md | 3 + scenario_execution_rviz/icons/check-o.png | Bin 0 -> 1277 bytes .../icons/chevron-right-o.png | Bin 0 -> 1035 bytes scenario_execution_rviz/icons/close-o.png | Bin 0 -> 1250 bytes .../icons/corner-down-right.png | Bin 0 -> 476 bytes scenario_execution_rviz/icons/play.png | Bin 0 -> 433 bytes scenario_execution_rviz/icons/stop.png | Bin 0 -> 4940 bytes scenario_execution_rviz/package.xml | 31 + .../plugin_description.xml | 9 + .../scenario_execution_rviz.qrc | 10 + scenario_execution_rviz/src/control_panel.cpp | 203 + scenario_execution_rviz/src/control_panel.h | 77 + .../src/indicator_widget.cpp | 56 + .../src/indicator_widget.h | 43 + security.md | 6 + .../gazebo/tb4_sim_scenario/CMakeLists.txt | 23 + simulation/gazebo/tb4_sim_scenario/README.md | 9 + .../launch/ignition_launch.py | 124 + .../launch/ignition_robot_launch.py | 201 + .../tb4_sim_scenario/launch/nav2_launch.py | 76 + .../launch/robot_description.launch.py | 85 + .../launch/ros_ign_bridge.launch.py | 221 + .../launch/sim_nav_scenario_launch.py | 108 + .../gazebo/tb4_sim_scenario/package.xml | 27 + .../tb4_sim_scenario/params/nav2_params.yaml | 440 + .../tb4_sim_scenario/urdf/create3.urdf.xacro | 323 + .../urdf/turtlebot4.urdf.xacro | 144 + .../gazebo/tb4_sim_scenario/worlds/maze.sdf | 1066 ++ tools/message_modification/README.md | 3 + .../launch/scan_modification_launch.py | 68 + .../message_modification/__init__.py | 15 + .../laserscan_modification.py | 90 + .../message_modification/message_drop.py | 79 + tools/message_modification/package.xml | 17 + .../resource/message_modification | 0 tools/message_modification/setup.cfg | 4 + tools/message_modification/setup.py | 47 + tools/scenario_status/README.md | 3 + tools/scenario_status/package.xml | 29 + .../scenario_status/resource/scenario_status | 0 .../scenario_status/__init__.py | 15 + .../scenario_status/scenario_status_node.py | 204 + tools/scenario_status/setup.cfg | 4 + tools/scenario_status/setup.py | 50 + tools/tf_to_pose_publisher/README.md | 3 + .../launch/tf_to_pose_launch.py | 83 + tools/tf_to_pose_publisher/package.xml | 18 + .../resource/tf_to_pose_publisher | 0 tools/tf_to_pose_publisher/setup.cfg | 4 + tools/tf_to_pose_publisher/setup.py | 45 + .../tf_to_pose_publisher/__init__.py | 15 + .../tf_to_pose_publisher.py | 131 + 256 files changed, 36315 insertions(+), 846 deletions(-) create mode 100644 .github/bandit.yaml create mode 100644 .github/workflows/test_build.yml create mode 100644 .gitmodules create mode 100644 Makefile create mode 100644 deb_requirements.txt create mode 160000 dependencies/py_trees create mode 160000 dependencies/py_trees_ros delete mode 100644 docs/actions.rst delete mode 100644 docs/images/graphs/osc2_namespace.png delete mode 100644 docs/images/graphs/scenario_execution_structure.png delete mode 100644 docs/images/graphs/scenario_structure.png delete mode 100644 docs/images/graphs/vscode1.png delete mode 100644 docs/images/graphs/vscode2.png delete mode 100644 docs/images/graphs/vscode3.png create mode 100644 docs/images/scenario_execution_structure.png rename docs/images/{graphs => }/tree_example.png (100%) create mode 100644 docs/libraries.rst create mode 100644 docs/openscenario2.rst delete mode 100644 docs/openscenario2_support.rst create mode 100644 examples/example_library/MANIFEST.in create mode 100644 examples/example_library/README.md create mode 100644 examples/example_library/example_library/__init__.py create mode 100644 examples/example_library/example_library/actions/__init__.py create mode 100644 examples/example_library/example_library/actions/custom_action.py create mode 100644 examples/example_library/example_library/get_osc_library.py create mode 100644 examples/example_library/example_library/lib_osc/example.osc create mode 100644 examples/example_library/resource/example_library create mode 100644 examples/example_library/scenarios/example_library.osc create mode 100644 examples/example_library/setup.cfg create mode 100644 examples/example_library/setup.py create mode 100644 examples/example_multi_robot/README.md create mode 100644 examples/example_multi_robot/example_multi_robot.osc create mode 100644 examples/example_nav2/README.md create mode 100644 examples/example_nav2/example_nav2.osc create mode 100644 examples/example_scenario/README.md create mode 100644 examples/example_scenario/hello_world.osc create mode 100644 examples/example_simulation/README.md create mode 100644 examples/example_simulation/example_simulation/__init__.py create mode 100644 examples/example_simulation/models/box.sdf create mode 100644 examples/example_simulation/package.xml create mode 100644 examples/example_simulation/resource/example_simulation create mode 100644 examples/example_simulation/scenarios/example_simulation.osc create mode 100644 examples/example_simulation/setup.py create mode 100644 scenario_coverage/README.md create mode 100644 scenario_coverage/package.xml create mode 100644 scenario_coverage/resource/scenario_coverage create mode 100644 scenario_coverage/scenario_coverage/__init__.py create mode 100644 scenario_coverage/scenario_coverage/scenario_batch_execution.py create mode 100644 scenario_coverage/scenario_coverage/scenario_variation.py create mode 100644 scenario_coverage/scenarios/test_fault_injection.osc create mode 100644 scenario_coverage/scenarios/test_fault_injection_drop.osc create mode 100644 scenario_coverage/scenarios/test_fault_injection_noise.osc create mode 100644 scenario_coverage/scenarios/test_log.osc create mode 100644 scenario_coverage/scenarios/test_nav_to_pose.osc create mode 100644 scenario_coverage/setup.cfg create mode 100644 scenario_coverage/setup.py create mode 100644 scenario_coverage/test/test_variations.py create mode 100644 scenario_execution/MANIFEST.in create mode 100644 scenario_execution/README.md create mode 100644 scenario_execution/launch/scenario_launch.py create mode 100644 scenario_execution/package.xml create mode 100644 scenario_execution/resource/scenario_execution create mode 100644 scenario_execution/scenario_execution/__init__.py create mode 100644 scenario_execution/scenario_execution/actions/__init__.py create mode 100644 scenario_execution/scenario_execution/actions/conversions.py create mode 100644 scenario_execution/scenario_execution/actions/init_nav2.py create mode 100644 scenario_execution/scenario_execution/actions/nav2_common.py create mode 100644 scenario_execution/scenario_execution/actions/nav_through_poses.py create mode 100644 scenario_execution/scenario_execution/actions/nav_to_pose.py create mode 100644 scenario_execution/scenario_execution/actions/odometry_distance_traveled.py create mode 100644 scenario_execution/scenario_execution/actions/py_trees_ros_common.py create mode 100644 scenario_execution/scenario_execution/actions/ros_bag_record.py create mode 100644 scenario_execution/scenario_execution/actions/ros_log_check.py create mode 100644 scenario_execution/scenario_execution/actions/ros_service_call.py create mode 100644 scenario_execution/scenario_execution/actions/ros_set_node_parameter.py create mode 100644 scenario_execution/scenario_execution/actions/ros_topic_check_data.py create mode 100644 scenario_execution/scenario_execution/actions/ros_topic_publish.py create mode 100644 scenario_execution/scenario_execution/actions/ros_topic_wait_for_data.py create mode 100644 scenario_execution/scenario_execution/actions/ros_topic_wait_for_topics.py create mode 100644 scenario_execution/scenario_execution/actions/tf_close_to.py create mode 100644 scenario_execution/scenario_execution/get_osc_library.py create mode 100644 scenario_execution/scenario_execution/lib_osc/ros.osc create mode 100644 scenario_execution/scenario_execution/logging_ros.py create mode 100644 scenario_execution/scenario_execution/marker_handler.py create mode 100644 scenario_execution/scenario_execution/scenario_execution_ros.py create mode 100644 scenario_execution/scenarios/test/test_ros_service_call.osc create mode 100644 scenario_execution/scenarios/test/test_ros_service_call_blocking.osc create mode 100644 scenario_execution/scenarios/test/test_ros_set_node_parameter.osc create mode 100644 scenario_execution/scenarios/test/test_ros_topic_check_data.osc create mode 100644 scenario_execution/scenarios/test/test_ros_topic_publish.osc create mode 100644 scenario_execution/scenarios/test/test_ros_topic_wait_for_data.osc create mode 100644 scenario_execution/setup.cfg create mode 100644 scenario_execution/setup.py create mode 100644 scenario_execution/test/test_ros_publish_receive.py create mode 100644 scenario_execution/test/test_ros_service_call.py create mode 100644 scenario_execution/test/test_ros_service_call_blocking.py create mode 100644 scenario_execution/test/test_ros_set_node_parameter.py create mode 100644 scenario_execution/test/test_ros_topic_publish.py create mode 100644 scenario_execution_base/MANIFEST.in create mode 100644 scenario_execution_base/README.md create mode 100644 scenario_execution_base/package.xml create mode 100644 scenario_execution_base/resource/scenario_execution_base create mode 100644 scenario_execution_base/scenario_execution_base/__init__.py create mode 100644 scenario_execution_base/scenario_execution_base/actions/__init__.py create mode 100644 scenario_execution_base/scenario_execution_base/actions/log.py create mode 100644 scenario_execution_base/scenario_execution_base/actions/run_external_process.py create mode 100644 scenario_execution_base/scenario_execution_base/get_osc_library.py create mode 100644 scenario_execution_base/scenario_execution_base/lib_osc/helpers.osc create mode 100644 scenario_execution_base/scenario_execution_base/lib_osc/robotics.osc create mode 100644 scenario_execution_base/scenario_execution_base/lib_osc/standard.osc create mode 100644 scenario_execution_base/scenario_execution_base/model/__init__.py create mode 100644 scenario_execution_base/scenario_execution_base/model/error.py create mode 100644 scenario_execution_base/scenario_execution_base/model/model_base_visitor.py create mode 100644 scenario_execution_base/scenario_execution_base/model/model_builder.py create mode 100644 scenario_execution_base/scenario_execution_base/model/model_file_loader.py create mode 100644 scenario_execution_base/scenario_execution_base/model/model_resolver.py create mode 100644 scenario_execution_base/scenario_execution_base/model/model_to_py_tree.py create mode 100644 scenario_execution_base/scenario_execution_base/model/osc2_parser.py create mode 100644 scenario_execution_base/scenario_execution_base/model/types.py create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/.gitignore create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.g4 create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.interp create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.tokens create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.interp create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.py create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.tokens create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Listener.py create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Parser.py create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Visitor.py create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/README.md create mode 100644 scenario_execution_base/scenario_execution_base/osc2_parsing/__init__.py create mode 100644 scenario_execution_base/scenario_execution_base/scenario_execution.py create mode 100644 scenario_execution_base/scenario_execution_base/utils/__init__.py create mode 100644 scenario_execution_base/scenario_execution_base/utils/logging.py create mode 100644 scenario_execution_base/setup.cfg create mode 100644 scenario_execution_base/setup.py create mode 100644 scenario_execution_base/test/test_expression.py create mode 100644 scenario_execution_base/test/test_model_ser_deser.py create mode 100644 scenario_execution_base/test/test_osc2_parser_action.py create mode 100644 scenario_execution_base/test/test_osc2_parser_actor.py create mode 100644 scenario_execution_base/test/test_osc2_parser_behavior_invocation.py create mode 100644 scenario_execution_base/test/test_osc2_parser_enum.py create mode 100644 scenario_execution_base/test/test_osc2_parser_event.py create mode 100644 scenario_execution_base/test/test_osc2_parser_keep.py create mode 100644 scenario_execution_base/test/test_osc2_parser_list.py create mode 100644 scenario_execution_base/test/test_osc2_parser_not_supported.py create mode 100644 scenario_execution_base/test/test_osc2_parser_parameter.py create mode 100644 scenario_execution_base/test/test_osc2_parser_physical_type.py create mode 100644 scenario_execution_base/test/test_osc2_parser_si.py create mode 100644 scenario_execution_base/test/test_osc2_parser_struct.py create mode 100644 scenario_execution_base/test/test_osc2_parser_wait.py create mode 100644 scenario_execution_base/test/test_osc2_standard_osc.py create mode 100644 scenario_execution_base/test/test_run_external_process.py create mode 100644 scenario_execution_base/test/test_scenario_events.py create mode 100644 scenario_execution_base/test/test_scenario_oneof.py create mode 100644 scenario_execution_base/test/test_scenario_parallel.py create mode 100644 scenario_execution_control/CMakeLists.txt create mode 100644 scenario_execution_control/README.md create mode 100644 scenario_execution_control/launch/scenario_execution_control_launch.py create mode 100644 scenario_execution_control/package.xml create mode 100644 scenario_execution_control/resource/scenario_execution_control create mode 100644 scenario_execution_control/setup.cfg create mode 100644 scenario_execution_control/setup.py create mode 100644 scenario_execution_control/src/scenario_execution_control/__init__.py create mode 100755 scenario_execution_control/src/scenario_execution_control/application_runner.py create mode 100755 scenario_execution_control/src/scenario_execution_control/scenario_execution_control_node.py create mode 100755 scenario_execution_control/src/scenario_execution_control/scenario_execution_runner.py create mode 100755 scenario_execution_control/src/scenario_execution_control/scenario_list_publisher.py create mode 100644 scenario_execution_gazebo/README.md create mode 100644 scenario_execution_gazebo/package.xml create mode 100644 scenario_execution_gazebo/resource/scenario_execution_gazebo create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/__init__.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/actions/__init__.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/get_osc_library.py create mode 100644 scenario_execution_gazebo/scenario_execution_gazebo/lib_osc/gazebo.osc create mode 100644 scenario_execution_gazebo/setup.cfg create mode 100644 scenario_execution_gazebo/setup.py create mode 100644 scenario_execution_interfaces/CMakeLists.txt create mode 100644 scenario_execution_interfaces/README.md create mode 100644 scenario_execution_interfaces/msg/Scenario.msg create mode 100644 scenario_execution_interfaces/msg/ScenarioExecutionStatus.msg create mode 100644 scenario_execution_interfaces/msg/ScenarioList.msg create mode 100644 scenario_execution_interfaces/msg/ScenarioStatus.msg create mode 100644 scenario_execution_interfaces/package.xml create mode 100644 scenario_execution_interfaces/srv/ExecuteScenario.srv create mode 100644 scenario_execution_rviz/CMakeLists.txt create mode 100644 scenario_execution_rviz/LICENSE_MIT create mode 100644 scenario_execution_rviz/README.md create mode 100755 scenario_execution_rviz/icons/check-o.png create mode 100755 scenario_execution_rviz/icons/chevron-right-o.png create mode 100755 scenario_execution_rviz/icons/close-o.png create mode 100755 scenario_execution_rviz/icons/corner-down-right.png create mode 100644 scenario_execution_rviz/icons/play.png create mode 100644 scenario_execution_rviz/icons/stop.png create mode 100644 scenario_execution_rviz/package.xml create mode 100644 scenario_execution_rviz/plugin_description.xml create mode 100644 scenario_execution_rviz/scenario_execution_rviz.qrc create mode 100644 scenario_execution_rviz/src/control_panel.cpp create mode 100644 scenario_execution_rviz/src/control_panel.h create mode 100644 scenario_execution_rviz/src/indicator_widget.cpp create mode 100644 scenario_execution_rviz/src/indicator_widget.h create mode 100644 security.md create mode 100644 simulation/gazebo/tb4_sim_scenario/CMakeLists.txt create mode 100644 simulation/gazebo/tb4_sim_scenario/README.md create mode 100644 simulation/gazebo/tb4_sim_scenario/launch/ignition_launch.py create mode 100644 simulation/gazebo/tb4_sim_scenario/launch/ignition_robot_launch.py create mode 100644 simulation/gazebo/tb4_sim_scenario/launch/nav2_launch.py create mode 100644 simulation/gazebo/tb4_sim_scenario/launch/robot_description.launch.py create mode 100644 simulation/gazebo/tb4_sim_scenario/launch/ros_ign_bridge.launch.py create mode 100644 simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py create mode 100644 simulation/gazebo/tb4_sim_scenario/package.xml create mode 100644 simulation/gazebo/tb4_sim_scenario/params/nav2_params.yaml create mode 100644 simulation/gazebo/tb4_sim_scenario/urdf/create3.urdf.xacro create mode 100644 simulation/gazebo/tb4_sim_scenario/urdf/turtlebot4.urdf.xacro create mode 100644 simulation/gazebo/tb4_sim_scenario/worlds/maze.sdf create mode 100644 tools/message_modification/README.md create mode 100644 tools/message_modification/launch/scan_modification_launch.py create mode 100644 tools/message_modification/message_modification/__init__.py create mode 100755 tools/message_modification/message_modification/laserscan_modification.py create mode 100755 tools/message_modification/message_modification/message_drop.py create mode 100644 tools/message_modification/package.xml create mode 100644 tools/message_modification/resource/message_modification create mode 100644 tools/message_modification/setup.cfg create mode 100644 tools/message_modification/setup.py create mode 100644 tools/scenario_status/README.md create mode 100644 tools/scenario_status/package.xml create mode 100644 tools/scenario_status/resource/scenario_status create mode 100644 tools/scenario_status/scenario_status/__init__.py create mode 100644 tools/scenario_status/scenario_status/scenario_status_node.py create mode 100644 tools/scenario_status/setup.cfg create mode 100644 tools/scenario_status/setup.py create mode 100644 tools/tf_to_pose_publisher/README.md create mode 100644 tools/tf_to_pose_publisher/launch/tf_to_pose_launch.py create mode 100644 tools/tf_to_pose_publisher/package.xml create mode 100644 tools/tf_to_pose_publisher/resource/tf_to_pose_publisher create mode 100644 tools/tf_to_pose_publisher/setup.cfg create mode 100644 tools/tf_to_pose_publisher/setup.py create mode 100644 tools/tf_to_pose_publisher/tf_to_pose_publisher/__init__.py create mode 100644 tools/tf_to_pose_publisher/tf_to_pose_publisher/tf_to_pose_publisher.py diff --git a/.github/bandit.yaml b/.github/bandit.yaml new file mode 100644 index 00000000..c91b938b --- /dev/null +++ b/.github/bandit.yaml @@ -0,0 +1,321 @@ +exclude_dirs: ['install', 'build', 'dependencies'] + +tests: + [ 'B301', 'B302', 'B303', 'B304', 'B305', 'B306', 'B308', 'B310', 'B311', 'B312', 'B313', 'B314', 'B315', 'B316', 'B317', 'B318', 'B319', 'B320', 'B321', 'B323', 'B324', 'B401', 'B402', 'B403', 'B404', 'B405', 'B406', 'B407', 'B408', 'B409', 'B410', 'B411', 'B412', 'B413'] + +skips: + [ 'B101', 'B102', 'B103', 'B104', 'B105', 'B106', 'B107', 'B108', 'B110', 'B112', 'B201', 'B501', 'B502', 'B503', 'B504', 'B505', 'B506', 'B507', 'B601', 'B602', 'B603', 'B604', 'B605', 'B606', 'B607', 'B608', 'B609', 'B610', 'B611', 'B701', 'B702', 'B703'] + +### (optional) plugin settings - some test plugins require configuration data +### that may be given here, per-plugin. All bandit test plugins have a built in +### set of sensible defaults and these will be used if no configuration is +### provided. It is not necessary to provide settings for every (or any) plugin +### if the defaults are acceptable. + +any_other_function_with_shell_equals_true: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +assert_used: + skips: [] +hardcoded_tmp_directory: + tmp_dirs: + - /tmp + - /var/tmp + - /dev/shm +linux_commands_wildcard_injection: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +ssl_with_bad_defaults: + bad_protocol_versions: + - PROTOCOL_SSLv2 + - SSLv2_METHOD + - SSLv23_METHOD + - PROTOCOL_SSLv3 + - PROTOCOL_TLSv1 + - SSLv3_METHOD + - TLSv1_METHOD + - PROTOCOL_TLSv1_1 + - TLSv1_1_METHOD +ssl_with_bad_version: + bad_protocol_versions: + - PROTOCOL_SSLv2 + - SSLv2_METHOD + - SSLv23_METHOD + - PROTOCOL_SSLv3 + - PROTOCOL_TLSv1 + - SSLv3_METHOD + - TLSv1_METHOD + - PROTOCOL_TLSv1_1 + - TLSv1_1_METHOD +start_process_with_a_shell: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +start_process_with_no_shell: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +start_process_with_partial_path: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +subprocess_popen_with_shell_equals_true: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +subprocess_without_shell_equals_true: + no_shell: + - os.execl + - os.execle + - os.execlp + - os.execlpe + - os.execv + - os.execve + - os.execvp + - os.execvpe + - os.spawnl + - os.spawnle + - os.spawnlp + - os.spawnlpe + - os.spawnv + - os.spawnve + - os.spawnvp + - os.spawnvpe + - os.startfile + shell: + - os.system + - os.popen + - os.popen2 + - os.popen3 + - os.popen4 + - popen2.popen2 + - popen2.popen3 + - popen2.popen4 + - popen2.Popen3 + - popen2.Popen4 + - commands.getoutput + - commands.getstatusoutput + subprocess: + - subprocess.Popen + - subprocess.call + - subprocess.check_call + - subprocess.check_output + - subprocess.run +try_except_continue: + check_typed_exception: false +try_except_pass: + check_typed_exception: false +weak_cryptographic_key: + weak_key_size_dsa_high: 1024 + weak_key_size_dsa_medium: 2048 + weak_key_size_ec_high: 160 + weak_key_size_ec_medium: 224 + weak_key_size_rsa_high: 1024 + weak_key_size_rsa_medium: 2048 + diff --git a/.github/linters/.pylintrc b/.github/linters/.pylintrc index 70e1beca..21e84adf 100644 --- a/.github/linters/.pylintrc +++ b/.github/linters/.pylintrc @@ -4,6 +4,6 @@ ignore-paths=.*/osc2_parsing/.* [MESSAGES CONTROL] max-line-length=140 disable=no-self-use,anomalous-backslash-in-string,too-many-arguments,too-few-public-methods,too-many-instance-attributes,redefined-variable-type,unused-argument,bad-continuation,too-many-lines,too-many-branches,locally-disabled,too-many-locals,too-many-statements,duplicate-code,too-many-nested-blocks,fixme,useless-object-inheritance,no-else-raise,no-else-break,unnecessary-pass,no-else-return,super-with-arguments,no-else-continue,bad-option-value,consider-using-dict-items,consider-using-f-string,line-too-long,wrong-import-order,missing-function-docstring,missing-class-docstring,f-string-without-interpolation,import-error,missing-module-docstring,consider-using-with,unspecified-encoding -ignored-modules=geometry_msgs,py_trees +ignored-modules=geometry_msgs,py_trees,launch variable-rgx=[a-z0-9_]{1,40}$ function-rgx=[a-z0-9_]{1,40}$ diff --git a/.github/workflows/scan.yml b/.github/workflows/scan.yml index d31785ec..d90d30ba 100644 --- a/.github/workflows/scan.yml +++ b/.github/workflows/scan.yml @@ -50,3 +50,50 @@ jobs: format: 'table' exit-code: '1' vuln-type: 'os,library' + bandit: + name: Bandit + runs-on: intellabs-01 + steps: + - name: Checkout code + uses: actions/checkout@v4 + - name: Test + shell: bash + run: | + pip3 install bandit + bandit -c .github/bandit.yaml -r . + license: + name: License check + runs-on: intellabs-01 + container: + image: osrf/ros:humble-desktop + steps: + - name: Checkout code + uses: actions/checkout@v4 + - name: Prepare System + shell: bash + run: | + apt update + apt install -y python3-pip + pip3 install ros-license-toolkit + apt install -y golang-go + go version + go install github.com/google/addlicense@latest + - name: Check for license tags + shell: bash + run: | + find . -type f \( -name "*.py" -o -name "*.cpp" -o -name "*.h" \) -exec "$HOME"/go/bin/addlicense -check {} + + - name: Run ros_license_toolkit for each Package + shell: bash + run: | + git config --global --add safe.directory /__w/scenario_execution/scenario_execution + find . -name "package.xml" | while IFS= read -r pkg_file; do + pkg_dir=$(dirname "$pkg_file") + pkg_name=$(basename "$pkg_dir") + if [ "$pkg_name" = "scenario_execution_rviz" ]; then + echo "Skipping package $pkg_name" + continue + fi + echo "Processing package at $pkg_dir" + ros_license_toolkit "$pkg_dir" + done + diff --git a/.github/workflows/test_build.yml b/.github/workflows/test_build.yml new file mode 100644 index 00000000..1e1ed6d2 --- /dev/null +++ b/.github/workflows/test_build.yml @@ -0,0 +1,60 @@ +--- +name: test-build +on: + # Triggers the workflow on push or pull request events but + # only for the main branch + push: + branches: [main] + pull_request: + branches: [main] + workflow_dispatch: +jobs: + vanilla-build: + runs-on: intellabs-01 + container: + image: osrf/ros:humble-desktop + steps: + - uses: actions/checkout@v4 + with: + submodules: true + - name: Setup Dependencies + run: | + apt update + apt install -y python3-pip + xargs -a deb_requirements.txt apt install -y --no-install-recommends + rosdep update --rosdistro=humble + rosdep install --rosdistro=humble --from-paths . --ignore-src -r -y + pip3 install -r requirements.txt + pip3 install pytest-cov + - name: Build + shell: bash + run: | + source /opt/ros/humble/setup.bash + colcon build --continue-on-error + source install/setup.bash + - name: Test + shell: bash + run: | + source /opt/ros/humble/setup.bash + source install/setup.bash + export -n CYCLONEDDS_URI + export ROS_DOMAIN_ID=2 + colcon test --packages-select \ + scenario_execution_base \ + scenario_execution \ + scenario_execution_gazebo \ + scenario_coverage \ + --event-handlers console_direct+ \ + --return-code-on-test-failure \ + --pytest-with-coverage \ + --pytest-args \ + --junit-xml=TEST.xml + - name: Publish Test Results + uses: EnricoMi/publish-unit-test-result-action@283dea176069279a9076e77b548668a8e4f0c31b + if: always() + with: + files: | + scenario_execution_base//TEST.xml + scenario_execution//TEST.xml + scenario_execution_gazebo//TEST.xml + scenario_coverage//TEST.xml diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 00000000..52691286 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,6 @@ +[submodule "dependencies/py_trees_ros"] + path = dependencies/py_trees_ros + url = https://github.com/splintered-reality/py_trees_ros.git +[submodule "dependencies/py_trees"] + path = dependencies/py_trees + url = https://github.com/splintered-reality/py_trees.git diff --git a/Makefile b/Makefile new file mode 100644 index 00000000..807128ad --- /dev/null +++ b/Makefile @@ -0,0 +1,46 @@ +file_finder = find . -type f $(1) -not \( -path './venv/*' -o -path './build/*' -o -path './log/*' -o -path './install/*' -o -path './dependencies/*' \) + +PY_FILES = $(call file_finder,-name "*.py") +CPP_FILES = $(call file_finder,-name "*.cpp") +H_FILES = $(call file_finder,-name "*.cpp") +C_FILES = $(call file_finder,-name "*.cpp") + +LINKCHECKDIR = build/linkcheck + +check: check_format pylint + +format: + $(PY_FILES) | xargs autopep8 --in-place --max-line-length=140 + $(CPP_FILES) | xargs clang-format -i + $(H_FILES) | xargs clang-format -i + $(C_FILES) | xargs clang-format -i + +check_format: + $(PY_FILES) | xargs autopep8 --diff --max-line-length=140 --exit-code + +pylint: + $(PY_FILES) | xargs pylint --rcfile=.github/linters/.pylintrc + +sphinx_setup: + if [ ! -d "venv" ]; then \ + python -m venv venv/; \ + . venv/bin/activate; \ + pip install -r docs/requirements.txt; \ + deactivate; \ + fi + +doc: sphinx_setup checklinks checkspelling + . venv/bin/activate && GITHUB_REF_NAME=local GITHUB_REPOSITORY=intellabs/scenario_execution python -m sphinx -b html -W docs build/html + +view_doc: doc + firefox build/html/index.html & + +checklinks: sphinx_setup + . venv/bin/activate && GITHUB_REF_NAME=local GITHUB_REPOSITORY=intellabs/scenario_execution python -m sphinx -b html -b linkcheck -W docs $(ALLSPHINXOPTS) $(LINKCHECKDIR) + @echo + @echo "Check finished. Report is in $(LINKCHECKDIR)." + +checkspelling: sphinx_setup + . venv/bin/activate && GITHUB_REF_NAME=local GITHUB_REPOSITORY=intellabs/scenario_execution python -m sphinx -b html -b spelling -W docs $(ALLSPHINXOPTS) $(LINKCHECKDIR) + @echo + @echo "Check finished. Report is in $(LINKCHECKDIR)." diff --git a/README.md b/README.md index 3c052a83..8c735dc5 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,55 @@ -# Scenario_Execution +# Scenario Execution [![Super-Linter](https://github.com/IntelLabs/Scenario_Execution/actions/workflows/scan.yml/badge.svg)](https://github.com/marketplace/actions/super-linter) + +Scenario execution is a backend- and middleware-agnostic library written in Python based on the generic scenario description language [OpenSCENARIO 2](https://www.asam.net/static_downloads/public/asam-openscenario/2.0.0/welcome.html) and [pytrees](https://py-trees.readthedocs.io/en/devel/). +It reads a scenario definition from a file and then executes it, reusing available checks and actions. It is easily extendable through a library mechanism. +This separation of the scenario definition from implementation massively reduces the manual efforts of scenario creation. + +To give an impression of the functionality of scenario execution, the following animation shows an example scenario with a turtlebot-like robot in simulation using Nav2 to navigate towards a specified navigation goal in a simulated warehouse environment. +Once the robot reaches a reference position a box is spawned in front of the robot as an unmapped static obstacle that needs to be avoided. +Upon arrival of the goal position, the scenario ends and the simulation gets cleaned up. + +![scenario execution in action](docs/images/scenario.gif "in action") + +## Documentation + +Please find the documentation [here](https://intellabs.github.io/scenario_execution). + +## Setup + +### Installation from source as ROS 2 workspace + +Clone this repository, update its submodules by running: + +```bash +git submodule update --init +``` + +install the necessary dependencies: + +```bash +rosdep install --from-paths . --ignore-src +pip3 install -r requirements.txt +``` + +and build it + +```bash +colcon build +``` + +## How to run + +First, build the packages: + +```bash +colcon build +source install/setup.bash +``` + +To launch a scenario with ROS2: + +```bash +ros2 launch scenario_execution scenario_launch.py scenario:=examples/example_scenario/hello_world.osc live_tree:=True +``` diff --git a/deb_requirements.txt b/deb_requirements.txt new file mode 100644 index 00000000..f07fc8c3 --- /dev/null +++ b/deb_requirements.txt @@ -0,0 +1,5 @@ +ros-humble-turtlebot4-simulator +ros-humble-py-trees-ros-interfaces +python3-autopep8 +clang-format +pylint \ No newline at end of file diff --git a/dependencies/py_trees b/dependencies/py_trees new file mode 160000 index 00000000..8d8fc19d --- /dev/null +++ b/dependencies/py_trees @@ -0,0 +1 @@ +Subproject commit 8d8fc19d5f6c81bc2107039a7f0baa763a01bb79 diff --git a/dependencies/py_trees_ros b/dependencies/py_trees_ros new file mode 160000 index 00000000..247cf47d --- /dev/null +++ b/dependencies/py_trees_ros @@ -0,0 +1 @@ +Subproject commit 247cf47d509f827bb24464be376e8ed2ddefc0fb diff --git a/docs/actions.rst b/docs/actions.rst deleted file mode 100644 index 4fc809fd..00000000 --- a/docs/actions.rst +++ /dev/null @@ -1,3 +0,0 @@ - -Actions -======= \ No newline at end of file diff --git a/docs/architecture.rst b/docs/architecture.rst index e1ee3a10..b2abfd71 100644 --- a/docs/architecture.rst +++ b/docs/architecture.rst @@ -1,7 +1,8 @@ Architecture ============ -.. figure:: images/graphs/scenario_execution_structure.png + +.. figure:: images/scenario_execution_structure.png :alt: Architecture of Scenario Execution Architecture of Scenario Execution @@ -19,67 +20,46 @@ The scenario execution contains several sub-packages, namely The architecture aims at modularity with each package implementing a specific functionality. -Parsing -~~~~~~~ - -.. figure:: images/parsing.png - :alt: Architecture of Scenario Parsing - - Architecture of Scenario Parsing - -Modules -======= - -Scenario Execution Base Package -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -The “scenario_execution_base” package is the base package for scenario -execution. It provides functionalities like parsing and base classes. -For more documentation of this package, please refer to :repo_link:`scenario_execution_base/README.md`. - -Scenario Execution Package -~~~~~~~~~~~~~~~~~~~~~~~~~~ - -The “scenario_execution” package uses ROS2 as middleware and contains -ROS2-specific modules. For more documentation of this package, please -refer to :repo_link:`scenario_execution/README.md`. +Design for Modularity +--------------------- -Scenario Execution Gazebo Package -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Scenario execution is designed to be easily extensible through libraries. +An example is available here: :ref:`scenario_library`. -The “scenario_execution_gazebo” package is an extension of the -“scenario_execution” package with Gazebo/AMR dependencies. For more -documentation of this package, please refer to :repo_link:`scenario_execution_gazebo/README.md`. +The entry points are defined like this: -Scenario Execution Control Package -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +.. code-block:: -The “scenario_execution_control” package provides code to control -scenarios (in ROS2) from another application such as Rviz. For more -documentation of this package, please refer to :repo_link:`scenario_execution_control/README.md`. + entry_points={ + 'scenario_execution.actions': [ + 'custom_action = example_library.custom_action:CustomAction', + ], + 'scenario_execution.osc_libraries': [ + 'example = example_library.get_osc_library:get_example_library', + ] + } -Scenario Execution Interfaces Package -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Scenario Parsing +---------------- -The “scenario_execution_interfaces” package provides ROS2 -`interfaces `__, -more specifically, messages and services, which are used to interface -ROS2 with the scenario execution control package. For more -documentation of this package, please refer to :repo_link:`scenario_execution_interfaces/README.md`. +.. figure:: images/parsing.png + :alt: Architecture of Scenario Parsing -Scenario Execution Rviz Package -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + Architecture of Scenario Parsing -The “scenario execution rviz” package contains code for several -`rviz `__ plugins for visualizing and -controlling scenarios when working with `ROS -2 `__. For more -documentation of this package, please refer to :repo_link:`scenario_execution_rviz/README.md`. +The Internal Model Builder, implemented as a Model Listener does an initial check of the model by checking for supported language features. The Internal Model Resolver, implemented as a Model Visitor is used for type/variable resolving and does an in depth consistency check of the model. -Scenario Execution Kubernetes Package -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -The “scenario_execution_kubernetes” package contains custom conditions -and actions when running scenarios inside a -`Kubernetes `__ cluster. For more documentation -of this package, please refer to :repo_link:`scenario_execution_kubernetes/README.md`. +Modules +------- + +- ``scenario_execution_base``: The base package for scenario execution. It provides the parsing of OpenSCENARIO 2 files and the conversion to py-trees. It's middleware agnostic and can therefore be used as a basis for more specific implementations (e.g. ROS). It also provides basic OpenSCENARIO 2 libraries and actions. +- ``scenario_execution``: This package uses ``scenario_execution_base`` as a basis and implements a ROS2 version of scenario execution. It provides a OpenSCENARIO 2 library with basic ROS2-related actions like publishing on a topic or calling a service. +- ``scenario_execution_control``: Provides code to control scenario execution (in ROS2) from another application such as RViz. +- ``scenario_coverage``: Provides tools to generate concrete scenarios from abstract OpenSCENARIO 2 scenario definition and execute them. +- ``scenario_execution_gazebo``: Provides a `Gazebo `_-specific OpenSCENARIO 2 library with actions. +- ``scenario_execution_interfaces``: Provides ROS2 `interfaces `__, more specifically, messages and services, which are used to interface ROS2 with the ``scenario_execution_control`` package. +- ``scenario_execution_rviz``: Contains several `rviz `__ plugins for visualizing and controlling scenarios when working with ROS2. +- ``simulation/tb4_sim_scenario``: Run `Turtlebot4 `_ within simulation, controlled by scenario execution. +- ``tools/message_modification``: ROS2 nodes to modify messages. +- ``tools/scenario_status``: Publish the current scenario status on a topic (e.g. to be capture within a ROS bag). \ No newline at end of file diff --git a/docs/conf.py b/docs/conf.py index 9085b258..162feabe 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -14,8 +14,8 @@ copyright = f"{datetime.datetime.now()}, Intel" author = "Intel" -version = '0.0.0' -release = '0.0.0' +version = '1.0.0' +release = '1.0.0' # -- General configuration --------------------------------------------------- # https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration @@ -23,7 +23,7 @@ extensions = ['sphinx.ext.extlinks', 'sphinxcontrib.spelling'] -extlinks = {'repo_link': ('https://github.com/IntelLabs/scenario_execution/blob/main/%s', '%s')} +extlinks = {'repo_link': ('https://github.com/intellabs/scenario_execution/blob/main/%s', '%s')} templates_path = ['_templates'] exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] @@ -31,7 +31,7 @@ language = 'english' linkcheck_ignore = [ - r'https://github.com/IntelLabs/scenario_execution/.*', + r'https://github.com/intellabs/scenario_execution/.*', ] spelling_word_list_filename = 'dictionary.txt' diff --git a/docs/development.rst b/docs/development.rst index f93a96d1..e300616d 100644 --- a/docs/development.rst +++ b/docs/development.rst @@ -8,13 +8,13 @@ Contribute Before pushing your code, please ensure that the code formatting is correct by running: -:: +.. code-block:: bash make In case of errors you can run the autoformatter by executing: -:: +.. code-block:: bash make format @@ -23,7 +23,7 @@ Testing To run only specific tests: -:: +.. code-block:: bash #using py-test colcon build --packages-up-to scenario_execution && reset && pytest-3 -s scenario_execution/test/.py @@ -35,20 +35,22 @@ To run only specific tests: Developing and Debugging with Visual Studio Code ------------------------------------------------ -To prevent certain issues, please use the following command for building (remove /build and /install if another command was used before). +To prevent certain issues, please use the following command for building (remove `/build` and `/install`` if another command was used before). + +.. code-block:: bash + + colcon build --symlink-install -``` -colcon build --symlink-install -``` In VSCode create new debugging configuration file: Run -> "Add Configuration..." Add the following entry to the "configurations" element within the previously created `launch.json` file (replace the arguments as required): -:: + +.. code-block:: json { - "name": "scneario_execution", + "name": "scenario_execution", "type": "python", "request": "launch", "program": "./install/scenario_execution/lib/scenario_execution/scenario_execution", @@ -57,23 +59,38 @@ Add the following entry to the "configurations" element within the previously cr "args": ["-o", "TEST_SCENARIO.osc"], } +Create an `.env` file by executing: -To execute the debug configuration either switch to debug view (on the left) and click on "play" or press F5. - -On the first run, there will be errors because of missing dependencies. Within the terminal showing the errors, run: - -:: +.. code-block:: bash source /opt/ros/humble/setup.bash source install/setup.bash + echo PYTHONPATH=$PYTHONPATH > .env + echo HOME=$HOME >> .env + echo AMENT_PREFIX_PATH=$AMENT_PREFIX_PATH >> .env + echo LD_LIBRARY_PATH=$LD_LIBRARY_PATH >> .env + +In vscode, open user settings and enable the following settings: -Afterwards, press F5 again and the execution should succeed. You can now add breakpoints etc. +.. code-block:: + "python.terminal.activateEnvInCurrentTerminal": true -Creating an Action + +To execute the debug configuration either switch to debug view (on the left) and click on "play" or press F5. + + +Best known Methods ------------------ -- If an action setup() should fail, raise an exception -- Use a state machine, if multiple steps are required -- Implement a ``cleanup`` method to cleanup on scenario end. +Implement an Action +^^^^^^^^^^^^^^^^^^^ + +- If an action's ``setup()`` fails, raise an exception +- Use a state machine, if multiple steps are required +- Implement a ``cleanup()`` method to cleanup on scenario end. +- For debugging/logging: + - Make use of ``self.feedback_message`` + - Make use of ``kwargs['logger']``, available in ``setup()`` + - If you want to draw markers for RViz, use ``kwargs['marker_handler']``, available in ``setup()`` (with ROS backend) diff --git a/docs/dictionary.txt b/docs/dictionary.txt index d9eb061d..8132e16b 100644 --- a/docs/dictionary.txt +++ b/docs/dictionary.txt @@ -4,12 +4,10 @@ devcontainer rviz unmapped Structs -kubernetes submodules namespace enums multiline -amsrl buildkit autoformatter behavior @@ -20,3 +18,11 @@ nav backend osc py +vscode +QoS +dataset +whitespace +odometry +tf +amcl +RViz diff --git a/docs/how_to_run.rst b/docs/how_to_run.rst index 78e2e67b..ba8251a4 100644 --- a/docs/how_to_run.rst +++ b/docs/how_to_run.rst @@ -2,157 +2,6 @@ How to run ========== -With devcontainer ------------------ - -Preparations -~~~~~~~~~~~~ - -If not already installed, install the docker engine on your system -according to the `installation -instructions `__. - -Make sure you follow the `post installation -steps `__. - -To make sure, that the docker daemon is properly set up, run - -.. code-block:: bash - - docker run hello-world - -Install additional packages to build containers (buildkit). - -.. code-block:: bash - - sudo apt install docker-buildx-plugin - -.. note:: - In case you want to use the devcontainer with `Visual Studio - Code `__, you also need to install - docker-compose via - - .. code-block:: bash - - sudo apt update - sudo apt install docker-compose - -Run devcontainer from terminal -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Prior to the actual start of the container, run - -.. code-block:: bash - - xhost + local:ros - -To start the devcontainer without GPU-support, run the following command -*from the root directory of this repository* - -.. code-block:: bash - - bash containers/run_cpu.sh - -To start the devcontainer with GPU-support, run the following command -*from the root directory of this repository* - -.. code-block:: bash - - bash containers/run_gpu.sh - -Inside the devcontainer, you can now safely run and test your -development, e.g., run - -.. code-block:: bash - - ros2 run scenario_execution scenario_execution scenario_execution_base/scenarios/demo_wait_and_log.osc -t - -For a more sophisticated example using a simulated -`Turtlebot4 `__ and -`Nav2 `__, run - -.. code-block:: bash - - ros2 launch scenario_execution_tutorials turtlebot4_simulation_nav2_to_pose_tutorial_launch.py headless:=False - -and you should something like this - -.. figure:: images/tb4_scenario.gif - :alt: turtlebot4 nav2 scenario - - turtlebot4 nav2 scenario - -In case you need an additional terminal inside your running -devcontainer, run - -.. code-block:: bash - - bash containers/exec.sh - -When you are done with testing, please run - -.. code-block:: bash - - xhost - local:ros - -Run devcontainer from Visual Studio Code -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -.. note:: - Make sure you have installed the necessary VS Code extensions, namely - the `docker extension `__ as - well as the `Dev - Container `__ - extension. - -Open the root folder of this repository in Visual Studio Code -and click the blue item in the lower left corner - -.. figure:: images/graphs/vscode1.png - :alt: vscode1 - - -Afterwards, select “Reopen in Container” in the Selection Window inside -VS Code - -.. figure:: images/graphs/vscode2.png - :alt: vscode2 - - -Now VS Code should open your current working directory inside the -devcontainer. If you now open a terminal inside VS Code, you can run and -test your development safely inside the container, e.g., run - -.. code-block:: bash - - ros2 run scenario_execution scenario_execution scenario_execution_base/scenarios/demo_wait_and_log.osc -t - -For a more sophisticated example using a simulated -`Turtlebot4 `__ and -`Nav2 `__, run - -.. code-block:: bash - - ros2 launch scenario_execution_tutorials turtlebot4_simulation_nav2_to_pose_tutorial_launch.py headless:=False - -and you should something like this - -.. figure:: images/tb4_scenario.gif - :alt: turtlebot4 nav2 scenario - - turtlebot4 nav2 scenario - -Once you are done, you can cancel the remote connection, by again -clicking on the blue item in the lower left corner and select “Close -Remote Connection” - -.. figure:: images/graphs/vscode3.png - :alt: vscode3 - - -With local installation ------------------------ - First, build the packages: .. code-block:: bash @@ -178,3 +27,8 @@ information of py_trees and parser: .. code-block:: bash ros2 run scenario_execution scenario_execution $(PATH_TO_SCENARIO_FILE) -t -d + + +Using RVIZ to trigger scenario +------------------------------ + diff --git a/docs/images/graphs/osc2_namespace.png b/docs/images/graphs/osc2_namespace.png deleted file mode 100644 index 0e3f91b8467256e89bca282bfd872abca210a7b2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 221963 zcmeGEhdl)X`9>gvvfv5-O`w+?7KE@ky7k=?N)E9Ahs0Udn5-|m){LU1BaxK&?$Qd0rDNZ!9 z!;eFXw{F~cwsLVsK0cc60NW#z$^a(v-23QgtM2nWJW8=>r?Wgf)x~WiwjolBZ#6P8 zS_|d{&J&nOL9^hz^3hD<$o$F$fwZ)=mahhK=|bjBk4K!Rddh~r?LH_ZgWRQmU-UsA z_g4z%#$GXa7Iadkr?~Bt#NA?-DgJ#YJ-@PcT39qE`mfxvZf4$-r0^y?uI|+l9!!Oc zQ*ug5ZU2jtHvWIzyK>Cb=EB<(ZDZqoHr>o3#T{`OdS#uSZ8GpN!o4?EYnv5M@+qR6 z-m|_{d~Q+~p|w^&67Rz=voRlLu@LWkLwvS|JF}(S$0yzBe{bvVk$b2BtH*2bBER6R zoT5<(qL~$`2}5bAahBlHDSmwD@In5LAd0)?CLO4>&Bi~|w`~iW|y8%qcO;ub_PZWYUPQ$B}D#xPRa`*Ha zyg-@y|HT|Wl4MrvK4G1(78}r~^nqVEGa(^%KfYuVo!*+R*_a#9Q)oXhSjDdYUQK4B z75*JHH6GRwEr=Ape_wqepBXC4SI2mdp|PLW;h^BoT|0a3oR;shu1mKG=1jEe6R)`j z(K^MGUdEUkYLq%MW%e~M{t91cT4CWMF7IUnx6yMwi@=bS(p3))< zCZa8IMS;t0@Q~GtuU+$X9SQFLyy}h}s`Bz2#K#r8c*WYNP23$l9#ecvJsyM@x8X?K zx!Ka$U%U==dGUISZ+-LN@<2!dm*di8w~CT+ z;R0EED65)FFt5hG$8DsxCY1Z!>C+Xtew1I~ye89q6^D9PZgl%>ZD>43nIDv#zJBvJ z_7f?^>J-8Enfh%jz#u1yX7;w8L?zfH+)RfZ!B@4>9#-G>i6+WFQUS{eks zCq#)W(woah;uE->|L^E!P63&L()luq}vl2WO zEoPrMKiS>Y`dx9iUH85o^9Mb{42hNU=9bmIPZ_CH@bQ)#E0wEW|U+WU9!4wL?# zLu!q5PsojRtM2^g{pL1s*RF!L3zJ(WrXY` z=bPkQB1{{iA_)&t)bX@AVW+VND|3x9CVvX;$)lD&j3=f4aK1sQ3Y5*iWA)S2gpxAY zZWNMtgZfK;Nv69TN>^@IrnGJO=4!ffv`EAH`!Q;JR#Kbqk1pEak64!;i_DNof$r)& z!AjYEsIyY;^H(x^RHB4#6PN!UNUx8R>dHkY#VY6K?Emk!^xgj9->>hzlETPw%W@D+hH<$cpb%8bn)goLg$F!EB@ACw+k(6ZJD7B=cet?hZR-VyQ^%p4T zk9lkh7gJ*lF<(ZyY|F#pCOzo!TGH*ve-dr6pqx5HJ|&`q+=HTlUO>XgWkJ}Rr6y+U-P|E zLfK-Ja7(8?w?fcc+2?yBF{ATiZFN!iJK3287naa-^@1u&j|WFa>Y%2a5+E)ot}pfa z;PSrM1@v=%?s06C!VTA7tvWwE%6;2x~kFnDnNXh8k+K5kEVY{t#=s)js$EoZ+(pBl_nex_|zT1{>IP-pD zmS@2)cDv}itx{7nE&gm@+1R4#?+1pU;)v!oHC3ZcejQbxQ?C3`zO^aQCtKL!6e}#& zwvgcD=jH62zjDX8sd`Y2B`zlBvYOPw`@Dmrb8JDUbYi_0JIG$6xpSMP{KAoB{YpDq z>>^$49dD=xveDG*66cXhf*bBK3Xw9+|L+@o+AV*RW3yu4$z|4Msyi9I;o?LVVcvsc zl{EUvSTx_Fq!K8&y3y;k6q`o(K{Y4yG=bo|RgH3qX*(oK$z#sfwkfJ&sB${%V^Tcq z^x4A9x67uaq1BV*H171o%7>y)cxBUFtThz^-3uKR;I%S4WLoEg9xCBM`>!X;2M*5G z35fDlIChwP&_eAzeE6_(pc#DZ5@A-E|Gve$TJ4q7D{~{-G-ip|OkGM2`Bbsb)+X+p zWDAKj)TXJQN8U})B*a-Ps8mw!)+-Z8MYbK;RjuO|J2FFL-p?1gPZo^~e$e;MBD-kr z<8pochTMf`F55b8Q&<7-G_9u`E={@F9{Tq^Wgc~(?#>8}BT3OvL(Qnpa3i+US=R{l-}m(SLPlD4aQ+6YxJrWriYoc|+Yaa=`%u`o ztUtw3;_2LaPFRnxmvsu8Mlk&^xZKTa6pgy5%}Fovm|ZSxAcs3CueA+2^I`k7*kHU5 zEwdnF>8650fCXO;)cfenvF3QB$kh!uM599LnQ^D(0zUFhVUz!#t-RO%-A>oX6?zG7 zI5zlh+2A`RWxi_*;~gYSSI0#k@|VRA!N!Y2omK>4?HQBKTnqB%;17?fGM>~p_b+Mk zTwZGCsjp|L!%Kf0)x@Vt=Q1Xu#0KBWA$Y9yyOP9{c^aj$Rg$#hczvg!m$-~=2@Akh?Zli_q9r0?ZZR=X7znZ$6wQqqqffQYGhmy{_pFZQZ`tw6DYq7 z9S`)FqhxEVv@mSZtuiiyPSz68v)bhl?w;%W! z8D-|uv7`T<`Pt-FicS|yKPGrsj8#JLP=`U$!fU*<~avntUdkx^xU$f7cr zXP}SVfn`f`!^su~5MEwZB{S(4Iiz&_57K=<8nA}RDRP?|cA)6GL}IXL*t%p*f*!o| z^2`7N$Z;BuL(&hQe`d-Fq21PF0_93`%ojt4V7C_-mUlsa=ds>v(+-Enh59 z9JdVM#@6zskm`3k9u#oo|NCN*IjrN$`EL9=fDhx2Y!jU6R8FIGSeTl0M{8nlh|K1w zdD*~8@8yc-r4ShI90C{c$9YHnhIc)VhFwkUkeWipo_LW?G^lUZ&&pO|I zTo*hhi&9rK6H;;#kVE5c?Vf&4T)d+*mgH9pF%K>mE6W=i)@Zivf4%?6`A5~l-HLg;AFgEbr?z~O-JLFH;6`mpQBrn! zM`{f06nCh7cdn#+%))naUw9x<#OeXte>nQrIKQ%Tj$8K)AmooE`z zBwfD-p(MziX8BLLOeX}<1J5>fiLi+q(wj)3pZ$5AoY!cSORNCaYk@kRXTI<0Skuytm8^SP zKer{Kr}QZXt{32kigOlw@M-Egg|AGuI}Asfb#4+_mCD=~>Rl*013%w9nMyKTnJDP3 zcd5oB_bL4C+sA8bnwPm1gN3$sg^s;A>HXDf;!=d~?tM{H!A}q(JuyX)UvlvY;*#og zf{p6hyzHYCE%HPM;Az21ZRnGqLC5e20%`+J+tquHCFNnd2ELlhqyFLDyN@S@J#9*7 z6uPP(=>az|A(BcG6VFg!na9UEa#AN6XHrKuXXi<3AXbR2cE&*;$X}w`iqkT3bfAC> z%ZL|y&NnOK5s18MZLn1GumJjAiK@he5C!1)lgW$MRN^E%oEAIGx;B}GFY?5>CemQX z1(y!%@Wj|Xn=oo}0BHMh%E1&iA5ZjJ>)gy3d%rl*RRWcKI7-HcSoESMxjJ8Bvar&r z&v#$vCYSGphGbnN98!LM2=0fA)XHEO9!QjHtSV=vLGBJBSxZV8NYrH*cSnrG4^9%Y3K2CQG4HK=Fr~8NX z&cyGPf^E#0m^wU~*gppB#Bfsl+B#eyJW}5mXZB_z$_F}bPgub;=D8#fPC4=~8ZMQ! zkHV*4>S|IZlY9=IOWiJb`0qCO>*=6X6-}1T{eC&RW9ZE$AJpv^I!0+woqbg1o<{=~o$D3j%imdXszriv`+&39-pHm;R+Sqe3aIC#k|xkvUE-W5ulZ)v zItd>f&*IP8C>jV3IAJNf%Z}IDl2m!$)D$=j-N_l!x}2eP%(|G-Uv(=(-F@$vt9m59 zoS<&2?@)V=j42K60}@g|&LCfe_cDIBh5E(`vnIzZo{Uj{@ZuRhg!T%bo=zB%XV*Oo zP3~HzuOM(0D@-?3oW|Vcsmy|&Y#hORww6alsSlR>7XWE%6_t(ZlRh8GHAy~=gyOMF z;-jCQ55lTn&8$fAF>)#=uj!V1msv2K^ol=e_iZP+b-7{@7^qftm=&Rnoa+}+uw-2X zC+<<*-%&KR0$a%>S`%p&XOY=((x%v2j-XeTG52a))CmZ{S8Vn@KZsEuqZQAGj&_*E zhXdOBg>w00z!!PQy4Pn5N=dK2s`$`Rn$!{g5b4#=3&&;v6bkWGq|{}OuK06tf05Wg zZy#9tjJJOMs{DIKF;-c3C^skvT8Vzw7&Qz2I0SaQmXdHDe+xgayH&EJ@7aNRwlk4o zEcho~`KAY)h4zp?)lfKBeG_T7tw!;*hc5yHPOnWA#Ot_IQw$DX^VwL?IOUsl2dTPUIfu^HQpMF5OPDG8&!D%$HVI%{flq>Ad>cs5;o8 z>q$W^G!|v6QKZSN{z-{F_^*e$$}4l=*&~f2!18L*9tjF9>rsvoYewg@12c+fLK;{MbUoSQJM~e3cXM{l zARsuR=I;IbhWXBJn=2!k&EW}u%+~k+aCCIc{LNOu!8BPr)|NgLB>4N~$72UuL5h6h zWPL!fNxd01dl1V0ex+0RoV(^1Q2Zx7r+qsZP->`0(re>6Z-e$0p$V96UoI3@&|ji7H4U*(Gb#e8a^Ge;rwZp8h*FQD0H*O5hMY={yC^>b%^$2 z`LCdzIE=+(b5KGkH1;iY`Y6mpU=QS5JwJZDHJ&q=0b*LapC{(A<)Tpif!5a7=yRX+ zPR*Ya7H;E|qSCVDqoF>3XQ(XQrZLPrUwT3j3qK}k`Z203&x&#fG-nk)XX;Bqrbww~ ziy~TUnvvz1t+n2*^|ARDfEZSmjUbTSLgemq{JDb9g3pt*Q7a?19G_*TfIo`l^?5+Y z%SiJ`UmH=8s2wkvBEAa?Gm`q?9vvELK<7OqUl|Myv$RUFowD5?#4_C_sfS zBC1r{!xW$0Sk5j7P)EvHv(X9ala`8sh*-4h1wSYAuJRH)-)hd>++2f;#N1@b6sF<} z4;rnVYU144EGzMX`d}&(lb6kvBpo+f{kb|k-g~vyGgXk&VFOkX$0kkDaeUKek$`qz zn&g8P)2lV__>oJFlBsPLo}%>O7a){+m$hmNjs2F~3+B9t({^_hn`rO$b8=A9HPx;O z3TEDa@W9yVLQ`UYNAm5kj6*+F6{1p8Q#}|{t!^v{swD+3c;P~d5>w;7JJFLXa`DgM zs!d&Xucus$bGrRvwri|@GC}a-3FmeL9GfH}HtE<`vEqhhq->n1Emi2BA5Kp3o}?{! zB~-h6=`SmVgmAWqnm2vR^&^8kVdd19rmE-*;v^r8|F1wUx%9c13mZC# zK4FNGq4bz)&06d!=QKasY*b*BG|9f|p&==)QIPX0nB`!#@;}M+n@Z*Md}u8;5F}{rLwP;) ziYM+$@0(ls#GAJ3}RQO7CUv$C>A#t+s5eb7~tUP(^( zT3gJQ=~5SmJJp~@PvpfHeqX%${sU5kJyYwPNGhTo-fBb0DW!l!YO@(`R#jDn59L-Y z4i+Eg=!!Se1dKmquaERkUEq>=8!oI$&}(U{G=d8s2oUQ^jl=bk1H}Lwb+xp#@@4Aq zf1JCX4C}wBhB9ZhRwxQ@4b?ZZ(Cd@08OoP8hD`NQQ$-RASl~_r&{#-TU|N3oR-5 zCmvgIzjp3B(dP~|SU2pviUTVfTNJFGzR$*xJLsW0uxcR_jf)Rdr50Mh#thWQN>JQ; zyQI#mr2xvq1M{jD2JLN5y);_dtC$8$RInM>u_0-@EmO#x`#PT!)V<+$$-=?{4-mI{ z0oq(-d|x!+uQfvH>>Wy+$E3xYqf|HoY2Y;xS~U) z^DgNvH#{ceUAi(EwFbxHgzg1$BD-UC&@rP;lX*u6`%7;dg`bVQ5$*ZvwQ(r|!JVEi z&*;>xT>wt!ed@wY+*6=z)86cRGGqi^F z$uR+r?w9jQWJ(fGyI&AvssyDL(?!s{jFNE1dO;T^FRjslQe|yKIuAuz;jeC4et^^V zBmDh)&@^j@AVnQ^6w8PMvFminIr55UC|_1dO!p!fzwE=3!2$AmgB0S zU%GaIP5zRZrqI)a!uo4!Rf)0T>l2snM{>z5aP;R6D2H%K?ed;n0{^eQ=Ywu@by`JH zdF+{S^AXI%BWo8K=W~xx+qiDWQ#077*!iZDpen)@#<6>kdvCoS07sY`9`iTwK zOK9}9PAc8~lHN>*=1|m2PgRBML{MsnON`>fu9WJRd*|z?Kf<1!1FNk;Ei)2)x=tt^ z?5I!=YadJk$SBcAEm0vF$f3wE*It5oFujT-GA$}+5ZdpbWP$)R~fpeZ&xm-}6q z*Gmm;^i_OI@+hP4ZAt1aVlxBi8@OKl- z1@!%nN!W#n2cJBh?3xluVzhS*zJHC=nD`J}y24(OniMv{B{!7VpSoABBAK+itJ`HL zQT@Wcr~uW4v9_GD@>z#wdG^RD=3u0mV)SIEXk|-1f|s+h?dHO+EGL?;tp> z$D!BzbghvOk6zJ{NNMj@8%k7?*%QV!H$GY50Os!9TN1bam6NGwTme(y6y~$`Me2Y8l$=Ms=rG(MXWhmPnDjDO{kc>I(q+{ zZ>K;EK5`2_=trMJI-RmVCpURNfb`eCe&FBAS-+YLoB4$F`;P1nA3t7z;wO~XPEL^9 zmowA>__bc6F9t;6**}hrkx`C-eZoPmL!4L@CG4YI^U#i2@Cj^84}@C(czMXQE+3CxeE5&3)dS#Myy>wR}m$Vgp9l28Q2x z003YE2r<5J0c|3mpJNJeIPRPnLP5pHJ}1F)Ki>C}GZ&A^yVK)2r=nQh{aBou9F}2} zDjF?n8(~4hMPddo9Q^*g&Fw}vmZT!Qx<-)Q)~qdkT|j|a8>j#3zF@fmEkc=3OlZ)t zrFlE$0BESL^@g0>H?-3jFbb$tN+Qap%6>f%&mEiHYKu#4M5nxMPXyvr0LvYcW_dBpYPvH3pmRVJjHFw=s$SIR!xi zLE$a)zBKOd&r$A{?ZZl6m&|x}QoNSB*=L_B2|ww45ODCMjb)s;c$~z&`}fZTvI~gh zeVG>=LP92%Gm6jiw#EEsYLzOe)01_6`;QC)inyBBj;%fS;Uiz;Gq(&MP@fti%y#c( zd@J}{tg`inl9_Roq+7P<`b@QkVjiLmdZw%*HhrY9RYY0`sUr)U|I*IR!MgSLjqMU~ zYMH)LuBLX1Gb6Nr2%Gyhn58YvFI`T+m@4!f3R@^e&jS)RY&_hR`zyJ-;Pt8ITZRt` zUBFJz_?#wa=l6QA1Nw0HaeZzHqgPx4aEfd!7oUk^zM`=Vx;)(LyJahn`7A(!qLUye ztGFm?^QXOaoX&`0)PZwzm7#KNX==)R(Dkc1{iv0tGgIa6tJm5o^m72WKV~i`$+|lA zs0llP^|u;>x=uIeb$CB^&>jp4l?J^lAq(J$OdLIKlN#$BmFIW+)beV~XLYI!0A7RW zi#N;$iiV@ClpErlHL%&GN47ug=Sa9}ASs&G34WjMrjuaQROE6?UI&AP{QhTK3b!YJ z$@n#^Tq;RT2KAmQkREtNa#cL?{=?m$?1KD)&U11sjyA(0S5s;PWBHvygU7M0F^l!> z$T1Ok_uY=^0oHx`Zu32l%{{Ee{P~jmx9sV}_)*Hkxrw}s{I#0Wn`^fh7P`UI z*7SGGMWh#}J&Y$r>SL4LC0m?|Di8Uk|M+oJ5k)eTVnpoYPaWCpur=rw_o~;dVBmlc z_-?YhBpNeMnq$#d!ka6;u@eYPu2#_Z8Q?%|#}cnkU%e*j7o!};^%`(@RRThk7^Gt) z`PHyO&sCk$ld|Gm|L!MoN~2%@u64Y{!BqsjV#K`F>}-(TYh%tti|P+{O;`RBGg%Gai#_KaMrp)^z+Wj@K6jC**WE|B@(nD(Q|63194 zjcZ?+&jKl18y7k@R&M5uy|`09_Usw2m5bZEXSmbAmHynhbGN|+hNIkU0EZ0G+Bi3s-RH8=}Hu`eVO-#HYwJ z_7nY}=bqNVAmCLVk3^3mv?Fuogi^!Qww#B?A|l``t5^ z$cL0=2H1}t{fK!ynq~Iu{Y9K90a{&4hL)gup!cdMiE@v`>p@*Lb`LYZY423v|<&ikiMBLqn zK@1@}&=2y3-RqA})PMVI*T@eZe$f??WGBrPt_V~}I%c&(xuyx=>zo?OSZa?P&q+gG3S^vRHh zxq!}=u4XOz?ag*o;NUV;#hn!ZeL_2-EmK=`1vuj%eAYbvn6@8( zs{#?$mUUwf4@q<{1I=GiV4}tjf@{!?(PLU>r=FJG(h@8{B+@!PN&kM(y02=-`3o{0 zTv9$pRQS!S%PXlPbhD*{xl}9L_*Dl(41knKJ`cqc_I@3&8IhPm$L!^!NtOEU)N}D9 zp6X{1;fl+bN&DUt?vnWfj7v_k_bINyJgUzoV`5I^uyP^c3E?vnpj5vHAn-d^BLpAvndG`S)~0k``Qu~E z^A}en-7Q#%rVX56@c~>@@LyxOm{g8+rnmKcGxqwNYB05*v9hwEwr1Ln6s+5`XLW&e z%n+v*57k$QF(kP;4lJ+oMlUHA-w=Z84%@PYh;`5&Z~=Flm$C@IA5~zqW$xcJlDMps^2@pQ_FY|k?0@V|&+tMc7SJJiAi?Z%U{8R49F+}zwu>*A#KL$l-Z^psZt zsv)X+n*9ZQk{GtN2~^|<0~YtoW){}JJnoVCG6E$uT(rlv65NZ8F? zxy{4q@lf-F0@8m`rjB2fb(KfFcGlO3OX|>Rks3)Ja{~h*^P+t!U=7T!x?1TEki5-j z*+2h%8Vm+Y2sYHr0I29}WubcV?LVYu;0l^m$FtbnTp=(x3U_v_O zIN(Jz;fiEayoo2BG?5(7#I8?BQQgv0hrShzzFP))4|0$YfNp|??AJWYwqMq6B96n# zIjqs1UcV2XO*L@6Y=3y0n86M%qeUzgb@i13|3iK)IVO$YJ4(J`beSzt_**mm3-rtL zNK8)Lak%E8rmhKQBgbpaSsZ-3A<&eB`FtyCrbm(TUkA|6)-n$CDs|HX&EGXS@P93^ zVv>RWS9G>;boX-u`iXnK2zKs1D0vF*x3F*{T$xiys}$yCde(TG{umAX*cDC_Le4wv zczbiJ;d6qPV9aHu!^{wp1`=}}%l5CXE^-{>x}i$W2_6jX51#;JuJN`Agd}k|94hHP zNSc?Ih3P0yV|;MuX}<&I7u9h!DIfIUNOS{+BP;KE$xp=H)+{}k;F+0qe814wgKhOk z(cy)J-;PAwA6QN9vBs4n$vD=EK4W9oQ@CG>z!Az` z<=yMIgpdLht7PY+ckbMQtj|?P*6m7I5!T1>H^!Rt-B@u%&*TloW3=3^nd^#`qwXC& zCtUv6gHzHxic}JiFB>^u4H1BR|HSOe#R=&+9{vu^@RDJrpX(=CH6&HAINpJ)io>sc zUSoA`9%8^s>8MQ>4luhx$P5}b_D2-qz>NF75=d`D_`uWOd37m4JyjLQ_6W&?m4fU8 z>4d_q$x*XC`c~KXjoIFGvZy8?&e_1oG2L>ByCi#BqeU;VjMAuzK&um;(-k<4pA>1f z*H?T%n4X3D9f^5}wseF51%z-yBxhg#0UZxF9OTVRvLH7CWhWhu1b<{?VX7BF(Q1-2 zH*e`_`m_@Cd#!GHeA~HCEUHHWL(Qu1@^FDrMoXE8i+Xw_lBI)&XKMK{7P|5*Bn&@d ztecqG!Q>Il`+{|T2KmdT)?YWjXWcU+%`RXd=BffjQAYh=wevmNdc_mW4UN9h34Wo= z@e(fhw5oi_uU3uFQ~no%Rs|@P%g8192zCfU4(>Dazy+9Vu)%271cLDKk%nj zje~g@x?JSb|J`5XQCf(Sgw+E{@&|TZhSMz7tJeei!8Dp))zQN?%Oe>LWNFUv#?Q!&K3?ZAvCYkc4{1^?3+AKAL$Jcz&sNobddTWJe;AG9x)4OZB*ccva)&;QL@k9}q2+Ggm>TbU$IRl6 z^@`?hV#JsIiXX+n-li?%tKDMHBbv^8gzZ90=lA#bA1+A@AqZD)Oq@DQH7rYd8)g!> z{YkDb>=9u(1){$G=aH zCemWJuh`Q*dUr5!6Fi&qR{#2faI6@@Wy=~q$tFOj}9i^+QKpmQLsKJ@fZDQEp^O} z%N0fMs$o|Mc<~!fgwvx z^CK1jF(5%ovRUw>srgZ>GP?!9deNEfEa}xhfpjS7xec-YUtOzs+sEL*kZE;Y-)o@_ zXR1bVJt5_eRem8>ERv~OOKW(#b9ctb=?Ekd+gw$2(r5i%u-IRE^|?kQrwSti&|IY~7GSakqeC86|IhVx0-d7n<5eSNzWI5hmjsKEx$f$z(n1hb@tuw!XzKTQWOvN7)$J;jE1?HNNjgibTCTdS6{_*6~4k> zA@-~Vv1}(ZPv=680R%`SCrZaaj})4RkR}j>;Atv>eDO^G zaf3ofgrWWc3<3>-OGc=$3mR|+vmge$+LDox5i6g%YjI?G(5ko-rVNlMmM5r0I5zjy zrKeXs*>x}7sMN6a;aQj(K=Lw{c6Ve>j-p!-hM*iT-JQESl}l31xiJIBE;8aL3hIvh5)#_Q&J)F5S&$13kO-L>s`l`SGeRAknkYN|`HCkvVr0(s zo=K&~i}QcZXdojGCCq&aby-;1!f>F0e;-c$H6-E?oc^O(BgqbU%-hk1XG zwj3~vu~(?itkY2^LW+2;K)v�VK_kRQx2l@q95kfAdXKpG1_!EkXrR^go$p6FA7c zJnH4%Pg zV7N`d{Vu+U^*q@Zg5({e*#302W)0zshB>V|+u-16sdw!P{dT+W2-T`jG0c5oOe?8s zVeYAO;tbDG%GViK?GLQH8Xwt~F*y=<4VJS_>N1SVj;wmQXHZfEJ^8c_sd%Dzw?`%n zpYx|CsCRk%XD)aArZNXt9d~6c=pZjHw(welunbnld4obo2aSOpFRD$y2c_$R#KWV^ zin;Kl(2{AjHuFw%gM^`}vt*FeZx>S`8`>9*J(^*vgUMXTIc| z3))?xe0?_16OIzp78pA+Ygj*&9{U3pFs78N`KP8CgIDiAQuKiB-IaB?f7i5os{W4J zl|3G@^2-TUmIR)r!Y3`ZztZa3H64`OU??yt@Zx^`cy&aDsV#+u*K=xn2tOPgdbNFf z_Ph!6qJgUv4#=mz_0wN35#L*Iki61#OY+k?qOTeSblkX726ITklw>49+@P`UaF{p= zEz&f7729B|k6m3woa9!+FfQKG=ElO66(Ih{J>N`I()vg0BaQy0qIQ_vI2-^;nd^wd z0WJ#?_0-Oile?jhn14B}GJxHLWADr*2J$-`oi%?tZ0u#wz6P0~Op8V@aR^Kz!Q?%* z^sm2vzY%ZX3Z!J){T4pu03K+aHR$D7%T5Ev-=jf10LH$ixrulzTCczXf~BzFn550M zA|ZtQFO8HeJ&JG03!}2IU^+;_82rW(rlCy#S#h6~Z+*8LGUl{H$)l8fm)~Dh zN9KNnU|*9BOX>WqD0pG*xHc?bFL$um_h!s^&;vXX;MaF|+qL55ZXh`{kFc;Xl>;n~ zR;9^@40@2fv9w~#&d{gdc(O;M`c$7)1H?Itm!PaL=z$8aH_+(pp3$3a5(o-_QJJ&% zYbRAS8#3KzU9~s(&A%FqzQGni!}_a|E0FWjpfT?OfZbE?s1&Fakc;BSvB^M~0!k(+ z5GS0HROy8bF>f=Gy{XtI!$?v&$_!yVNQZeB8~X(F^c(57B5~Ax;ku9*Brm~XQ4Z(A zaAMbH;nO0LKFNLyiDa1yuq1tt4I;X<>=b1~vaHr_IMh+YwC4d~M%)JfhEG0UHZ~}9 zaIhak$SpE{*P2LyEAZrv--5iNe>FD`sf3K3f7?PW@yaawGD%#s(E>`5R>7`oru*DZ zpZ(E-@H&+9zlMHn->nd0Q>Ob0-%s}-UBHxA#Msmn$=yKS4vV|Gy_(x|A`+-@ z_5(?kkOY*CXHQeVfB&xtqkg`1B>W(nznO_iBxWHcB}E+5SPYW}3_to2N5z7!AEtN( z`4+KfVRQ&ss3707v12Yjq!hX*Pstmx#-om+6 z4-`<15O=uNRw_V5OILMe^-vtY#1|Oxu`De}w`wscgm69izuR(}8JNMkoz*X6eTbY~ zMrL)>-T@%aDDtKK)MY7)rJ82nJp0Cy=g55Yes>2H1EJ z`flDds1#H65oN&1#QXh@0KKBGbQwv0UIC7)p(WdXDUsFHlB%qKGmQ_9wp`gBHH4%w z3Pps#n0g==T+%SG)BhmKVhO0w-pB&rLJt0*BRQapC%323rY4JN{5k%=*aY;f>H3KZ z3%sbTb}%N?cR#a&ZcM&)#rAL3z@fx0WL7j^(s6d_s4t9PSi(uy^0^@^W2^9M{097N zVq=H+{9O5OvicFQjik-w?6QSaFHNiS%IQamBlN_c!2j!)pAz4`=!YO>7$7qW z%+)}i$|+PJO5vJyN47jNhS33ebc>mBNF9a3&{{Oca|I+>uB`!-aD@S?EEdgJXL44SCP5p^rwvp$Kh> zl47c4=ffCV(u?RD*f=<3=b1WvhRxz}00%7!vy5~!_(z~;)LB1_$Fol;m7-`1Vvwxx z_!uQM@nd-~Of3qGCFX0^FIV#KPHk;Aj`-g|v2rnX?oR@a0!V7_Uv!{sa>+z~SH`C;Wd3u^H;%!v zIvAzFA`QeIHV^Vg#!mD*zbD*FQZTLSc}902gW4)L0ps66MJ&4#26!1Y(Z{PnR=2RE z$AL`xkuxxR1wR879n! z-~)>0O|QUj$UuC?jLItd4T4 z2TCF{zLGGtj3C25PMkHXa;dvosSgfHFF&S&#W{Uzzc@b6eF%Qz;8lY^Jh)O+`p&ye3u_BvivTR5**>kt1Tpu1 zHFz#8sAzAWW${X-pK%sD%&MQ0JX)_V=O-iutH;qw}x|dzN2_(exgeg@s%*&73IS5x+TA0PRSfos-&#^9u(dmt-Bg0 zcVz`X9{W?2<7EFp;HiJ$-hNfGx0;et4({GTk% zcmd`>yjbBI4?h&Vl<$ zMrb)Hd&5_Y_}`-T#GIfl%+-OGYiwDO5UT=@RcY@=Ck2E#D>tbY5J%}3k)UhqGqo+Y zvCmE=b16~$y6@h1@`f&3Rly5Ii<#;^1!)_JDI(?Xg2nG?AU0E)#2e`ur-=+>am<>R(rf-T%eELEx6sNID)Jp+~vqmu~R9fkF z72tBiZm-lccgm{Bs8P|aIcAOdozEtKHO?LTM*BQ{YX(N6Z*OgG3_(x<9GaA*vRLe` zrbed)8bvhkTT`Sxr;zz$u*kBcA5A?+=!v_`7?I;PR{RVP>LAwQ+=lY8jB@{>dBMcr zHG>v=3WGTaX-IJA-bl!;{XYs|+?|h*vepRCUNMoV`mnDuFKU_ij-nnOMujQWIpMrGlu8c;n;1vNX(IUMDo_hHhHxYRbUmAwO~1uv-20 zsvzkZYNGTLd$U(_;Ad5R?Nbl1ZuI&>rA;h+Z|DE!t5Uw~Jj8NYHKb^@KtME%s`{ipGnCqNlFk+6!5ILG*J8ucDmN0=BKHy?cwlkew12;l6s4)r zUUk%34l$oELvlZNPjDQCy7G=-@@iMxy&DqgVv(=)ciW><@Ke;gE*vdON#1b;82E2X z!$>S6BeuIWe1)<3+CZ8p-nB^N$O1j9)d?EMe^+WZ_JT)nE`AjH`+kNf5OXy z7cxKinStu)_@g?&oMVyT{=0YYbdYyp1^GZcG6o%g-x1u#P+ARlNN$;$8uExEJh&dw z@hliPUCs!#%@3)&P3FOML@XhoEegcQ5DCOn2|!iba&gWyq9 zjCcSkHH({4;m?`TH46|2|LB7{0pqJVvBR>f7yZ3n_l?vzTw7b4zocDs!m0HhSzJNo4Ge&`6*-!9txcyQ4}9Nc6Bi1xyPgoqv(-_Hbli-bc$(W_|kkgqQ0j_|{1Zu-~x$zG^^h8IFGZy2b6% zd-?XAuzR}le!}H|g zY;^ILViFb93N<8KhHR$Aemr<#Lkmt|XTJ|T=(wry%bhM81=@viOmi2wFVn^>+w%sB z4J(QQ3Mhioq$^cA3P=wM(gFbsEri}%02PrUAfZWDs+7=cLOFm)la|n{^b(3fAaw4I zp3gaF-M`@8wZ8e~usnI+>^*z-?3rg~o^8xYJn#U%hGE)%qI!{WMA#f|IzMc6UD4u9 z4;=22eM-~U(PbvLPAL6;#@Z=6R&kf8*@d1oP&h*r?|JDb1`av&)-OJ4V%e6cguX>p zPj)@11eWXWx^{RU)Iy_&oQXm)VS{;RkrU)}822vbzJcH)CH#^WU!Qa>L85urZMaoQ z_dwd^Yi{iXvE*Z&vxI9>j8B9A*~}(M>9B<}nlK@$59Iu)%N8q4@&Ldbr9OH|Ne$PM zphl$UNWMg$Z`u;rh)&f{6_CYWb0EMFEBn!1=On@7N3+YIo{~#WT@0VRAMqj_pd$V8m!7a7-%j~4D776L$*m%v*Y zFd8`D=6Q^Vo_HKynCZ}$t!&~xd5VW3pFgQhu)qJPf76PYT$>xh?cP?N`%Om2m%<<=d{!b=k-IAQ$qzG5p1)Bdigp6OuM@*W5@`Ece+ z08PN2eAbK)=qu6akY%i0nCFER=t`!;dp?zV8xH*9JF-q!97swQvgqv8O6sz}TnN4y zo_pOJ-jbQ(uz%139aqr^@wwPbD!aO}pSrfVp1NjJlLP|DiIg-l=MgANa{@FTAeqHz zywuyi`*HJdv&>-$G$j^FAgp?RXv<#D1yBHD*c#cfxkWBdmss9;2@qaEP@J!Qo_}R< zQj;P#rHSY^FkO9fZL{X_Fa3h~x{`wO0D2D zU4cr3S_5-o!>pH1mt?g;ZrTl(5~QW0tKzTQcN}THo~@XbOyxh#1UYqGgG{9*5+5U` zbx#9hCuIKJ9vGvpEt#YkP;7``>?0DLM+zjlfY`!36wI_$INjss;^4RyW8G~}%FCq$rSn9+SEqO8}@<=|S@P zm1Q`NXBR}**39zv)j*|D9((X>l~{qE#fgV-f;SU53t8A1m0qj-T}~v zK5PE%xUd&}5$WWfV|aF4{QIBbPXU5jOwP2(OZ9+yQto_?;NalA%fG2=nq(yy4VB&> zuTL$JTd>Gbb^~P=z3y$+2S%G92^a@8bqAY!2Ee%@W!?BEm|17>t4xad+6!RiON=8k zpuIK~V{`7q>vBD_A7r+FoY2m_nN+5vBq&#Zke zvV9EL*D4mCxF@?3?P_fJjj#k;Ol$9Nr$p|qqA9&GBrCA@nbrx_n(k{s&hbyEV9rot ze10RtnO&(G0DZ3m5i1%E=Hcy^-tJvyeYBj261oCEeW6C51n>z%ZTUx6YP!+d{Dijy za**t0MDUa)U0(L$<()8zr8~e;*Gva#;7oR5=c?BQwYzOl48@spa*fEYSHYea8)hn) zCvW!g@dv&Gz`MZ#_P0hPOmiQk&PDkqKRD65`QbYN zQ`KjE=uGQyA1J9>e(kOm0;X2;k%^D&$0EkQ12}xF)c;*rAQq4unrvShGGC=Qs0C7Q=g07iQ(xF69fHTB$+#<&RdSROP_Z10 zB?8ulvV4ywkvPOsz;)Zg{^d&p^YNgGPzmIS+z`^U_PO^3t8c?JjV;2mSMNCZE-ati z^(4EpU>Jw_o_Ux0EYz8ftu2b@kE-0dLXIuT?WHa_oJ*m+899y%JGN^C1F=u0h;ylY zuB&dhOGhJ;|0#s@TpS%yqG@?ME zVLLg&ikQJ&z9kXt4iHr`&qX`Ai?a5LHyIBR$uY^w@c~^Xc_A-)I7CEr$RH8|V_FkP zpVQ+uJoGTjqu1cHvxyh5POm+GNsnGDe)B*;i$Hj{oyl~YY$FKL>CNfSx=G>2%cL!_ zTS7v3>tprz?0?9`f%1Eiy*98|Hc)waNiWN+ND!TWk9UL~*@9%%xVK25Gh4AwKKTR{ zSvQhpri=_oAa`2l&AS3JlT49)P_CK-j!{XaATgWa-crg=02spgsGI>H4WfCT6r{2e z%V`8{sjD;Yq9!QYO@U`~qrx{a-tS!bYXR`7u4cc$tK->O4jg-eG@~uK64d2;w?T^Y z1eHil7l5XQB$#nX;VTmOKeDvD;yh_z!sJ41m;rfzGK{9%+TJc?ayAj#tcHc;%&;oY)kr0?Cm6JYFd12Lkj2 z3r;!BJetnwxrgHr8J-2qFyj@1#oUs_?m`;+;o*|QgAs~LK&E;l# zYY38UWZE}64tUSXO=-^-(Cm$<<#C0dNn`aUPJMvvk=XTKv;ojH zy4z4`Qen5L;F$qPTDUlrOl^P~YEdp;-qPSzFHHF2f=JSOb@hTzIne24-p@wUG(8#< z37G!$n6FN>PcK9=;?V>Rlz1-|I91vlgu_~}8gXl9E+Oq8ae__fE^O+CzZ$-$ zoYK`+N)vUc(Vcp&N`yXpb$Z~j)|v%Sihc()-9CGBWZKO%id1T-HN-Y+4=dk3qC}T{-GCb zA!9NHbqV<^xr)9O>o&+WD+^X8IK$FKL&)NVhqLvSJ~2IUFroiks+H z#!sH~bWT^t00mN=U+l0v{%P;g_7eeO6M#?FiSz?w4uFmvp2=mnPcVO0{)&eigpx zK|V@3&$mnZQy{7k^YL6`O;5;k&q+0;Q`4AVmRtp)r{kaXuW}mwbt9)s&J&jB}PPS&B+Uh=p9miTQ{YfYsu0 zguF{4D^Z_PehJeK%qui%92niWBuvpyb|YQPS%Hf4x%NO*W|LHigP)GMgWBjFt7Q;X zke$H9?yv_v!(6|Kwf)?$iT%#&QBwgg_6;RfaX)id@8#X!7KlPF{mjJiMDpMJSMx=N z{{#wtmVfg33YQz~|9tH)hTng&1d|zN`TqPH#W-~UIY;rtKjKeuABCUL?}UsT?X3%c zb0jAI`78Cz-CsFUsUxAm}^~ z0koxRWEwY+s3E67YyV_|DEtKeS06%t!tZ0FFqy#p@6Z2nqXR+wpAh~}2!Hm&|7pVi zS2Tgl=}$%Rpd{^!Lir3`%iR7-vG@RNbVL_cvEkx{wRW_-wtT0&wxY7K7iq|=NM{=| zx}w;`Ze}9DB_jK$bPH_kB{hg@RBsfUii+zsf-a#|(k>D`!lt6B5rY|GKt)F1aY2+6t$l9sBMDp9?fnl0 z@J}|Z?r`U)YK@RxoKHBVE*zhlymOJ_)kFG=fA#NnjF^577*}h5y|!+Xlwa+6h3y`f z!IdkKXhVc#{U}F<@{1R!y?&UcvZF8J^`37~f1OHUIn8Lo>Taj&7%%pJgyo+&jPi>K zXl&F{Ikr-D%!G%l=upFDp>%o0P~?Lv z#|?oA+sB-EFks)y0Vh77P+B`)qUlDqO3mC}??7 zUd19R5oPuE$Dgf4LGe|BswE`ERT=K^DvFk1^EoPN`2#BTAp$Gq?Uv({q(0ncg!rK47T+1@uypEj#dF|S?Ow8R+((WMRrujn&AlV%vy z%y1KGGiy~m8o3rKT#KmqWcJqVGIsGX*r?0@Bt&i8-}0-$J9qg`OXL-|vDkwxI7iLa zi2TJRTpOeG#jiXK_AHMU7$+h#1&SK%sOoF-calD^aDmsb*Tkf!!?%-~0{HLOib2(o>S`0?AzDZ{cX}d*V7;LdEPN(uP`sj`TZJf6r9zMt8)t;z&hH*lVMq zB56I<5Vwy7Py1?KIxTuVmRuYuNfNgCUXJV634w??cZ~%0&iuP z27`1Qt&ljL2#5Snc!6$;Z%5LN{^`4C9h;WuYqRL1={*g z%K3A1aYf&wnQIZFnQxt0RMSA{WXHL%@ulUb_vP@M4N}ScK6A^*UEvzVsGO^? zLotnr0*dd8OT(&RDbKYc3Hue~8V za_+CJE<-rfEf$pwyXt4rAN@6*7Ju%4Gkq+S!LDdlzum8)_4ES*>NeoAX0ChJXKIp( zT{`rYXW&IJOL~oj65P4^x?PWa+SNOvXe?Wnxw7X9rP(oe$9VYvOajH3Fx=Eb9(sWm z6M-hl@`QdEPAhVDTfY6_uLDV8A+((7?F*+H?!?xq~!23qTN_)xIvGGcc~K z(h()hbJC6_Naa7$W~o+HQ%!$H@En@t2TQ3=;OAqU*Z;g7*X(R|&P9P1D1VD?-q4G; zKP0Yr8$O7Di(I+FR-=1Dr2uB4g)32K{hxf~Ou4yRN*)Cx?(;{#`1YMh%R?*M2#Xi% zyoZ+C24a4&-u1d~{nsGFdein$rdjOQ8QRtst7U#F_FEA*!CgmxJ}j6@)etkUaS1mA z){LfT$`cr>`_*ZQKI+$oDv&hz4=LalV6Yz2-#Hikt?f8mz5>- zfA674HGCB?RfWi?{IW#5^lsCV^;%*t4C7`EQv2ONcaEEW+wWWN|B@|e+x8G&tY+m| zZfYtP)B9cG->W8A%9jVrTN(LkU+!H6UjYhj+Wpr}oSDF*U{+_a^%&z1)}RbKO(}w| zQ&RZiko;505q-)iyw$(=c=!$KKK&?g$^(HeYvPg2>>78h_glpk*|6e|pS<+^{$q`e z*u08Nd1j&KVep}*bM++&%8pi<@P7VY3m}CRbLnzjXh#iKWxNoAv@Q9VB;OCUlj9WA2&3$Z9Del~}#R23uJ zRfnE@uzS}RB=q6hU z#7RX}MeN^coC!ds9!EsE*Y}5JW~eupht7UGe=*{OM8#b`KRf@)K(8kDjP>3Tn%N|Q zBSAhhEu2+?OTE*7r1)MF&aX+vcKyWb(g=+kJv%qAbv|H$mozdL*Fde+y8meS_zaX3_`6UT{Z258kE5A+K zn5{<8VUuQwhFVA-q3_On3cEl9gcHw?%nuv?%*zyJZ@#V0) zHykW_!%Om5yw!|f!7r<*t42Uw49TYN-|a*ZkL|PcCyL5p=B$=h zDT3n%2UYRRR(sfoMz7L)e1UF2lpYf7yM}2;!exR$fEl_qG5Lbmn2N3MEEK2TM1R~ zMqe$cmNirXvx--@t(&o5?9PmUKaje8K}p?nEw^sAN9% z$jJW3lCdO%l~)Jb$i~Xd*?$|Zw1Th-bO8eQ46l|k9zWW(({@_xJsX7TD=bSl>;I49 z1uDHA5mg<>G)*~1$6t*o2_Mn4#m?Ak%k#2cQ0j%2@oTPn97^sSq?l!9SVM_#7?O>FgMh+Bf_!Cy$jw!+--D08Y3jq@)qKfj-f`&xGx>6N?(5w#vNhbrI@ zVui2&M$UlLJ_%BNJ-FJkj<{~1s5MU-EO~uEZq__?r!d-<^jtrvg-Bg^v?3TxJ(WdD#GT}q)Kb{f4109 zbh`UHy1;8TT_Sw9vxsZF@&(J_8iZ3o&hD6Z<5J%5-zQXemln$WdsBr~{<_4}foFN- zWJMy&*|V9)o`l}LaoI-A=hf)`ApOqEIY<0$RK%D*uqkGLSHy$q$!*Ts8F7y|4SbAm zIhJIo|H>V*;*5W7sYo9dSZ3X4UN!rxz;t!WB~y{D#MUW08vp%InvyIUzxWZ1M~3xC zbwjVhmhIT%fJ-vQP*LuZ%=NZD-yn|mxAnjqC|00oRVjA|TP*|Uc?4aH@ z_2_0wW`Wad74P5=gl}C?QrOuV*l`@8F-eFwe3&{TY{i+)AfEY;;!>PRW&%EQOxbxw zql`?&naPB($d{gLW>$e$fmG?4k&^N^y=RrQX;jo95s3jSY~twhe-Chq*9Db#P0I5O z?_@M7f~Px=Hlu~YR$o{JQi7+?6d-r8QlxP^u$ob*TSKA4s>OT%8mlv9Q>iN;#EGC? z8w9GEFFyaQir9NXgDL_T+~*{4=**ydeB(RZw<+NrtZyf z>(2zu4=2C5KjLk$_iy^q?0Ts|sQ9|tiYNL%n2AO@=fb3gWz_%A_4_s=cw%fwNGR7Dv{lDZP0iVkl z(yMxBywlV6jhX=n|0xJ1BSw<9hkF&YaK&ucCz5}69+P!EHNo73YtbN+LsvADfuSM% z?u`dRh)KpOvu!=_`o#D}8TwKeJNBr5Ejz^%fd}9>qtl}sOF^w%z_Nz2ab)QK6ZlfF=vq={zIiA@qiqPjbKIfhJGG4e&h!z$D`fli2hYsQ!@w#n&qx4Z<{dYjrd<7GY+duyHO=;vpF6v029;vek&I za8H6?ZiV+k$lmauD=sjp7OZ6=2n)|f{n7dG)9+p_(^82c(Z zI{G?L&*+R>r9j-&nqi4|QV#Codli6t7yEws+kdVp`+BXTO^_feCQ?)^+|f%d;XnDM zsN&JlBEPlKGPwlK)8^&}f(9O$x6*+MEC)%r#a6KKH%h&YJR?{RF`H)$CM5Jd$Sb9yzonW9(t5KEyMM5>QrQ;t@&_m)}h#RmIEPq>sAEI zzc%{|2YI;KYI-&?dnODOPLH{dzqxxOteVs}v3_88UcKXB&Uz4v(h~g7hWC>dM&Q4L zp*zI4-m(Wn$0sTxe*07L%D^L0Y0vw+apm_a<;V+(b&R)3Z+&y;NsxaA*X3$kzP&V26Kp$V|Yy+QF*FzGzQ0n-I3>x0=f>XTyr0;9wpoV@w~+ zu>;+|q2X1V9&H<`pjX7E5`m>vdy(xWSr04ifL(zpqV8nOagwpmo{Xom9USS(Di0kE z9N5+1se8Jm>6LXcyl;czv_9yMz>3pZ07zM7M>ARxRF*fg&lY2NYQK!nE!29fvbR?u z8H4n@;UjllTiyjsTX(hpp}5me$zm&5vW_NNN7Iq9ysVsT9a*4#+(UN^GOn{>-IGkC z^CFjVo2c3GPJV}pn0%)cHkub?qwwm7s&Z8I*8o&PuiQFntRiT2gpGvuk`ySawPxo% zZEa&fDp(%G^bFe$v#7~!Vy3f;);k28&?{flO|wU;OV~Iv|5&I% zXNh>MPmfl%NwLw=HG~1jrYmo(DVOkX)R84Im|a6Ov-|^9E8kcXGGT_F3!V35PELx4 zj}N86W3CEUDbkVM`hc9NzaAEGGM5q{sA<7ZWIIvMyL|0{sRYoe4r)S1Y`L;=3QTxCEYoT`tYMxgF1IX zF-U zXXM3L{&=36L=A>==K7eKjVi(*5*NlbaM|r#g$-)7?7W7?Ofqm$BllbdMYe&?V~3)! zFiK-mjCCtd;SxD4ajntq7X`maq40XQNiCx_>=Z7&1?I{dm536V!L>4 zMO1K+8itOkbf)BW`XWx%dp=k#<5LSPcx*(G9lNxeI$5P{h+=GC>fKt!L3Fc9W2sta zt_C9ioX5o*V~Kgr44dCsvJ;Y?_f6h-e&1DyShY42l45Q+0sz&1;=+44c_7pfs*tN{ z?G3)5dea-ORr(mGS`lC1p844o-K&tD6f;vhrsHfX2EOU{6CW{a=oYoiyYtr5(CY0% zEiFess*h{MRHx0jSjxr(aZ;Qb;cQHq#9x#C#hQZP$12f=9Jpa-(L^AwRWZ><&cKB)sZ-vEUAITHYZ#pnW5!w}7rJ zLdV4!T2V>Kyy9>b)NCyo{iDXNp9?k%37Gc8)(k=uMiZjByxP}^NHe&qg+an_f9dfa zF1v#lTrDPcHWeU9m+{>_t^!dlUHS=p@|a0hpBT5={q|u92(K|6k}5A=1nZF9BEM&r zM#O?ru8-X4^I57%Q+=6b+*EZ0^U5x5!AN#a=^^OEb?`O0eVj;h1uboRrp;<`O$*|F zt$0-sFNAO_1n1QfPy5bq%pqpt{-ulx;OV!(5zT*uou}cN zxa_P@8TPwKz)ueGn3z(^m&k2Xt{IJC=TS%KNUV5_eW%TijpH?dzuzZc2l~Un_<50a z?=x@12oW@fGXWLfp8Edgx*hbAK}vBJ{M7A~unPm1r)G_7NW$WuoX%^%0bB|noNSRM z=116X!;tnoo}o~E1b7pL+>c%^V^%M^eGc^b!wuMG=%Le{ZOh;=dK+vlk2l%5JY!dQT z!fdX$W5W~q&L&FiDbU}XCxb#BhX)htd=HjHCiGBRIQ8FXN=^Z?o^8l$uK<^0kAV** zQU2IOWGKtK^%#;^K}9&p?8qp7hcGx$*@Q4XO~BDcGMOO2{? z$SzBYin{YMxlTD=^n3AAp%VSgW^hE;yk`^x%A}IZ=MwK)_}kw9W#VOb1aL^h<&QQ{ z*DTh$>jRKz%CboI`h(xsHTs9NA584-zc7fbYh=7ktS(cDr#-$0_~G z-HG9w0Ajm6+OEl$bwDT`=so>an6d5ftR6QMsEO^NB3uHUhlu^uK_b#uK2lYDj3Leuw zH^U*wx?vd?H#AX7F^2VlCbUwFPwj-Gb@8xON%;6NWVtRRMI%BouHcR4q{{hb_!}iW*FK4S; z1!HdUWuZAh+}+n?J7PX}AuX(KZ^p0j02>V$Eu4jaUfvV?Fh?b*9^xdS>e-WnUdNZZ zgq_fC_}N0Yba#KtX$vK@*FS;AzYTjdaIjd_buBJtiNQgsB5BW=H+&8Z=5quT%CcvB zq>HgV(8Z~3s3YQ{(oez-IAM%^kO<*NugE7%;ET6F;G%WPF*f`kQc+_sOJ9HGjWZ@# z?r?5c4n@e7zy5iLi~9rE2lqrGyb5HrAWI{yy^k;J-I-EXfoE3}drX00&%+C^zOkqB z5V^BUW-k(66w;4+j_gsl%*gef#j8LDeg-E*u7iLWugY^19cttFQEaKY(Y9#MMC*8>)$N2J7NH!7-MQGB3uUOsVgA}TP69` zgybWo&Z@ObRhtIP_e(ouFfv=| z7=>JSdS!Y0Ef2ePhU=?Q7e{|pY^S^&Vq7Xc7?RQ%kT}WAPaO+Cy)WXWVjB$_!0j(MuaULuRlmdDNpZI^Aglg0 zkfPX)Yc00JLyJvHhPCQ+ga70upQg{Nfja^bD_Sj*yQX?bru+exy~ zqu?a&!%avYQOTN%9y;RE6Sxh2=_B06T^4%5CE6lS=Nt3}pHBydohztx zm6NKPn-N995F}%RrKGjkwk3*FlX9OHpu}jUcVc!QZe6>fT_z9S?k9T%)`a6(J0Wh< z_!wR_&5U1?ae%0l_E!_iEFjTbhvWfJbS~^fCF?EjL?>H-ttcRU3BPeqTHwTSl@i$w zigumvl+&=+?H$&vlpP=Ip!}87C$ycI{S#d6>uy<*2`Y%S$vO=`#nsmHL>d|&WLei) zJ-e>WBLwe%#IXA<|H=L#y|X&cVyQ)pa83fqK;YTResXo}1Lc&$(i~_The{rLs{^@a715 z!sD>m+hcV@F|)5~kAIb=MxsxsOc0aot&!P7`Z}^NUNw_Qk+MkuZX0HUaVBc7C z^@<7RyWDvBZG&n@Lpfs;P3MWFBF&^RV>=`|X;p8pytTaFc)-`hVZx~BId*@;&bDle zPLo^4#C2~TN_u(VxgO8hb^FPo@t6H%?N`+)!OkhtFOC9mpCIwV--pU<0ryYM!B{ak zySUFc%eZa(P|Z}nVbt>&ml-pr}fp z|6ra_;X1;1@@X1pzT=J2ezpq(dv(J#zKarj(adi+cXtoVo|TyF71ibgXQ$9r{z*^M}Szb56foAU@m_mY>zV4%2UIL)pEl}rgNnqr_+m?UFQPy^&5RgYJkq8DW{ z+o|vGj77Pod%Ar0^K2D`iMLj_eGc`DZ#5(pkh94)B*GBnX5HpVgk-Wf7We)OaekRj zu=C_3H)|HSf?0Nql*9NM{_%1?Ai5D2_S~5}$fIb6S872{q`c!Nn4VgEWxv+MlqWaP zI^FH3CdpxWfAJF4my}9RlRD7XAD%5ix^~vNG&jIIn#t+eOTy+Q4ysk*zyZiHh`dV1 zMDEdC&F9k}uTBh$6qJqBz6=!=ZNxb*sY< z$gCYMXMG->=f*)!VZy}^#-eV%BktH^3j7@>C@3UP&-ij%pzB^%uow*#j9{N+mhs>J z1JIp}O?F${iA{c|W29-+g(rGzbd8Wvp;K0mz8E~O1`hvoyYNG&`Ia`~@Fu&s2)=hp zGa=LL6-3duvw%_X(Rr$m$<^f{D{He+SwFi?7}swY!D-8A7-Ph1?5K))!h89%(jK~; zH1qhSu%_8qZn?2PACh+&L$`>?O0#&Qn8Hc5Ds>7)mtu!JT(K-P!e2at@m-Kvx^!^3 z?pM5z)NmhPs$J2dmr?r)ntEe&767u0atbA5t@PNLT+hS8EWi5Yp#om!fNcs;kkT z+Rp%C|mv`ut3`=3(>`8od=>&y=8`v$)a+0llgd$S8dB>fYWq=S0mX=i!~U za8h_xg13xP-y}k|8~HTF0-3~(6Xon0JEgQXe(bMS8P`?^uct$LM3)2i{c}|teM4C3 ziM3Ee+nR5Dqg{Gqs@HlGFr?7BYqr03=vR{8EPsz0du@;GsEaR!uDY%134|G2AB-+T zx%xLg7=7lEnr_=uTX}D~h&LNJ&6&|0C*T9KVUlk*2{}%B*-dhq9eC*5e1k+FV)uM%&Th(N zIa?8h_H>hcR3%duqW0**(`M^lB1tN$P1C_L1-mYqrPB{*4bJ9Z?bO|51D>IqFR^Ty z#^yyfIx4li+DTFMgeSx4vZrP8-7FKiG)nMnw_f$t|Ar@T5WVw^&4aOQY7ZQ;b)u5% z%6LBBb_vmI#YFXMebhgww-2;aX@zTjsOTIvE_RG0u9jyB=bMb=G_xKBc-*q`mU5*` zYY4R!)lMf^R$EfhIkTmWIoD1f8gX8eA;y-OJ2ov&Y?696iwnHW1Ikv*DDOotdVcSF za_>_=#p0`qc>|KRL#W|cf49;=RlfRBP5!aft_*!x$TmvpsJNeXOSq%vuvSb)GOaDp zDk*il&d_9wHNdy*2hQ zKZ!)Iy1T?k?T>qpOsnr~WDqL!G7*kmFG=3Dhnv3ThztS}v6n5MrQduSxh7!rWK(24 zb1KmMfV3;Mtrh$iRN+zt>%ZtNRUzrb=osRmSrIbjnF3NcKMfw`nX*Nx(?X0D6uA3_l zn3u6jj_sg+ry9Yf(Hlb2n)nS7X*-^*c_&Zfta&#%m!~(GjPD7(SMr~{XW10b_q$+> z1C`v@V%?Ng-jTDF+%}?XTAmsL*&Fqm7*m3CQ(=USeks0T$NqdQKNYXun0qXoQkika zJ@o-frn61hdZR4=XC2RmTfhqA>yfw0(Tk*gVf50$=8A3&S488=bV^JD8b++bM>M?3 zR6FzZf{e6_#Fyo&t{lqZz2zq*#28>AJ*t=Lq>ioSF&Py0lZrfyLEoWlh zY3YT*u@gE6;+JZKx_X>4pZm<-)qCS@R{)=#*Pif7lREj0Zt>Toza)pa4<8SHLM@zW zJXr}DYP|EJD0^jUW?O3vx$1FgFR|dF=&n0=!34T%wtHZHTdLMliGu1-q;z1a^{vRD z*s8HRnb*w_3cJ*HQKFGQ%^Mq)qS}qSC%V ztS+8DS@RxpE~ZagC`E*fiabNIo0uDZ(i3|sgucg+Q*P<$O>4cUlkTT1y!`r)3tUMA*^^{r~4Vp|vQgfe;*AJ#^4!AK8>$}eI*q7z5J%wEp zi+sjqXD^9V{t|hJ6=Yi6UbZ-DvwC+76)#b+G+fUZbt**WTQE*5l~hRj`tE#gb^k7g zO3HK~YHCtf|LNjRey>L(7gL7U2-%sF1j5%0DsbjFo;A6Yca%d}8R}il43Vw&i1s6S z$Tk{Lh4Z*kI|vqwM-l0#HI<^ee2n4cu5jbJCEUeVFR)!69>+z#B4Q)ur|JN*R1ZRgdOaVe3P>9K9=l8t$Lm2RlpCHGC~*{+xT zu@+%Nv(+`s+^6g6S1)|7i>ym4+x+kMumunt$b| z4T_fY@*cxo^&QL?$w=W#*Xwl2OcRK=&5YPj!y}$$wU&eWabvqnI?#3P~ z#_pNguk~)OKlfBD!Pq5D0cj0U@!|W9I(qDfB8jfcVMJt&i4?_IBe`V zn(XNK;rOp5NMo%`!ID!?d6jQ->@#>j%b4|wpiR9wV2O)XYB=o-T+xceDG_rhu>h33 zd8(#5+vplX`_P_=WSEOWAtlBIm$xA$Jpq*al^H&>;2xi!8(m35_&11{;V<_3S>Soi zepCO*>L$H`E(4tew>J%!Eo_>x7WstR0CN*86O1&siTZ2@;{7gX;VlsFClr-hhEiM?&m|__iLnO^kXkX3S}d;KP%< zZ{#teN35cEJRHx|ePnV1dwHpLP}(9njCnjvB}CVztUqpxgnSwy+x1F}gfR(!bHctl zXH{l?Wm|G8%vMK2aFn<&>w}(O(I_NQ`H~P6MOgs#7x!*YKurzzaTPyVc?zGn`{r*w zc@wM#D}FZSYLHNeC?81mzp%r#ciZ4&PkSjvvW@;>Mby<;SW5K~CT-Tg@pVbBUHZE0 zr2N-mB-;Kc6B}lhu#rni4O(D6@~t^TM`%_*n!dd>-nP#8zT1_1jAK8(B5x^b2r_Gn z-mUhx@-H8=#A6IPjcKSLWpCc(&*mSq0)Y&g`e`E{_DTpVmkVsEEv<30?EE+ArbO9h znw~RCbBzE$<;}SXx00T)iSI8)*2-3?W%MH`AGs&<>!0W;s?$rN%re}Q=-;5dQ;|{HNa>=g+xl1NCFKE|iH}!FL3w*6-98-% zL;T$DIOIi2^3kHlr{qg9_zeYVlRScq-ASn;!AAdL2r-`BDwAFl00&=Vr!5lrB8X5b zwp$TDauUbDwR}?-d*mCdISW=^oHD($F*+Y&JwQ_{A;B8jal(U3n3cEbA_9*?fOZ0#yArHoI*3CxvsYC0hl8P9y zu9!q;nGN!mm6Ph(kdtQa-Dq(1taXpytA5hOd`vQ)!OB%X|3xPKrOK%rC(fMWIT^%2&s*2D^&Og)nl z9nKmHmQ!KT{X=?;wTSsE$l5NfZ_dgFQ`hsP!&TR=pt`0-=%PefMgBax;9WjxEhwO! zQ4leBBilIz&%n$b5{=~V1@jmzn&`JnuM^?(1XW;gLs|JPxRDy_ek6GgewFF-Z#<2^ z%)gr@lE=R(b)_)U*h|m#zInq99>e$7j2;FZ8-9~!uQbH?oeLhfswMI`&_W`kG$1qD zWr7Fuh~e7RAlCL6=JlUm8?zfGQ%>jT4{CVc9WZ(uyEY_ijp@j{ z(AH8eMZ*U@fp6N57U(Em)tk^8Od7)+e*RR@?9%nUu;B&LUNu$Ll{(JU<&Ebkh65)uVHf4~)}zgYUfl!ovN&Epy{_updi^z=`5J7hjy5 zi&nf5bN~4B^J@CXZ@pssko3VAH@3KG(uLNBfllNcj1H_1rgN~j%O#cNnQb_qj7joJ z@#+k^^m;2kekb%26>BQ~i$dO*@cpzeJUpqsiL6&bf5^HXo-_>B`jJI_91(Uf2D;}q*9>>`d9oQi&;<`cUDC*r445{1kkhk5x-uH|e> zT66V3BZ=1y-F6(~Sh^lJ{^|HL_uct9$&O=^H%mocKI)4~ILPX~$0tD+Bg?mzZjaQ? zYcAvT4$l_6wdSM!^mLLCIYf5545R!Ked>T~l>>UV!Ug$(yv`<9gyv;aSADFL_!POk zTl;t0-h4*0O6^YAILmu~V(MLuR2tOkoqKRj@*q=6lhzXyE{mP=J~{bBv!=MOdQnJm zOHZ~WmoLMjpD1A%yxZvO`%EqHC)T5JjU)VXYFA4iDgXWXuP&n-*m|~+ecKC`<2`0- zMO$reWZVX2(rn;Adc~@b0={PfBX`79bMUA{bHsN9y6_RI2cLuF3(aPX>i#}a1G6?1 zlf=T#C&@lqs9s-K5gTHp)}1vCoFtqtsHv%MrGIy#;pcHuEPKzB$v&4f4LHNK(F02x zSY40byUv?7SC{qZ#i*-m_+@^Mnt8jchNv$Wsd-bB&Gezmqa@?EMtPE4YAQs9B!&pG zhwHU`id3e~m9fX&zT!Hrk1w{kL@LR2h<-kBoj_f(;cHua^wC=D`Zk}<&%b0}3s`(; ze;F}xfqrjK9iPmVWmh`qHbL8L`G2T-?|3%9_kUb>sa9LNYP34gsx7sm zv_)&xs@k0oGc2un!4{k_HdBSulf>{5P<%u-2@`lW0|0v5QZ19dE zAiwJm;X>&%G?$$DQF^F%>tGOKGkWV?r@4}{RnVntyW113&(}gl(FuY}fwDmt=&;YK z=|O*GElz1br}!J@s!T#feNj=o<6siVs)5*}c4T#0a}_ybLn-!P`Yr)iA#^*dHVx>I z1AD;s-9zt8oMvzT18d*$RE$lZt#>M;bmQC`1{9W$esT@J!MabgKs6`@)%Doj<+1)M zD;B6}k#BUXtXL{>IHgQb<)Vnrh+>sBOGKH1hr3$T7=;jYEOTBjb)Nfu(`rzFTJ5vW zKajgn?sccb)#bip-u`x@To!KeO*+hky+SMvI4rco&r zB!fL%f6meo*rN923#0>ab*J8kj~}6@kPS)no>V|71u2-ZswT>v)lsmoRWkG3_%HL=AcHSQy^rV#tgVEVyeGnI$O#eV9vJ>~^>S5KSU zG_aP|XJig8&OMIjRuKPAH|%c|=8zi5#}z6D=EP;Ncw`jafxbBlwg^iz1}wmwsr ze2;YA)n+eK864#&lJs^RzJT-X_3M#(S&21)BcrO@->uw4reJ(%991Y z$uy(25@4^{;+0I3amc_t-cf!Py(PKQ5nj$Sj7#MX3T9oG4?#<1_y)NX5_|ncrg}L9 zpF2h~C~*fmif&P+0zF*_g=78ba0iai-5p%fFLf4!&$JdJsx&?r;yzW-v4Py#vpVjw zUanCSJOz@YoHI&~Q{qJ8NP+4o#~U@Y<2beZ?$@+N+ykK4bLsj`jaR2%8LY-cnyze2 z7;S!$3uf`)oIIWX^l@oDDWeu%JeYT`(YiogebIL@cq44uX|#a=6imiq>ACD+`k=rxjD@ zoi|(0Ipsi*444%YleC;DEU19e{k^+Faev5v&OMuA!0KUAo$L1Fwpp%phuvczvsdD| zA-mZ8N$LG3TusR~1`|(RFZ?>fwuK0`Pcz#$c$tEwJ~OiBQvJ473ls{Ouf2OMvdKAN z6yl0WkuDwM)h+3Got5qeMr_@q{F(8U+h5a<&se5S>Lr8KV{&Sx`Auxk zo9flCBIa%UuT9KOO9TijKvCGZ@CKYuESQNH8`oXj$DZL?4vZO7 zLhRTOkQeDgjjK|ivBo{?%H?u3x@oZH@mzpwlq<*f-D7~#aS1;y4&QjF-2;x-NbaxZ z)H^^pg}8k#xhW$I>FUu`s@L_f$?_IZth6t15#@uRAM4Z*Bc@TGs>WgPs?^D)l?|LI z`-L8`%yq>-cE$tTc3mPu&On*e#+87r9KVU=c@!$B(MZFSg|BIIbizwI)#MO`yUg#> z{43`O6H+>llKRRh2%Vzs9^5r@UR$NT)Usd;N~04;R1nKnl;l z>VKtlEAxZrqQ|iXLo)-e8i|d)y`9}_l)T*hG3RDtaC>5xTThn8WIzioP2kC5R5uR& zVm<8M`)boT;v#iVcnI~bUfFes1lR1KsV*&he1u3Sx|Ax2-t!XR4GOXWlG3yJm8I z=g&0fgOmC_X{1+x(%#OG%DtfoS(4d!+kHbgrc#a-v?!jYOV)&>uc^^=N z*V%8f)}6Mn*a`D|uJ0T&l^Nhz#D4S!tm|5IW8<2y$Mw_ACmxdf!CSGX_0A@U9+OlH zTe&wB$%5y2oF{z#=`rT!KPPG$-+AtM9McTgiVhj3K>%GSix(W^zubVbXF}e+v@V8Q zUq9zc(n@P6VEZibS)UcO&`|(B@lKusQ382LE^Pj;5Jz+1=nd@0rso4^$D81ENE5^@ zKgZrUPRMeI)Tn*=-tR)({7+xCIi7b*t2fl4h1BHkryHl4B3k&u@urC>$m{rjSR5v= zholU~4fQO%S0A4FX8K2lxR|%`=9A)+EvNd}wTabN?ZqG$08MI8)ajw^EA`}4?w0P> z)^#c~o@Qz#>TtTiF-^6@`M#>-=h#;ks^zYFK4NL*toX!dI4{RJ^{f@5s8)-v`B9B| z_f%uqB)f7<;v{`MMb#$haY){xGHJ{-5U))&R08h}a5<~aks22peT)`}+4QNUQ#=0j zOv}D!lpaE^T8j0JjG!q^+V2kxRT5{6l^XI0y-iy%J-lp$%-Xs0iP&I+Z#W%ve8=pp zuJhugvzj%&i!QTc6-3Uzo!D zKYkIKNYSLJd- zfRRbB=s}?kA!^}WQWj0G)VEht7?xQ`F=18h&sQ+c*RoRm_kl2%h!#h zTvn(^D!qp`wVmc$zHTGo_pyrK8R=vyZf zyZ$sqreGkLL4C|%QiE!I zy@LIZB8x%yyT~&!K=!zT-Z0*{HERclp)7uYOn zmSq7U?fA8enbjogZ6gRf^XxYrQ&~DZP91uAM6vyMJ)lzPH^3VmVhBMQB@tmOb@61k ze<6r(8)G|tC!KVkj#rZU8%Wzf4Q( zaqg|d1d9)q8&N@59s5shGBG)b4Z;TxF}>DZva|(LR}-_@%U1rLoi6An>+&A?mu7VL zQ$8-)RMkyNTnUjLVDq5B-*c$V3Hj${e#~@sSw6wdids>^OX=&ekuqur{WM>lI zKXAT*uIA^ssCA&_3h77B12rNif{?*yt*s1P!BWqU{);(3)k;j{kx_yLnX@bEb7s^m z?80^Miononytx(aCmrM3UUf+xYo9n*1oO{fF+jx- zV7xWm`$WC#Ck00_{RJPw1uCx(r`C5$=l|2$zb;Pt zCieEGeE9US-=n7ZpYNqOhc{5465cZKE zfNRC+@6~PV$yCmmS;#Q7bD4tdff3+)fQmNkcS&W6vC+w+Wp0F?w8P4lcKC z{a*NOES{!Q);}bfroJhh<3F&8BS*f82TRkc=rtw0GEn2h6vc|p|Aq=yjD=@)Ehzg2 z%>{C|>89jXXc}-8=u{*F>pDsOywaI^{9sj*Lz{%vR|=jTVQ8oB-;ob133GE3>j%@} zV2M71_lLF~%BEOlP;+YQDmzF?nleA^?(kR(*^Qhky9Vr)199OrV92{IqI`hyu2eX8 zRL*`$Lb&xLKZhqe0fxxG#21$6UP#BwUJqf|WD&)NL&A4+uJ_7YwFfq@#D(>t9`2x1 zO}l&mJ-Vytx-Kqt2Xy6O$qkTC4xZStHv(cymSv(K@9TI4$Ah`COhCvMJspb^dUZvg zI>$kqER`6y3M0+u^NWk}f+fh&ktqL#8XJ%>-y8c8C5=e#5NGS?$rlC&Ci-U?T=e^e zaH{(~J1tV*7y8~1?69+hhw8X1OjPCRQ()-dNeVq3^2#zrN_K87gC0ax}Dx9i;s)7}XwC?6i4}F^@Z|F02{L3ymOkQj3h4 zYNJS<%y&~_j8l9>jHEISI?>e9Nd1QP%=^@uU@Eh58Tf~!@r4FZif~%)V6*P$BFToR z;);KCe-qn_fba2T&kw+ZqJI5yh`Ty%ww$0VmU|P(81-M0!)I`FCc;ry)>RoVzB}{E zsf2xUDFGs;-P8SiyqJ;Yz$6l+xIgUwWv=lFsiS>e0nTy4F|PBn@HnsIC1F;a_may= zF`ff+iZ$h~#oplGfo&9ULh!ZbM(w;BxxaN);{1GkWBui^{!V5_^}rA{{7=m2#eNQ}>w$q*c`2QW(~L=k*lLkl z6eVK%wkvwm3@(nFeF7SXKW6MK?*2jfg@klGYgxiTckjl6AYW}l=V%rBB<$~eB&PXm+rJIu+abDIT(s;Hk# zVm!~vRT4aFb-l5%s`cN|3Ob~5( z>upH{o>|bW<=^a?=63yR`lrve=1`n7G;>$#fYKIrRtJ+`OI(r+3>RnIMBl3;GsT_M zDEz=#zCFTxfPWNfuQC|!-S%n?oh2%g21VSKbi5R7Z+khCH{~e?bC-ZL0aRlsoS8wn zZ(dqmg1ROiZ;eU|L}U;ZdI#`QrsuGxVv1A20uI+2OPLSRrY)hkaa;pt zY&}+Y_FN=Ml$vnFQ78W378&17nv-=GhIID)j+}d-eDG2&JyO47R*YwsbMBYg$_JUGNgZqrPv}_o?-<_SsZxcc%iWF66e>x&la!}USwOvo@R@g z@7O`o%CyN;h>RVs~S6uD+VFS@-tg8YVh(|c>^Rtbn>ivZ1xIEYj z$NV%FTstPS)~u;BK`N6@tc;O#v`3|!$Mw_%=zX);*fr9b@qe4~H2u**8fV;@3{ zqB?0}rr|N+0!xHaF3kBuM5LrLTM2R8O*=d0aqsto9W|Y;8F$uhk17xcv6F8=OKOL* zp1&2F2f*+^3M zPszsH672xVneHyKFKTxW_5J}4)_Q+`!^qp$8os98w||ZdVCD`j{+cu*iJUi44YROIKBO*d$op5NkT@W{731`lb@DO-|eL|8jT5>4JzXgek|cpq0xJddf& zk)1krok4(kg-;v$D8Ql-#TzH2S^;du8NU#wht3m;n9!}cDP8h5*r6WZ=$0ji@}(Ug z+-vPYZI29QJZ(fwKsIlDOVk~gar(cxIL`P~=1F=mOn;t}86M7#WeiXx1bE^*y4;G~oz5RSYChK*2!k8Mycp7&et%9FDy}2kY_Z(%lesCr zAD`x-(o&_edy3>7fNpfgGHw|rz(Y$M@%Ihy?SNayG*9)4oq`v_0N$odqgLiPL~q#t zJKTiXDiv4lcH^YP% zn=GL$pQQRLtfeUx!JLyL!U3X5>M}I0I3?i*P%4J7?+%D;729xe&a8p<*JzGm`ZOQ< zpvdmmspnb23gtFd`$7%lxvuDz}p2(S-uB8fdtp1#{sRg=AU?uyP>!*z^=#^ zn_L;zKMin<3D<(`{8i*7bd<8^+BR0^2HqXsDSW+0p3|gSk71g9{W`P}=%7bfT_tH109F|&@OZMRqJ3fP(KNmE)p z_D3iA^!==^O(I-1Y#78O^Z{KBPx-^=12|%QqZ@jwlA_Dye&?2EK%HojD>uDm@}uRb zR1 z`>4DL(upOH0L%*M))rCJBluBY9erWuZr%#+#5`NUjyj#UCixBT2|}tW#+{IhKO+(j zi+OP(80<)lenj*L-bGc}7}1Ytk+C#8+hZk<7v;t9^XZR>T9Y&^DGj?p_< z7O!KR;&5+hKeJ-?_)tEoSHi#_w#&g5!T5OI;-*7@UXr*`f-1leM6u?GbpLwWcSagP z3*<$43w-20D)w`Mtp5JeMPQ$kuc^esd^XlkOt&YTJ;)9-Gn^pU&7$eUfP#@HRX=M| zJ}@UF5plj=C`0@Rvwfc1uS_(DHm*U!L32da_tsPv%w-K<^2X*wQ{X^x@~Q7T6Mqif zWvZ#@FXvvBOT8rmMF1i`d0{*MXj5{@;?T3@$g;_$-A0SjF>npkTX zqo<>OlfS;I)!rMMtegKjxTz*`(LjXV0ocsy<<;!H=lRHMzUg$b>kLeRera9la;Jta zI!_Wq9MjK$K<4{Tns^Xz6u5k;7V!{-zl5-e54!jw1!SPUi!=2&8_wG&xuK>#p_RuS zZ5nEBG!i$xI^W^$77AIedyiRT@Gz0uLCBoUC*rw;CeUsj;wLyhwMO-J2Q%U`^NvE) z`mtr&kh4ukh){O9wP}ZFwa2xg>q8@IJMQ6|}Wlw%sEAZB#&x1zI z?WB;m*1?xMSfE+%&CEMy{pdWz-{{S{W4xPnD?RV$J;$W0h|>EF0*GCmd;2~-QH+gq zDI^C5>d|cOlE@JX8=Iczdc|7yzZyms+^l2>`FE(KGZrk1$raN7%;85gV5br`Hx&Ow zE_lf}-CNa*73i=2wT$M-d;0}`eIH@YolJSql2Q{fc{jR*lPkJe=Xw;}=)0lsnn||d znq=J*QCY3)quY8`1?)X&Phu* zD<36TaoKh8*pX{w(`b7;sYbWN%cSK_&tymg_gzT0$tFBm-vc|Dkg_t-CDU%4b}q3k znBqb`QI=NdpCxm3xP0*22jk(C!Xw-l21jQDad&R#b|VlvHi&pi-&Kd@wr8ZvCG>h~ zx%a%F4sO7_;svB81e;tQc8X;f7-dLI2vVCm zeN*hkoCMq&Z{Zou4W4T%J$<>|Wps_NFN%$ku~n}&qHfqSt|9a$1m z(AZrd8d~k#g~*oKU@U|@v$<`KKRs<5dB!{qkeL5&hngEWU3^Gm5o9ZaD z8r$>A8(qy0_TJ1A;K%Jw{tev5!hrIS*Z!W{!Stt$t*3|*9ZM^6#g zo-^OB8eN^zPv7XNF4KKbP)W~=?tl8Q%w$1k2e-XZgNTdQ1;uJk_{kSmZW$Ca)@+4}?h^c6zkS#hxpwfBp z;ozz&wz^sb3pOwBuzjALfbw~qJn2RCm&y|N6@1%wVJ$Uv)I;O6g!9;!fM$ka@RwP1f-Kws?skH`U*SmK2FrnUfma zrhP&D)xFre`fH;@r%Qz>1?UOqKV#OZQYHvdj*|7N#KXgz9UeX?=H+01Q!Kp3pl~Lx z2A60IO77IZ=m@c$#3BOtF*eK3P1gm&0ySLs@&0Ciy}!j+O=HQcpp{SizACHEVhu=P zjJ-4yYvh`tJ^JsQSLaMU5mbg3un%}>x6dUM3=8iSmbI!6-2AMcEEQd?SNG_Plb?Y9 z^agykSeskv&zpq+88187!a=k06osc9VNO9^S?OL@CcuXe0r|=oMXLHa%3t4B`)-fl zD4SP!RPR|duR0-ZM*c}daQv#xKQY`!o88}fIJF^9AG_2T6c7Ljk7?S?>obGNP7UAp zpqjS@ajd!AYcP$&`_|mus@7vk+|{419Nw&h7PS&2zHQP{MDZoj&wy%FwFMu;imghK zkM|>N6fZ?t5L&QWbw2gPlll?dN=w+A(_T)b*R|atf&^ntw7JS0Mil3jDe!Y{k6*PMnxiV7}1Dx1hYn!r(03tTeO$Lk8Da4i5 zM7PjAYzMG;3lw3!#?}P=^u#rlyan$cBaZsA=T*m(SccdIW5;Pi7%(*}d-Ii*^p!c{ zt5!hPm-!0r`%df=&(_WJ{n*DGX1Z%TdO{rK=)8s6AT8_W{-hE)B46p2`sq4xWDo&}er4WY2c)W1vS!eZh_2b&K&@)y)b?DX6Lii;=|@ zmY(+psxI}81_PTT`1;Af=8>GLWkdcGkl6ho9c)5O{<0o#_*>%YlNXKd;XFF7xk(MZ zy7fJ-i0JUm!gNHs_|*|WNp#*9z4LgB>q-I#7H63Pk&n}vdr}0|TBoWb)rd2kfOsCE zsdqfXIh!Ky**b~IW$i?YN6b^JCaEoVpeQVxO4?+3wWO|NW-%Kg_VonWT6??3*v6x7 zhVMl){oZ;LEJ}MMCLjZ?S#~FPFd<2UHs zF?xeFrNG-w^yWCo@Wk}_CBE`3qA`%}8QJN8->&N=!1rQyfA`*;FmuWlV#NtB`ERzI z8emv;Jg@4Y!E(cx>4pysk8k+S!+hoRXW{W0H?Gc{X$!ObDk%2uWjvudvS07wuzlT{7EJN?WN~8K|D#1;b*hVHr#s6F|_pDwz>7E(2pYXE;c_A zA?EW53mYtQXYuG8PvNI79Dmb<H3&!uF#9I-VXv_@;+BQZx}VStFN1x$-0=d*~2<^tvcUgo+*iKX!)Vs zfQ_uu!^;Jso(922pZ_L``3>PQWKXh2=ts5EDv7#@q?|&wU2cnqC1sTpNnVf+`Uj}5wEi;lnV{vDgTdxr=IsPJVg~4 zg`Lj zn!Y<=A^f&ALc&6r`pMXgH9T({;`=_j+Ak>giP8sESM35(p?;AW^&$GCHk!i(ImZnZ ztt&htSK?g^8`Fik4GzuC|Fy@$U&T+Xd>lRAn2q$anp<}_Ts=;o?60r;Rn<@baLiqJ zqIH^{W?;@v+p8=^i4#u@<;QYyVZz4VdHa1jL zY*=gO)f#iTQQ=F%qAFCJXX5Y2mFxT&fYe;K(Vu&q%O#!_H7a0M{c86r3qZd@bENwwU}E4YM++yR z`tlW{2=BXXOO%Xvy>&U%gr#TD>#d7X6MDyn>gv@bCcq$`VEoG*4zgw6%kJ?kq)b#}1?VrH5qTK51LB(ILekeSL zKHJ4Sr4nFa7uITrvVZGq?$3YMHRd5$5ub7ydC%?Z7-kh}!E!5pJ~QL#Pj9UUT$=$$ z#3D9%j~VL%bS$iLj}o^P*;?ezZz&$eh*HFGz^)wFQz`m8;)ExIn0fIQ^yWfec437T`3k zl_OHu-?JRp8F8hUvHgyyzh_=@a5`RX33vljP33wFDG=jWHm3)UKa&DEtE?)YY^9B% z35L@v$05BD^Ua-^=`k6=w33F7xn z{sz4g-#(@PP9SZ(T6H_EFZcv0Y@kv+h$AS+VC?y&C-+T0XN?QuJq%UEsMb$|zpdo> zlrX%!?)}xM)o}!p(B5#3_LR4{x>9&|C%O4KR{p`pO60~w>0PoO+-o~C$iR}vI zhqxrFo2b}m@x|A_a{wLH3U@i*!_VF6BsF?HR&E|ZBl5V$1EyEvpXpjJ2dV}sP++_5 z{}@40u>mT&zMN_3!|aPieeRK@}50veu-n-KIkU=X!FyVak zz-COL@kAN!Q-Da|#akSuBY;Pk7v3L_TB4Yy0H$1T#JCpDcF!%bb>GVH7)zC!At%E{6Ia&fozq5Ct$&9b z1QoLF1T9%?io{Gdi)$%$*yj|6tV$jc1o;Y{C4m`f=>88~vIfPZVES-V5Z zu~13nSeP$$?EMaB10&A$Jse@YRoll5Pt0&XUEne?2q>6uJcLS5b;)UFKp|gOa_2pj zGMfk^Q_iHf!RWltZ>&h8hQ$kau{=8-e^1LpV~NkSTQqT+kjkdnl}C`< z9aVtF3*Yg&%+e-jsGOzwT8W&YpJ5L%Xd56kBkiX;QaynSV0RWA?3;xb7Od5bl+jf@ z{_%#B!)@+lU@alAp1*!0L!056iYBHBDdob+msQx!D{Gu*9$LH=gQh>zzGM3U?G7(Z z&`*JCx4b19lZH>+s>=J4n%i^^6k189H`n)n{B$`8x-+epRrzLuL@+m|*8f4xCrKy@ zzvpb`8qj46%llN(o^;%la97pa{rj_~MV;%nH%n=P)5RDJP70l*`kq>M|9(Fy62N_a z1!NyW_x^44kUyq(`JLc+N}f{JO%5QK*@^@K?L~k&$APKFuIyyy<`X%PVQ+M}&Xz7h z$4?&S)igrxym6X)PDZzkBv^CXXX^6L{FAz}HSl=oyt z>wbw^JS+v`Ff{Q?pEiw1kul!o-!e3ILBxRi`H7}U@DbI!$jTJ=P$SQASd02#_1OM$ za8G`3dEWTisbGYBlf8C%GxFAEd+M{SE_WudaWKB_+_|rwGEI|mis=Odlt`sY2Z!6o zugto$j2u8o2Ba$x@hNDE34ksLC11HPPlgcOwZC&USAOd!RP`t2Jap9@GjxXqZ$$!b znCMhDfaHfoA`ILYXiEhHGbkJc6wSX7B}IpT}Sd|<$dKze1%DQ#W&By z3Sze+ttw*i{@}Hc8wXSVR8-WFq|U?32rPbb#Kkzf{YaJ)7Sn+%KT;9!k-k8_B|}btW&B?>aY;E|7@$XWBqyLtnX67F4H&V0(ExPsa>VW z(lQbs_AL8e;N9UC{mQ)EzUs?+s3ah7;5I1Z)1~p_U{FD;zyR&EPZnPkmaIb9-DxiX z;yNv1h$Ilz9~>E@R0(rVi3n|#i-mDbO>h9Ky94GSY&7u>VtPeCBqb!5!~f{8w0xebg`05{nR8zUJ)96Z+oaNOuqR>JX)|2 z-FfYL@@7=Ak)#z;%U$yiq|l=*RT%58UEl(<1p=aO(7D^W=*qZdpE5*GQgam>EG&}x zbAX}Lbf%;0mVWQEZ&fDF@!+?|gaJV1a%DF0+p8WCY{Bm^L!|{&#o(Awpc}I5k zJ{P`+ljZqfom7z>TUMGe*bh(^_k$6v|JL3Fn!L@htk@W`!y1-ZMnV3LRqvK&ZlP%T z>ccXT8V4;Ozb!UV?psJZSz1Mi^3DoxFv3ni;Fy=RFJrLZM%H<7Ke{BsW!kxWuHlQw%#zcX&e0=T{kH#v)VZv> zpY!_eN;Zweq~jXG3w%uhh>wrN0;AqeoIyU0*PSm(yV(fICi@NrOI6OeNiC4aT(k|; zP;n#R!6wR5ydBErJ57-Q_&Gr5hsAeamz-9?p2G!ct6#}QD*pP^b@7MunXJNi8Tc}e4H z8G%d@KbbL`imUeRF|RUZ*-U}(srRkk$GwU3e`fKhZ}dUOdPs%v7-cdy;hi zQ-!7WH+^8wL45qNzWFytfBlH@)tgFM;rTFrV5W-DZ*A-YC+C?Gtg+|M=?h`v%Augg z8`tCY=_SZNet_#mol~)B=VLm!Moy{X20%?-=paSFw`x4p(UVDirieH?C>sz zPxJ5`7^Y0epz3%rnL^T$d`oL{b)Kbj%x!#tej3%da*mYq`4&piNSg4Hy)zwAMo|ee zvV_Qf(h$oVU`V1jhFf_=e&&3R!!D-{R6Z=3=N#!@UAM~KZ;#x5cWQkp?N}AkRWRcC zlBa2QhVK|jXvlr?&LfzCgG8u9CPyuEC!SP7v%Egz3B^3p}w8%bM zEny^wqgF1n=Jxz)poi>$^ZjLAqYpP$Ze~6AoGbdFNuotud51T)sH0X_N~j~hD#_Io z&713fgD?%7`C}p#7}pz6EE;6cust6n5s>>nYXv`O5papKx~BOW6iYiEqeaA%I<=t! zzj^TG>ujhlQagLK>6K@&W&0W}KCuMD;69%@zoHrM@;Sff&*y*&UxV}eV7kWQr;x`q zvGd_<8@jS#B^#Ni0{6jl$!E7|aazAUB6h0wd~QU+V_KNc81(9TWn-ClCKifzM(<@g zZW!?|3kL^Z4jq?#|0>9Iah2%3gH__d(>(XA&hMmBH--ewmm9S5R@lLSgnqmR_FW92 zSw7w`z1|mq+a6u!V|w%yW?e=>@D5Y5y(ifm3O`A-CP}q!TKHv%^UAp6!`v9Sx;xS@ z(c_R!;wpE(a(2@|_XQhr!b=$|x89KmeXA(wUToRzX}h!YjXtC|S9_1yNL+7SJ9-bw zw%^R0b6owKHV}wJb6I{m4J)6dQ&{>^gWx$OS5c=1gTARNHkZK-KPPN)fcc<;@6yl@ zo9J~vms!j>j$X-m7lT>s?;p>Ti+-N_LAV*}qxLyrSNhH2lh}71Y9h}TSuinUI4I#N z#Z45%F>ob-Xg&Xz{g}G2gx~j(Uvk7vlR=DA3J|Cf>LGw#YbweIX-7(7BCL=)@_3a- z<3f9mLs=f~1!8A*Aaa#ib$|3WdYcz{->u=eigleRj4~;dSSWE#$)}dkMnhB!`iuvs z6wr1Pv(07ubvFWn=$D39d%Bi?#xFVF8r*#Rw8&F_lz4)E3xrJ@xs0|7xbs@?j!kkz-_qk%6m17pO_E4ld z;N<=gxoPqDz4W}+ux7<1$ZOa4D3h0M+pK(LLEfM!R{59A?C8$VG%cxGbmM-gI4`C1 z*YZz8+oui;%OMPayX!r>=e!~ zp$3mzrye)w9+#Q8&cZ$>ha!uZeKpI+; z)@RY7_Op>nuy^SB$Y8ko9V<`W54TcXt8#AH<@32M{DSsP)ztjhKkR{P_qDqvNmhY* zyt3&~WbdiToL1^77mP5zz|8FuHi`QArP-t8&%G*r^Q9dp^F!WOL?D3I_v5L}ezZRF zIoN>E;Ihx=WbwxpTXSpgoeO>DK5xXKF#!@Pj?l}h9AFClXt1JoR}cCDEg`L2GwE$Z z@X5a!cFs-&X1K+1ub$TGkpZ0#u*ub`^i?xjECo77;KY=@W8!(kZ3D!SU|BD@c>Cg@ z_H8%f7s>U85rT6i&<%b-!TP?)9eD7yu+26U-@fk@{o}H?`>ijaE9-7=n>6C^r-H3> zXmxARqmf6aD+MvW8&(_4RG*`HPffFkDB=Eq|^7@hAhNwTE%ik?uu8L?lQl}5pm31wjLx{SVKwg=Ol z>Hck`Lm@1KO5PRxesu5?=^W|-106ZwJr#4J2LMrfbplYa9&4Rh_W~w%H7%AdK!c~$ zjpU!BLcMGDfQD{1vZUk?dm?J6?;czAS}0J7G;K;tnu5sPzz^8;vV90 zOnJn|eF~Q%S6wW8L0`oJ?|@Y0I8}1O3JkR&C6noV*>{WwQ;P(Zf-CPLMJMESHfh2g zcjy^?~#1GV$3P|*@}k*(PgrdtOf zU)Sz$WZP8beO}?1XGjpQB}!n%K3S0|?$&=Af{Uv&EV{jYLE6ZmePWs^&O`PpCJnVV zyxzrlUQ7{(-wtXW>cvBuPXf(w7~iR-*2@H(S1wGN?>{6&9Lih?OO}J?0pOyj5f*@R zzOMWR6Nznbex{Re{`MDv`hfINXtareoSxs2cw6m)B18D3Z0#JCEDK52_3ZImyKO@~Q zdY^}38GfAlTOm_#z4iIRzZW5=)Pd~Zf9tLvC((_p@JB*~{`aB>R?9!%kFePr-)8!q z_9o>e!H~m<;h`2{U!nw2H<*M@{zo8ZJA4D$LC0PWxTSu_10YbTtJTqHuJ(h0zbDWd ziAWWulmB3QchmrDXT*48$+OcOR9qiAc!BBrb&R-$j*Ufp32%NQfb>DjOJ>~2d_$kG z;zv0P=Z1x3k5r2K@P=oK7n4|+z6)efHAhb4H<+xrnL@?pPnA2emeaYc8K6zVhR}h7 zbV|N~{@nZCAithJU|VdrhMzltzcDd!1*#JWxDyQv%ETaE?P_me@lw; zcU<*#E0B~7XQM zOn1t?vi2LwPB9hy_bU&O)1qUKyOwWhXlS>h7YhGD<(a;EPB)#IY63G| z0s0OC4}5$YwZtI6P`NcjPB1aGMA8&PXgf@Ctp9sQJG??E=l$S8f)-QcDJncp*FCbJ8{zyK0M=YFyMPy=WPA;uR zw|@TDn=CRnxqsS9CoyKIHk5&4{3sMPzx_4oiNpc&He~ucQspZ$gGnp=KUU`%)F!tsDH}=xpy7RveOsuNqwzZ|~>k&8Z9RA<$b9(=*M<&Viy0R0s zW$a9^|Iz$ALO1}O;#D~)YMPLg{HEf3J}YCkfEjAV)(1b-4?k=r!So*JxCwk0M_oXu z0;W^pjoZ-&8~n7^%ZB^&@>Nz%FU$K3g2YiT)Ytqxe?UKgpeeNa5L&>Ysh34sj4{`& zk+C;eB}lRiCn!_MbYcC?0IRP^4AV-B$rZ*|{$<&|MdI^kRsd*F+>Pq%yI*B95oHXw zvC}$d*N$K`G3e_MfX@--SNIWhfTd+EUFe*HAEIs?{tEQtWQ^Kqx}13p)7Y96w+xs( zKyv~4bhz`J*`^J+Xq?1z0Dfiwokzn{7@*9ctHo~JvJCGjYUy{;U!bBpz)7{^_+#Vv zQ%tJ=sJCW)Hx}V=J6|dy$8Fpl&G8rvKV#+><8sdzz~N(e{x zg?=jq@=20G<M*0}$g4zoQzdD>1$Lp8y!?b5$aK z*mg`{FJgPEP*``cOb;eNC{y?bQ}!*Jx7;(OS=n+TF1l(Pq#7RN6j$itkHL_4V3<4j z(;@f%-F3gK7n-;%q*3oTnqQ=U276|U--nk3^ulh^!%8AH+=)-e1a?wffCCK2i9N?E7Xqhw+SF@s$1ZvaS^q#VV} zrmiGI3IZB^lfi-^mYz0(o;Dz+#{W$s`Q5Z*__PRkvY8^^Jj3)oc!_*uiF`bS+w?u-GlP=AQ(pfx zBqktE#+XvH_5XjB{}LdWzJB4B(G3t3Zh7~Fk;`TOYO!WT5%33%m!249Bs54iB4=l8 zl3kQ+ygR+GMN8&FZlp_x0+|ZZfYeIuP5G>_z=yJ<-qmrL@iQ8e{04^T0D%Nu9DoKx zcX-HR2%w+N(f#E-??@Eq}$(Jb}`>4Q{nL2WC#tj|FLoL)27?b@Pq7usfCKB8HRSs2;O#npv;@zP|bnJXyb`d63-xwQp=>#4*X^ zWEp1@+O>4M>+`aL7GkV`7yaL@`Ko3mx2q?-)Hh>ouVE-9vd}9( z>S@Kf$QwsX%~qha+OJ;Eb~qYb!0^iAZWqj9Z9edfVq(Y$5-{F7*J zie zLOx=`YcPP=#z4!{bX)_XfjAj}bzc1c*n6+Irn+}slutzwMNq&3QWOhCiXugjuAou{ z6s4>55Q=m{5(~vf6X_))5{f`XdI=FwL8X^a0z^azEp!qfBsnAT`>(zCS-*9A&dv4? zDajm}bBy$qW7!SX1(r@o9(zpWD-x@Ig0OZoahF5pLN zwC;iC)HAH-R@+{NJXd)-^Rt5SmLpqJLfKf%-QRTepZfqHN{=jCu$0~Y!y#D?z3lD# zOWZaCni3FxEM&ad!MH3Vc)jB$cnhdVitoXSH62reeq|%!5Vxx>uotk-+tp+*XzniY(+*p_G%2PiEtYjWca(=auq9-ug4xq zjYU38Da)#0?--uAsa?IxBiN408h7D~UqjFQ$ZLz)*OVz$qlXa-AxguDL04`)N#|0t zy6haPT>NTpFqS|*K${TFM)fZq+Idxe>s|D-WX;d;pClwPQf6tnvNjp61y$jp4as@g$WoKij;|b0d z?!+E-J8DUUtj<_nFcHaq^7}3xvhSU#lT!75b*;s=P$!&a(JOq%eRa_N#=6L8{J#ppNA^8Hs9z}`(r|e<~M#ORvx}}iFC*2 z21;MNY9zp`N4ticjk+Weh28y0nd^VF6uGRHF8~cBb5tL+c&CPtbIuupxlbCfrq^VZ?vB&d7~X1(Fo*rW z6`FOyOhvBIx6qSzh{yikhMukIGLwo2z~sE-mLXKCdVxnqm$`oG{VfSyX7--ReK_#P zCpBzt#CqYM-L!Y!*O;p)$dcne$|h;n`Teizf`iT;Ra$no%t589w)NLyRF} zLZ@B18dlT6tlQ33BYvy&hVYqKzwt=yZ)2!!4mi~J*jpk8M+AtEWB<9na+v48PI;XKmVqy*f?`P~+KhdLGtynN^5Hojm zW8-X8D(jTOv32+gBY&GDj@QzFM4hzTVW#zZW%zw77OREzdK|3>{(U!n{~0##c3=U$ z;AfP5P1*e-hq(HGuCZ1ttU2i&Tg)&r3mtYdy!q;|oQZ}o5!`dHe+d1z9|zo_-29%c z<;pi%uUDjPxY2;>4TfX@60y-eKf~(b-~ISzQpGNoI6nQm23=qR_Y)1S9p40s597@> zI#f1gm>=PIL-_2lwL&IF%Z0_r1Y^tbobnT8>Ac*}dpn2IJY|c@@97TH*=^0Ef9o=i z^P$Qm0KNdDKG7}j>(#Gy*H1Vo^skzhR{YxDVa~a{1#iB7{c1oLTFy;FtQeSq0e*Mc z-}kfoFJ8gH*X+$b2b2;!qlek&y5CwzWl}>4;76ESwm-q7_QWT6LWA=&;ICu_F)^-4 zz!wFIOP?)1_5u%Svzt(kXWcA)pLa_j(2==K)+R7V-^65iqMqjg^9fDltzaj=NH9n0 z4oaf{(Mi@?1>FrM)QMGDG)STqC)&fOPlBOz+F_!%|HiWfIYV{60ZlK}ITH)8ol^d` zt^a;Tnt=@rD|Q7KO`=QHi&jJ42ZGK;0kl-&ULO9qw~C2lWMLz4j{$DOpNhG|cIiIh zwUyTi=E!fdE`3)`)d(z=kQB=IBOOpaRb=6teV005(dA`hW&8_K!!;@R{;}oHli&jy z#W!UL%WEPN`Mu8W`zrY8Lo}-jV97yE(i6#_V(EXS!hauK4l$NIY|S&Y1q^R2rJY1W z8ueJsUWNe>x)=?mxKq@dYHw?K2WkdkigOJldh2d$xk7G+LXC4qeWsu$gT;=jD`s|t z_t1hA-;auE^=7IP%Nmf}mt(*Obv-N7M+<036I_NCCBv-GHcZSAhpf+$A|G`+IJ4EZ z@Zu#K=sONu=zHP6pYGCMaDZc}e}%THC^R|>4sY~iOc_*GQ8p;7*}q}yWARrD_N!hy zj0nOY#*$X7T2_(ex#I>ZJAr8OW%bOmgg<{c%;D@l937p(swO!0JN&&`vo9BQ3B|4! z+iymmyZu-}J7l^6#!hMHsk~qHpmeyD^CK75{37LGr^&}LSDAmx0eZYjyRi3ipp*2R{e-meVIE8!dNXwU(7OpkDJzUAfzv{E5S|Bg4STYKa#I`g}xy-tg) z?rsDdIgpN&&1?o^6%SobCcHKbMX`}uAca^JU1x-*E0gLoS0CfATRF&}wx2VOag6kl zLJ4|wub(iJUqH6Dvm=_7cgPW$eELHr;q`eH<9b3;+`j( zjyTTZ{;+=e@4vUxe_@V)zkG4v?^gMLzxnTi0OaZa!xiFmYRZ@P>wc%vE^?$(5m~ch zwp!&Nx^UT&(H=od_0GE3{1??>y}4$a|K8rd=+8LDGxbT4qRb=lBXg^x!`=@VX|`v^ zmITah>Jwn@ZZP3}POv?{*B<1hCd8)PFO+Vk?o(QvR!$yWPP*GrJ5+FFr#G_~wmnM3 zr_q?MPb~}(E0p#tqT4OISLbL}00tIl@KeqL{r~Y&+BFsmrDOnawiH7YN)_Y>&cdO_ z=tg%>1EXo9ckMe+;_8yDx&w5@h*bjWw|9s~HTw%%VT7G;Y%gk`3^=GSI zCuG-@pu-R$W6d;S-W2T`DiV?DDFM-@On#9D*~@+r6Hn*51W}Tkb3F^{P3*2^!htNGg!1T zLrbr{IuI$g4>{YndUNQD2JNYjQ~~rNYlF1*y86VYTlo#xpxIt9fPtnDo-zGMUfJmC z%MY2QEugs(feWgBzZ9{v#W+oyn=uVvFUSr>J>9 zN$KBe2OCb>q^TJL8fQU~q~e5-OeU$G_Ar0z7>Cn7fO0)QHX zJ*Z|C&DsJI&3kwynjh~#o0&;qm407H5VyT(?zcFzZc?33Ok8+oy5DpbHulK;XtrIL ziM_(npMLunZn?A6t7<`qBeARsoWtxD_zRxy#y*Rd zgI+=bn=3!aQ;kSZA2ff=WdyYvO+z#ll6Y%hK=`gi{u{6a%c1qn%O6|&LO^yxgFUClau z8I$H>hg{i9tX-M77BP4sauBf(111CC$f0qvCkTi@il<_yYq2fo)hdl`#INoodw%^} zsq$hfqhSv_j^;6#cH2eQDdRnA4QcO2jU_q+%Sk!9gt5n6Ynx+tcV3jyM#Ckz7F`D$M#{KtbWw`C& z3S%EQn`K_&9vDVEjvqgITYzJWb3E-3y$vNVY&KXkGm+V0jos3)BGx@ju~*(12hEw4 zVbeX>OYt5Q)y+SWV`3cUtRRc_KFtu5luVv24V^qqHaO4zp*Uec`B82N>3LNh5HuNt zw1FtQNO7_Ex4+*PyQ6qH7AWq#WE<`yY>zVVX@^&f=N!r^8WYJ%>8AfW!yVHq{P7B! zf8kbQH_Yzh7B(0Av*=E*2e7E?KIbs%i92N51zbY+_yv0VRG#P=vyO#BR!vCj;5JD6 zC$?!|YyPZ!%6&?PHL3pFn^Gl;%snwLXwcZI`kZw;X3+tP;wj-9*pE`oY0U6xy`l&S zwQFNospo5Cg@qWlQAnSdo8;K`Y&c`7$M{mZ(uq$lxG@}Uy<%4ro~%AGhE$6TZC?tr zA=*Jw#FV@3Hjw+Uv_7oUwZJ?M9S$8izI{7Va zyfs%Bz$R1q-YF~Yv^3yLf%Y_--+yNq#1=%m09Kqbt0_V8$k{+5lVdWRSfp~xd9}_r z_*fMHOLwfo!LTlfpw_$2xX?@K>dYXWyramTg_;!|(+uVgVM~H^k7lWJ&o;1lj4x|{ zeVaVS**p|i{K&Ae3wWTeimYcndy?ZYM)R^>)aa+o&ZR|a_6JHH#d&{^I>zbD9oD(k zR^kG-GD>Qnz#IC2qHs?rwsC(m7LyD2`<7UGgd^c5*EVp)RiM#|A{Hmd7Kdh$Tb^*r z$Lo)2sLJse13X&LdRECq^ZpIw^cHJRp;gt7zxhgAzjE7q@Sa=^x%j=xgHvj^cjYPs zcMEnS1*++k-ytqXtjtjPSb6L6yv@FUCfJB4@-5v+;0eliq`W#^zfq$(?(iT0VbAI3T0wghc72+-Eq0Ae({}ITi4BCM#m2J zf(0ZMcDbtFh@#)nUCxFrCE`%!c3{>O_M0eJ-@)Np{4O=G8B!W&04S&#eYrN+bu`}ZOK zd4XP*wT$Pxcvs=gizYqJnVmde1pP&(j$IWA-!bwQQ!GwUH&@q{Xjl57v~ukVChsQh z>lL{8-HllTnq9WbJIekWG>z`)y+ZB6Lt?{Ph)?}g&G@PIgB}>v+q-CRA{pJ*@ufahVq(WlYzK}= z4`j}LD4KaoKMq^k<;r~jiS}nO{uB2drCXI_Bv&~EK6T;JN*837E*-bt<3F}@@1K?D zO^sLJ+KXB}43C@^hv7pE0`Px2p^E3>Cp_}+7@?U1&i%GADQ&v z=3uPWIvm?DR>g1#z&*O1lg_`sc{T|;!y6>QD<8x$56^cv(5Hy;ez}>6fM4oXcA8ip z?K45>1pisB0wDlf)QTUW9gC|a@Bpt!6)iX65&A8-F(x~A-&$8?z6RdwMwsG$j{UCd zc|?I=fl~ct7Q_Wk-|q6su}62agGe8E)5!xFj+GAZ48_E1Q8DHph2E`}mqwlFL|_CU zpqgxoa)k`#NsY+39QTCWOykB*)W9;Kqk-QqlbE-xf)}T#WvoT#*bhecFUBsTq|UXhO5TBm<_fJP3``qHq(T87eD)fM4_4;2lH;|<@n@4eAA#m2xi z+!8C~K0UcEPp`*wn4W!mdnsV5Gx-uk|7_Zn{UUW+*#6}{T_yU;!MkZE!z5>R@4zY8 zsGQ8_tsZc@Eo>LisXmnfaX9}WY{!hh`-_0Z{D<%?xrTKfQoy#R)$C5|pPR=}acfU3 zDA#DaIoFXvd?nOkYF>j_2%L_a4IPs=0ssngS``X8H4=Tfek>SwX#sYUmufwg+QaZ; zcF?l6KO;^{vzK4u;?4-_;M<9)7>Vba$WRkh5Ii>73vpffD*WUEv}?`*zIcPAR33>F z9X`ytJW~?H%h9YesoA1x;gr{$s?6g13#~k+ZqIY@M%-QyW@fRp)w{c|^n!$j1 zr3!fsi&kAeWb;F_*m)rr3axdHFO!2i*{m}QW$LK}efD~PicmOywbPsDS5l>%jr2M0 z*9TCF-vG!GF7wRjYGeG9Q}PjCcBX!^zL%qG5X7~R>u64x$u(2FrCsR(had+_e#x{( z@88Ng>kxy)=1fJGICbJbszzN2#T)H@2xIQLKoA79_GmakDcR*VI5xXPJoyHJ{q zuf!KY&poLk;s@8Iu!~pVx}8iSGqe-`Zuh4zfEf`#GPeF}(Pkyv@A&nr#0h%++*ESH z5hDP+oh0z>ZAuUUwOXk(NmO{tdu#Rg8$~r0OdrepjJx;Q5}w9rXF>Ox33ui+NG;KP z13bJnDF+-ZKEhm2bX6)dTdcx%(zu{G`p?-Faoj#oz$7U{W!i3zJ7{{<7Ep{fOZe7Y z|9P^+#d#g^c=~bKg>+?`6YHERrw&Mr3Jj`Ld^5G7W2AO`YHjWG*HhqJ0<~bC)&(Wv z24@Yfo@!@v!=%v{{kU2evRJh1=WQ=ufpCNEaomK#B{5{{6@VzCe;jzo|7A7yj^_+M#U7bPYH!wI?a`30T7ns6oY{ za%Oy@-7J~Qi$c~^-P!bO$#O4d(U#)aBYs&o=gZzNtgeNlM*C>YJC(R43yCBqu-~5o z?$?)#qwtm;5jC(c7;64Z3(fOVz73O=LLv3XD2V$3r=7}nNaD~@ajw|lWpXT3%0v90 zyV7F{C57)k^1`@%u#jIe?~TsJ-4o8!P99>GV>+$-LDaC3GdDEA;32`HFxzcp}JHlHp%xAdSd z7Fe1*n`42fx%rh*$a{v3Za@5shsbPE&l?SAewShM6#a;x%kX5N1J|yHtglwG3sLPr zzQ~+uo>SYGJyG4hjSu*&Eox5Dk4Yt%n`wZ84BsRmy*u^OpkbrC+MMLsm8rC;asv-J zxFTY7x|F9zxENbequ~0_H76}pMU#VV>1fiERhuZaM0fuC%@5YI#T9o1SCqHNS;T#3 zP}6s4rB)4mjg1sTO|^?PKX=fg&H1H+2@kn=+0fi=bkl!2@^E`t+=4Nf6+8&lwD&fg znHf5S`@&@|1Hb{ijgI^!4i4tp^(#7-)Q&TYlJH`jh|~KDD{q+RQTt(qv7}GU-kF2st34l5zIsDC7K0CTrJoNO>q9G?-mreK4@;))%}k9 zGX@l5uCi1=lZ<12wJo92x!)9qY=kuC#~k@ zsJ8<;G?*sC;kZ;W5)z|W5y;2wXS1*!SuAPB9mausP ziWQZ&JR$FP0)k3UT6;TlIq}Wo>V`4k|8=a`fM;VSOahkkhrJK93b-G7G4@lYieUam z|J*wtNiH0vzQ%=_DnVA1Jk#0Gn4dlVySbP=#bBOr`sYz2`VoxQ-;xR>l}Z}vw})Mu zGu*rNI_Ktwj`zRX#seEPwy`OP*$7wj&9(A{DpYT5JGnNbH4BxgK?tgKF4kad7}~TM z^A=Gu8|--_yjyu92Ej5dOuQx#Kj98;-azF%2&355#wwQB0$C`Bqhz_pnqsg2gw%Np zm)>ND9f`NZvhw+jVnReL9i}h~NKDhX8 z?#3f_%TH=%vw|Ymul1Jl=&8UPh-wr`lSDyhmJeX0`E}>Elj%RGaXb4)JVVhg-RsMIe6#N17a&Ck^2(pXJ zp9L>mSM-!+Rs^hp$fN1V4Q=)O(X+8&iDFG1}ZXZLl1Z5M7&HUdJ6IDKV*f9JuUG2Y60eB=J6}DZ z-ltioG-&RFP~3ScCtWbj=7EEaijqLjJU5pY#A2H?->X@65me11KrY(2R-rUxeFv1@ z7HSt5#9qDPD)$7S;*0^1Y2)MsjD741uz(<8UPd$0ZUzGnR8cJD*r9<7C>7N2NR3DE z6{417I&QZXrtj`K?>*I8-rU7Wiv{PxmEJNMC#iWfvRDMXTT87+@A42Hov96k46Q@V=W?QY;A$eNiewkJLL09ZZ$ zYyNoNQ__f)l~sIIN}yq?zJ~LBQ@=Nj)grsggGjdJ&2*n= zBtt6`QFdjz%!aGwItRy#>(nh3@ZjH%)q_eQ0gdd=h$Q9pu)YOwAoY~30HACdm?Zw| zXg@E$zvbh@?@;g5Gbneo;C|`8cB)jb7+emqrNfz>Cn6ly_f^F-ZG8JxI)1!inbBXF zl;!Vrrux?#4Wj_(`FjQuJ<0XIwKVF8YQG-{7w*6&Q6^JcTA~;cCOK3(-jCsx4}DtA zu<=uD(D^lxt@*CuH=4Nq^eSw4c5Tc^n++G=4V$BnG>7xJA9-7r0Gz^&(~3|c)4{!jH!r% zoEg*4!eMiBs4TP7v?2B!wZt8RNL--FUO}i3-TbR5ch&l+asZg90SDJBKr0mAY4;%u z+<+|eiyeRb-Ze97O=TG#c-W*CVb5(P!5g6#YVR;W<+*5UG>{ql1tXmAV{)RZ3Edl;d6-{S z%D)fRHLwjVa4s~gQK|q$vY>1!jsVFe?O+<9?h=k2o(Jdyi8joAOlep(b@IdSJa4O| z5Aa_+_>(GUGyHzPVu)YvM#wpNC`RW~&4oV{kCHLU-I_II+G^WIm*xwzx{YWB)5+In z4$HJlK}^Fdgxt>9%9|(=vH@u|f#km7f)c(OqYGblU`lAPu)m$dGt76^Upps;OPP0(T*W7Ar_E!ruv7h zP0B}fH03bGxo{oNE0akjOH4@N$?W5HK+FzU!i^~m133p~k! zebSZ#i<|g$3@3L8k?vz)^!dYpeT8NqeBMdmnM|C~Ve`#yi1d~I>1qEbK2Yxj2uwl( zxo$6*#L2U7-OrT~cGvn|QKiK{CB)Dfdyf_Xp{f+_oxEg^y*q2uGnykaj3g9A2scV znoUWFrgC#=*Ipd1VQcjcxWIsGGi0d0Ojh}s2`NC}nKy1LxEIK8U4?sd3-Ib$bt+ww zb6L@gU+N>9$bcN>DO&@$eu^yfX_k8!pd%FY1JgJw5((Jh)C?bCwVRK|AG`OgasegR z9^>8*6|eG)^OrM2ZN}U1Q<)}?WuQ$6ahv(3Jsu?IE=1x#km?qgZaZgmb420Y2;y`t z)|$EzO|@yujGgj2^{jHDsB_-qTTIalcNI?WPop6~;-!iXcYZ2EtSGSCdb}*CIEeBxD9tlS%u=!r#4qYGQop~6 z;Wbzgvu6$yIzo{_T9qY^L>sfM{h|QZ_j^@@DR}0-=cdh-m{>#Ni1M$_%N*cpb}pCi z4%#e-XS#ni6#mv?lwG1w1DM@2(BbLu@7!sEXkKMw9f$LCTo%fKp>D!w2VI*R!#eRw zX!>{J{_laT%2o1!Q34CCPh;6(>#}J*UnJNpQVteD?P(O7b;(*o*1uMXe~B;buO7Yo zmv6%UibGQE|9%Izv+| z1w;Wl7#%o`J@~<8^HXcM@)`j21F=!}FG6*rWh0D_3ETYF*zTyuE8x@z#BrMG3WYy1 z>K$KPddT!W|Jd71s2}SA|4>6K4R~x22s04-33@zbDzkI9%}@EW^xji`9nV2uGe7j7 z#J3kwUV%%ye;FXD?x4gLuLDjh;v$p1RF!pyja;b$p1}I)xmgym)7ZOLzZWnrdx6xS zHJQ)yW8Lo0?mKP#y62?&=pCg!!6hZVgV-6ikdSbJ#Wk;Dw#84S`H@mkC=J5i0oG$C zP5|>WSum*pLmU?C!s7gdqlE@jpf`BzzD3ovHOp_ERhxi;el{R+$Hnb{7)NNv@r}gl zE`wQ1GP`Wkrm(@b3pqaZ5Ag@ltT6&WUI$&-9VqbXKmJIba~w=;2HH~I1h>!eR#mF^ zK4LC-&t=T~l!#@G2SO0*ks>axt{D2louczRj;g&E_>i>8aXN4RKOEW!7M%hJfnI4J z*DC~OVJY2K=ln!-5ZkW`fbN1K!+Lv9K;jagfzE~!sa*-s8_0?`xvK>Iku!PnX`o}C zDvE-Wav+%j^%AiTMBH!)W6lb9U(;{7%;XLO3|MKxO@-2`+Z;z5(8kZOCt6t_>`*@- zeYaH_PJPv=bntt!S^-QT)FDwY_czr$e9=ZNX59jegB@=e{M2$b*`;GhOR8HDT)Uhfzm(5uhn$gx;84)+hb5?-4 zjZo_ax_>Y5iGrUg1Te1!keRS`IUEAqfZj!)YI9RyQ%P=G(`+Q_XrA!5 z0xx(^S+eftN49^t*jC#{xBK@nUjA*xxq*MuBLpkjj8(LcCy!8){(kbly0W#X;j^uj^1-Soy8j} z&Ly!pMniS@^yQqww!uhgi(ALAV)-EkRqpPK7eH2QT2zu(o7&%PaL8-pqW*>;s zg?0$dc@ZzWN2Zp+o|f^jSWG1U-bQeQcFZv;@k;K+-xpkUr!}&`Q#s`4k+~{l@eMzS z35Qo#jD~cASlV_s=9uqteKj!z;9Qltjd_(?;Nf+dZ!Ju5XRK?gL=CSjwBVhcm7h4l zuR&(3$^%lV_$p^-v8|g#FvLz_Q1jvW)D032qrwVa4v~w`9t&Lm?x#n<0g!-Bz#y38 z24t7b!YOUK8EtcLlfUiFc_lhQ%>C(Ehq2eorH!$5*lkU%Su0-o(Knw)`IixqYwDfV z4^xYIUd52k9>35%uUw-%r7GbeF9PYCqH3()8(X&!kN@9ERUAl`knc@&ste>Ei=cd0 z_;Nmr$P0#*_y0Fu#0|u;T#$ic!J-|8t(-Nw4t+3EIZXu!MC!u2cUol>!UfeXYD}^R zuC5tN_H&sp?aN3{2aJJo{nGlC$WTHqlBS0#hVo(2_I1F|1&mZE4qrv1zIh_OSI_j8 z1w^|eS5(+Y-O%Ii%G+YqUG8&$l}snd3{QA#sA2{96z|^otgqw>sX{lN5uArp;>cc5DA^$P~ z%2CX@R33Nim}BJl!az@@ePD|XopyDRT9-F}uu2vI(iunZmTB6>^99*YuZ|yxOX$|L zJshgB7|r*68fzQ)ZH!LW`)B=~OcV2Sm$EHlYRrXtT_U44IqAa2RzGIYy3Y|>_hbSz z_&rRavC0Ow?yRW#^%aY`>7!ot(_TU}X zvB6@9DYD{TXvhW@l>-bZqW3C|S~G*=XTs>`LCS9w)Jjzi_#_#Bef2am^yKV>Y!ISZ z<=m}m_1}s|TEcq}yM-hnHghHo(mr5r>klS4lMoMP|2fs4Ago3q1fZ=^H@?fS7i4;{ zk{C#*;*9`=FCSQp7%Ly~t+c?;4T!=TKm^FIKCGGpTy>Joe%1ZUN$8v}JZA>>Jdd?9 zU5B8q>`zU4aO3QDpZDoI>o4|vijzv&WN{}u;TM8G3TFGP|0r`&ho2D^n3s{{{UpM@ z9|w3Nq}>tz(@K3&y?dLk65f2D<2fAERSX?{a6{Ftx1n2;`%w5xO)Ay)VO+2L6LW=7 z0+n=0#d#M`!d2o2RQDWbE_HH2Y~kR7);@Cjm49+9Z+-D5IC{}QqC4mx^eqf*K^Zay z!jcVZctRJCWL@YzH|SjiKVuYtjRky$Hm-{93UJc#_YSsr4c~?zeiCLP(Z@st&)Q#) z6&$Wg-97%U^5q)s%1N@oMXn>%h67tQt$|vc98UT<_AFPSy*#7Ys2|*^eC91+4#5fdBdLb z%c+E|Qvjnu@^e3R)^%j9CZD!_3-BXviW7bCnc3!By<;-1EE$|NIT!wJ;CRTmgfD@7 zcqlpbVbi35w^Wab&QqV~^K(AwoH^9r3oikX-^|3Mi<;D)yT`YXe}m!e0FESa5!=Ks zAG70ZvfZS)p({!PZGsV!i1Ao-m#igspuh{M<3Ha#Ik}$tc=vDaK>^iV!*OWWz-^TA znvf8^p!-9-!O2h!&in{%@;i8fwBx$DPtey?7{U6X$3D)S=l0E`XpaY4q1eZwrfaJ@ zJDJbIh62~={$3qjlq{-z9W`o5O<79Z)Kv>or=)ht?tA5}9F#?cm2!+=>J7ZfLMLu4 zN~|I^CV6H=@^|8O))J$=#!Y{t7bz?Ow0p#xYsFRA?@9OjQNDg{ZmufPT!CoGs@N+6 zJ0Pc^=#11IF`AwDC;Pl!%Qwk*8@FXdb zj@H!#xmE1==TUp1Y_b7?eB=*rk`q}V^{y^&B3)I5@c!U4S~tx!u$eXIi-S5Rv#EKq zNLxU@eRcHG*Q7X}w5+W+If11WeP^Nzl#9uuE?Bk;b?< zI`qDvJufDf$IAZBvhQ2^%G@edDM7ylDw0X0P0hlH0r=O5`G|Hj)HSw1 zQeJ67|67!fN4hv&M`u{4On=CFaHDH6{phTz7a&Ud+B44vVafH3+IDgW1V;QYuk0Is z7eq0aY5HDpMF#2{@u4|9H)qeRzGT|Em(Y5pS3hehuW7BN<>sDt=@}GKd{^7XxH4Fh zJwTgCC;(Zr=hsp_@{0k-k3MFrO71QF2X1Fvv-xLa@SyB4hPl3`zq+bbbWufXBP(Qb z^i1zTkDV0`z!ksi+0FGtwC|OO5Y4{i*Oyi|W_;;7G!vEQ+k|58Z{;%@vB+QZEq1yz zGaS*lg&%5K2%jE6_AP3{g4c9YDIYXMI+%0V=zKYqMMQP;<;{owX$zSBE0r*< z53)WXks96aLv`NPbBH!?VSb*P(Ed9E+^ zY#p9Awu^R+bhPBIVExZ4`NhfgpZZgEZCjee$+-`{e#oY*nDjDy4U>n0TyorbMO^!o zLoE}Nzpfc$$I!9rTet;;XFyELTw6?xC~fp6_eUgU9sYY*8}(fHFh-e4qAsp^(|(_x zqY>I^LtUlXw7G85w)}{`QyFT zLXuKNkPTnT=>xd*%uc#1Q*Z88`fGCw<8sk&p4rLl_Q!69&kRu>1By5|c8rUa@?-2^utvP5hb6PRpZ2q+v3r|f%EkWZ3U4fx zM#tQ>){^r=&C&~zRtqp)fI(5a*0&zGwCGt~f|x==7hVs?ceMU_{b?}$vtf&oQYJ>@ zkVnE{Alu;nIA@BxB-eV&riwm!qin*Ii6`FvPuhj9mL)sxVzt(zZpCgYE%T@7$Ij|- z#=)Y4{cy4|op+IT+pIXy4{7?RyKEWSyZJ+pqW<8L;-2H1N;WUeX{t2!K6_B>4JXG3 zt|ATqU6pEQP_a>i(QTmTet@`5uqvg6S!kXPZ7v@B+2PEqMte(ZR?#C{&b-oH44Yxx z3mO56lGMAazEQxiN_P}Dc<5m^6r_G#n3}gZz-np#YEb=gLkM!p2IKkhQ+Q+a`jd_a&8QE#vH0Y>%)MBX$2~@MwqDHsoft8wr(S`VnBrom- z%=RcjiZH*@Mbm6sZRj6!I6x;~TaT4lbd~JIT}oY0ET+R}j=|FPJ4sso=atjx0@wBc ztDSq%Bu1W8dfeE>AKbHSiaHPP&>h9FKS5#(DEy_9-D=-*5KG}w#|~;LUuyilGnrQ6 z3UtU7ERgqCr)+oHm>0M~wY%xC+5uUW_NrO*^S)#lD27J`?#mp7f=Lb~^$vpWAn|cj zr*@V#SN<~hoc3yVA$Vad95XXT-O|BV;`8ZS^0xc~_Bymb(=zv&(J9|UN#k$|txNd| zGqMn*u?6b=fL<#{AbNTBB~Szxx0c2bLSt60kqCpecR=2yT?^jw(nlB7IMRhwX_%@p zb=ID!a^J=;Syu2c=L1v*Kkk5ioX<6Z9a62!=3RaZ9BA#^)qx8Ym{UB@1g1UIu>!5L z@Y7`gj^Mv0)p~n6MVjjfJeF9yB-Cxgbu!!L9SA)V1xB@4pamO76`;!zGnrtQzRU_u zzjo}DQIZ2QBw)n3vwNf@$LV@V9?r5ymp4`ms! z>m4CCbz*6*$B)3y-^Ls{#g%O6jr>_O_7TVp*Q)e%Rvpb0$Z%BcvUqE$$>QPw(%u>N=>VUx4jla_r2@23O!J z1(hv)xZqnUU>nAV2+bGp9BDT5hJ`ov1LQjC;+wJML)o!#@Cf%W?CF>Co&iMj$rWYTol~bD%kADC`bLWAs8H9knRj?=KbPkrRV&R?jr_a_-q1byDC@ea#sL zT}&0?q@OG;u$GBzhPXU<^k`WA=$nKirySID?&avKiX9dMA*U z3reJ1pBolAdyW-|WGe+?%{i-fW<&jZ*ZMY1XcsfP$eqYoF<%8|qXie_;LxPI#pv7k z@dK8s#Xhi)8(y&8{yU%G2?y?f|G=PK$h`RtHZy>XubS5Far~a`vfrNeR z{5EIi=`hUN-#9SD&)Dy6y4Oe&<^>O<0%zLxOaEizLLLy2Kk-s^1D^ZmCGJQ7!$7Gu zqGO}0n!x^VlAYTlMH6B{Lp{G*@s*IYmA4jyK^SCj(z}bFGyvkbCCW+iLeK~w*nGV? zd#d&DJ+A>;sfvYa&IjI2Vr7zg?Xhn(QT1eIf6|ke`&Q4kwM`#4$XVqdy~C0s{@KA| zh-&K>o+ zk0G}8@5|U4lgbjl_Z;Xw^JR=LyCJb7TIQfExfGN6vl9~TbwzsFHY^Nq0$kUYI(CV} zjH7vmERMZEaC0=rD|#q5pHp`0Qa$djK>|kM_W+l=w-3$$KuncHxxQbmMBdX`=#Z!3 z&K#+_Juoe*va2hBt`9leL%X@%9%Kh`xGs~j0O8f#7q`(~)P<$ovf=LVCj886tIQo? z$!r08!}-a*mdPv5S9g=I)cR4^XG!|9`iKGi)$m)@n`czTM=Q@ zr+}9?41XAE!4(v&Z?`9#qf0%YrtFM&No3@al#UWnz)*CU#=&01H|rUzSiDzs4mz<~ zw|PngVW|GT_HK*1`e!^jb(HIu$T7`0;a5*qVBXd;ns$qbqfBaPWo=v1lVc`y0gg!P z&Z)upR2?@pC%5)Li>UzQdEz4#4 zr)_S0mN!~p>ARoIjeTrNvMu!2d`;lTvh!C`^m|+{Tn+KIn12>3#c~B{oVTSourogQ zXZ?4Hs?$^bu1q$rHU&UA-t_o!WNlc3dy!04#mBdcS_zec5q&Hz7Jl1qIT72QUG~7V zBmtUCq-rsGlFIS>f_g0%9MnP!fm!k_$=i;ZR{V7ZvadMxxPPHr6_L3iu844&m!u+b zG;+B?DkS~l4~y}nAOX*C{nFZIb#l6V6vgqmmA{6D}g`Pa`20YI}{cKac^9G4M~yCv~^$MiC+WH>9U>zS{i{LQUlyh`9x{dotDl6EBy z=OJPnkA6+VJc)VK??0=h1*^Op_BHIRHhtvm*-Owug&vIYo)4&9H(Lo=h6vPIY!EAD z8wZdhuutHb zdQRHibd}T5ulpq(IDdHzu&DTH-WsDU7Bs>@Ay?vT>XxFHudb7Ejr}zp-xJ>ItXF=o zYyRZk)yEs0Dsn3Fm=V#kZy$c7F{~Ya`rjbyRt8#Z_tic}_vs_d`4Hp~KZ}z1S8HzJ zSbhAF-_e}lsZ6C2?aBRt$BNaQ{)plHu0N*!^y`g^5%I%I|c zczc1@C$Jk>aQyVS+rz59r^;z|cZNC`F8Wp%9n11$ZmetFyi*NI#?`XU`i6F@;%}<; z(;Am*;+$a|lnNsjP@pGDj%Bq|I=*NV7abA1MmFG9(qkxWK2U(1Hh$N0(P;k~Jrt?giukdcoqF)}u@VrG zf&yOBEmpG%fGC*&!j~0{{L5jK%vjmiq%_F{0#P3q_13k>N8>jn$fV6zp9c0H0ye5I zHW{+ss?fCJ^sAo=;;P{Jw~lN`hLT|{GrIDQN{5sp5URmaVCZT&G~>WsmyJHS9#Q!I z2~rUpoQ}c3pYK=reIcFsfL}#TLLn9IHeuCO1AU=3HyoOuaRaJ$y1C{N>7PG6rDlf) z=y~>xwZB})FjbRH)GLRs8V~vbn-}Yo6X+IW`39E07s&X2()jKY7T}m+iuaMvmAn;T z&|&mk_Q<O{W=T@&6K@LAIE8Z%-vR&X{;^w1c-v)-ww9c@GKuE|%Yxd&&H(?B zI1zvbKns=xRw_y6>=>WIu;GTvH_XuV-&9C{{RoEbc==}^n0y`J)C2N@s*3!`gOh*7 zq?_&DcAgP7el8aWt$ntREl$r*iHx#FYc~7zAu4&oB_cIURX{&onoN!WJj$;o*_4?U zld=lOat5|4_4TMDs2;<7>?OB#ksGw7oDJh}Onjdrku zMCe1jj?8L(%Y+(;Xa4J}618x=hLwZFjs7>$fOdj?HVbI6=5${5$O`_AP_hPgj0FdC z9{l76b;6WsmVJ=rq~1cILMG@_Z=aUY+(&01o$11=d;`?>6ag&_8voDALGyFCf~?+b z1$gp~{iddx{||fb9o5v=wTq%+0Ynf*rGtPd2q;xRii-52ROu?6K%EYXqPIl$KK>=NgXs80Q`jGXe^xxPXnPDC;Mr zd*9{FPd(k$mZW=$t4212=Dm*Rr>~tWN4u(yu<~5*Cnx=sT{9%HY3S2`sh{~k{>?^w zbB<4jl*9`<;23pCz1s!s`7H+Sqn^Iqij&)-wKJ$x$@QpQ-W$2-isJnK%RmXdj0-mQ zzTk*yWXI{*$kQE6kNIfrWB>g&il^RYcQYN|2iEQGG=o)@#qCEAtm=;+Kz5N5Z@Uh* z_jga52%55jvY>US?ZvxF7I=*m<3(jOo}e^Na%P{JUz zZB(ZMMt4GZjd7dktcJh968P+8&zQipU5@^MfIB#oNV>` z4vqjsavp9EOr`X;btnamY?50pfUCVMq}PFJj$^&+-M#afQ#PvijVisrSBS$hfTa2n zK2atRfCiQ2=hg|}B*F1nYuQK%8v>OoqlQRU1~DU#A3&(+PKN-wIr=K+`IDR9pt0Wo zKbD{nbr$`I5C_hl1FOScK$q_&a}m)-&qzim4(610&4KF{>Ko+z-H5;xb>{Nj&wKMp z*UT^P(>A$2rt&P2Do2ynRCJCSy1vMyRD2R%KY!C7GPNyqm%fJR=3HltCsFydz zEdhKyP24+|UU_AMqIn{F*D(t4lY>Zp3F;b+rG=w$t}dXsWC^qbEPNiLntW|En5-6lJN6DYhvLWq63`kqMkW&?FPP6y!25asvXZHy9UmYf8=dIrk z$z=V)dOemMzQoL@R$uzHKyod(=imUdnb-j~AgfdopOd&^{aB~%XGoOTe(k#YMYG09 zn0qz%2g?Hi=eld6W`95_zWJ(`z;OTxFY@?ix=WCf?5fR0Y*jwaz>*L;?8JXJ=J6V3 zI|#y{d{VrP^<;$K-hCl{KWHq)YVyi#8SNBSeY6{NrGE3`oTcRXCO8Z8$b!Iz$Y;4N z_b816(P`DVZs8E;xyo4m(jASo#QV)rg8vD%tEpS)pNe>pjY?j(zy!RLF0XX6^>p%H z?@N#|C$33db1|aiWcR^!gL%KobGgTEYy4>gh{&k@~AyT~eK2h$dH8U1$ z!juD%n!P$qwh3-k+$=Z$qq#y0tl@l`#oY%Qw`x6}9bRfux@WC!x6$r7Syp=DHk{CC?boCq zjnPfGoY=JBZJ0<2ZTtY3JUldgZ#T3&k@1tC-IC!EXm^);GWAUmS(}7oc!U+kBBjfV zjVmReP!{Q&A!tyZ`sOfT`@^H3el0cvHTj$mqt+fiWr^}@;rFTUAfb6r+>szN%wWc~ z;*D?o^Rw=({dxT*XqBPtSl-LrCE}@3Ay;Mw8u>gSjYWC^lfG_m!2y*e;=Iu=$0Bcb z=vE$6MXn$J`L=x#oC}0|MkCIo4#RNK9c|sea}hE1JKQo3vETk(IrIy~5n&;Ho2yEBnXKao)YuykE>G zhHrdRb$=deFA60_#7PO8Et>niiuo#D3}0Z#2{Yf&88{fU-|(Z0%c1W~#e#H>6ps_) zz`Eo51TA(H@#aIJX=-*46tr|0AMJuAQLYaLDsL9%h)L#P9Rl0L^(M-)e$`E0n{~cM zVta5i&}HoX@l0#qac~c44d&H6Z2bNDQz#6DLHolm zeA4usAX0tyT>XnS;O#^!Cs`_3(N4?siuH$9{Z}`K=WYaroEXPY@~}~t5K)vw-{>?} z^|*;fo-umI{U830SB?`3r}+_GYm>a>b$|ovy3H%vVCXl_^=DF~{8vu}sX7gi)J@y{ zM>>&+w_)vPW5N{pQ2(hRrG@C~@uc9`;2K1e{#hc6R;(dV>prhI%Um5%C8C|7TM0EouHc zVT%+1BEm4L%K)u_Pdkc0tT_gsDo+IJ?|i3ECAd$u>9Hh|gdEXG@hpWaCC{nm$2e!I zK)&RqxX8~|K+9V-ra_f38(Q@Kl7gFGoHC9lkSmPWh_Xwwa{HZJw!d^T;RGPU6^ZP{ zP}68fsyH80TgTy*-pU&;{pa#&Y?1<1_H*P3F6^-GFhFpOp~j7{ z>4T~lE7yh6i^?FgRn~11XqdCVrk>2K@!8Vpdjk%%gdNs>MNlFKg2Ck#hY$XdKWd74 znl)}X+81)RqS>c=sNn)cgCOrmW&AJhu-!nNz2*5SK2Qv@X7b%T-~nWIbq?~&?X z^6D%rSnDDgFXt1?_CZN+WjB$WNmuZNg$t3$qYb--^wJdYqNE&v*!q_gWiEgSF8}Z; z$$FPBaai8tV~h%19l3Rq@F5QrwE%Qzhfq{0m43P@50y#m*Qy>!5X4D9WPaRtqYPwg z4z8^WeAwTfOu*DQ5&y6O`f+b#@4e9J29t@oq6lw{ii`#9xRJgenm~Psps9c4y@>o> zV(0|q@I^4TvUllGa17z;UMzyx*TlNNS*-Kur0l0YK{kUxKR#sxLzIJ#tO`JFa-z}I zkA!<_c?YH~7z=CVm{l=C6UbA(9G4dwVkiWZt$GO+NkDlPG#DVfa-;L$E4~dN;ld1w zErtpagg(s6cY%oCfpzrRb*B5H{h-{k9I_ioUD z7gNx0u?{@lCAyD3K%a~MjYiC0g0G8Hp)P1yF!F^HZTopEnfG`kmT*0yy9LMq~)jtM^#hWtOG2K^p zZ0ZPdVt}C2QBES5U7vlsh(UL>wgcFG6)}tbed~jHdH#+!j!j?eLt<16igPP>Hz!dS ztuBfj4O^P+6m6Rwe#@(d#X)N?L|915R33qi``1cf)Ujox$igq0${U1ox(@a#q$y-% z4)1a9=y2{_#X)YfQpi|0km2hjh-8g=GYepTwUT9j5zh(OS#QZZKE9Wb`?NU_WM?`- zCG7mH;~8exf5!srCq+cQAAz{M0O;@w7Bxs5D+9v#n6AfZr6{3-@&f^r0JZU~dWr@A zvwT+hn>s+EsWf_cBI)URmgBki!pVsk{wMu7o;}d-(rv@LcfJ-iSscG?xC51Ytkrmd zWumDC`ZU_ahjCpZ-2e4sDyr$*Uo-{ajBL06oM~aX%jaSUv?OL1y|NY>}9^37f)gP)s39J5+mqV zXaCGM+(w9TG&hvHR%~^QtcBj;bDOwLUfZIWTGkx(UTAF?>^Y4vr$7wT3uV)+JQ#*l zvuwY6pBfMEHpth5g&1MgOv6;xEBuh7ZOOadG2%OKC#&(5)<*SOl?F#UwjqLjh;UrI zPphhPcX5~N<(MGoc17KZZl{-x$=0oc)NQhr91W&F*&w~;+oEMHnWv}Fi8-i)vRu8g zx+_%`t&5yBLod@`Y80bvSgX8x$t(cRYe7PJ?#-}YoNK0&ROH78`VF}sT$R2Pw@hcb z;&VA-V;2pbHoT8F+pZ0KdPcgj*y@GNcQ%x3|^Lh?p- ze+gW)VeFb%0=F2~fRE%!E++BZY_*Sjr-f!g6-)YDdCl=jZ>#$kPqc+#fzizjTkTTZ zm;Lo~80YSI|38xwwW%26aC`6hL4${Z)1}>21`iw7voDK{480GM6oy@46TM8~n(lX!y77d&q)?mh#Rir5lKW3|2Qgu8 zR}LaSs9W4)S&1-8F7%wZ-mOc|$6x0)<@~0(irt?Pmd$<`D!o$-JD}C9S-f$ipTA(hveUh!SCqXO&6*uBF@d;GC5>>;B5TMmxudF^@Hvr zgl*H8?@y{*T0b8mW16A#IWV^=X4Piq8P2S2V;XG{JjLXLF6YJjW09LYGszZw>Tto? zBTG0sg*FeMjjq{@@mGke|+Ij`k7|Z|iP&+m6Txlp>~ed>;C}<$Y2eUd+2Yfq0lqC$`7crFQ^wgSe8aN8;*Y{uC$;|>AtwQiwmQsXVECXTqNneF)Z7`tfI!0;HEQgg+MecPw$CNBgg*n<#B~YmDS9AC$4W( zL19kq3JtGV7cXD)Yrj1Cqp`lo-IsW{P~7~vq{pZ_<)p5|%ySv0g`USRa-|p@u046g z*Jxno+{}5>Cw4p3`;kn~A==Z6+ZOfw{^8s~^HNI8%X*2n3YJv&v-V&lnT2Rv_ZEdl zM-GuiL)=+#Cx$e=j~CM!e^FDzcv3oG}a zS3u^yoZRzRWWd)_Xyh|wX~J(R_!S+%ydtl@ikJVsy&FljeR8}Nue-ANyu9#^{RQGi3pLKMdXTdR(y@8iKdN zM)%ET=;P&oc$b$J%|SZCD5@AMlG-EAkq$fJRsg57y8Fp#_Q@a8V~8M<3i8XStF+m1>WykW4W)Kf~<;idk|@d zJ~dCWZt9sE3$ILkv(l2t;Y>k387$gUY|ofyBGa7t$*UpL&B8Ki)D<87I8HEwHA1k2 z-{Z=l_?%d`sf^`L$C;mWwd}z~1_zOOV{3UO~r*NjtH-Z7HHulaByRRar0-it}e<=YQl!z!*d z$y=Il(aw*dO!wp0Oe~4Y$_wa?4V?H%Vjz|MV=*ju# zWq5+oq|t8aY)Y23?q__bGC$4F8vT*1vGcw|HEUL1ve|u#rNm;rE)yFoPf8vPvyo%B zZu54AsaWZiy_NHcn(;QCRNv+8ZiaMRs^BQiIsJ*wuJ1B8sl#{w;FJ{w10%^8!$Q@>TNu--E$N)MFgv~SBMYj3S z4yr@;DuSi;4x0~i)Rv9~E6{eF5fjxuiB_U;ReVF#1Fa!yUL(7TmzC&GE5;*H+Pn1& z=KJw!mbg6}ietA$LI9mI655l{zTVbDc|1ghweSdmRH@KjR+h0zM{FF+H;ciKwYQWeNs z(1iFyRqLt^@O~y*E}3WDsD8*(n&0_}!yWHDA9(P>FwRbO=jBA1mAb`8x_oLTCcb)e z=2y{cBjhw(2g;X9ylzOR%{nt*a-|FX45_!|9^{^!Ns)w&QiaOgo`Q>4M|Yc*f8Uaw zB<+eM38$G7mZ*G!e=0A>b*7FuFF9fbss7~z-MY#Z(t;Yby$}(9QsTB`aH32Vafn=y zB(Jf5{wP_Jp9G7Ad~GMc;Q&j97CneUE!-cc+8DXTF91^n0e1LZ8U*5EfFa6W<;Heu z@jxLnFPOdxnJC;V%t62V`j>rdKKC2zYUkhBP=r@1P8EaixaAg!Q*}L{d2JY|+c2~- zX|%vuZA&iFl+EY!30K;jLpxPON43*d;LcA{k+t!pz+{DeCALS5exyj9lGpfVm~(sb ztic2IszVb=E~8ylZItZXSG{1m2OYDU;|Y-)VBn=VfhuSpq*M1hRm*LOB(nfnzP)He z_#DTXXD8wRLLB+-Qy?%eVcxf~BoPtsGX=HL0D2p84#S{1A3djmyQ)0`OuaAm#7Es7mLMZm;0w{*ATqJTb z;cFZ)mKgmi$YN}+xj7XCr=B(4u^;N``B7pvw+W|KFuUDefRTGsaE;_SyONM1?{cBu z#QBDyJL)8j(xUr+*kyKcf^NlQy9v?~FO=-x-?*Bg8?q`l-VY>+fr!2d-F zD|}q0CUfSx8{0;}G^IE}Dx&93s8&GN!LomDw=5pa!E3T_7}`@82D$JQPq#xX5SKI+tNSZqI|zb zWatFZTJK5n$JWF8Sz;3YVLsYvCMdMmZm%_s*C5kbJBtwZH)he}M+M&xcS?mdeDrQw>OM58M7MyfFRPbqb zn|Y7=UV#wMgk|a75h>9ui5%I5`mOmUX!`UOroCz}mz~xyNVD2Ig3pE0#}za}=ZjC< z@ciIzuwxVFEqjHn3*h=lLBii}jXWHwYdlagAlX<^xn)8=a*oZ7Ecz_PNA^oA77}QN zRGKa-Es4c9X0RWBB!+aRsB~qxjIqBA&5-6Vcb&f{50ReOVR|2&=Wg8O>#t^wpp#ws z+L?J%MVP0h+MOM<;K_gyH~Ik6QWfR#^0h4%TAO>viFWATwH|XRSH&m2^1)pul4_uN zlZrZNwfgjm70z$5JI#tFb>KfY%=A|GMC(P>9K&Sl!xZ1Uv|+!@Z&dl8sOi@7uTdGw z-fq_4R=9ko%m!;$bB1MNu9@G1Ax95ZT3j;zqF2L)yirdb$Qc5C_2&eGq=H$LnYo^M z+oh&5vMJ)xhj@tOCS#j-J;zqv!h+diY>fI^B}5V>EY^FKlRgc@AE6k zd=`}E4Il2aL{8Qr7Yi^KYv1txOjfXx(EkcJWoAU? zc?TDiy>Sjs9Swp2=LRq7eFf_hn&D0@sJgj=OL~wyL+Q31Hq;(aVBcPUxqP z<=pr-H{QS(y6Q~X?+NoC#*bWk+R*M6^1dH$Sh4p#VRP#Snrt77ondGfY;M2`Ef|XF zCJScQuI?eWRwcACjGp#YwqoXEmDe!06qhh0&90h_2d*y-$V#7@RR*mTTprASq=!HJ zYSX>6Nd+Ch9Wk^fz`<=k%7o7Dd-RAd|_Lse{V*KX-q zVo2w+|9dIVRU30_d}mgsf~A9;TTuQL`Q@mbo-v1$ufC=ixc zjXVhNYO@?F2qr zjkixS9M?8=!W3(mEt30yosyFq`3iq{-Hf$`}JreA##H+pb{LhPBw!!23Px) z9BCR?UPfuof9KcGbxE;bQCWFYl8ALqt<|bJoHYw8mCf1JojAUr?bhiPGdCt#1`mtN zZ)2B4iRZ7)IOZ2q!)-)x=O=5m@rP^!mE9XIjqCegj1g}@I+9tlaF{VkTDTau3I8Dd zsCwocTFvSxGSNBT@ipmnH9voODr-3VJMG73UrW0%cU)G>8HuN|YTf`NJ?|k~aD_QN z%l{qKu7m)jV1Mev`(R3+t?;MKGgW~NHm#O64kYEtJN%=K_ZBIdVI4c$-_(CLVbhT& z2UE}AJ8?y;f7%Lr`>lymb;`_AOw%>oan%Ve?J1r20GJ_JwkJ6SVJorz&bjpdLHi6t zYZ@kDDFu4zNki^Mll8h);}L6m4MR}ZdK==eHRgtIh*4B+ibU2v!|%JgK$MkABh1v& zNlZoG{!sDHic`mig=(ksm6M?$`%VXrrSsxWTykAy{g0$Q+1j@W_PP8fj4U{sh2INJ zJZ%eedhmu{Qa!$(wwvLe^%d>N8rF!BvP~$BZO3Pu?(o_&5e-JYrC(hu6ve9pg=teq zWZ-EK((rMqwG~LNo*FfgZ)m}C%z^&->8ATAl~S0~?ZE;sl`22B=-82V6S^ixNSGRk8)~P<)qYiRJCyLuo(3?F&5E|(Dz<{oe^9g-!J+{ z1!8xC-%QPO9b)Q3tWnjNxm9n@m)HB;mdGa(y#c7DJ+$r%M#URL=-2>Y7OB4|!wzp;x=csFgfhUKx)S@E6eV2vc02 zT$AMF=5li9q%pb&Iu<(`46m0JpP*wQ0b(IWnOIK){>Leh?}T;qc<8dNSOK6SUL96^ zKvvA&XIi+TVTz29qQ9T7UUt)3$WQs6Irh50tF#KFj3Yt))3F9K>Vr4J>EN>6Lzn6b zublC3r47$1CnByplNh7|LMF3RTasdpBR_D!S=jsX+w{**ZFrXkq~>});ZsCf9}8%% zcU)%8bRlgJD?3zNy+qPrn#3L*M@OFN_bzc=k=k-3U6{Z)C6ap#a21j{4L_Y0Yct+1 ziB{2T0uwG+3i1W9r$6qP7Gn8_*bD0B*2$Ca5D7zqDn_tpz7y{64X-PYF$;gwx!KK; z{Cwx5y-u;Vu{w?Fesk=Pt9S^40>`w^59*MA6qE=!q^40cU)S_x2Egi1ZX3T8vw&{-A$wNqKZjVG5_%Yt`xDkibZFo)j{@7CH8)v;;r;Hl4MUTPZtuQ! zpHk%5(X@m!^e|$U#k_~Ctc3-MttTM{WCrE3zrhUcsTr^}D%5*&9RKGSNiI^zVhHlb z&RnIz?>LsUUTlBPapn?{r?JbSBNA;_vdei5uW1`2AB&Ka_o^)~7$|fhlv|f`z&tNA zzcFF>)BB9nnOCl1TrSDXGK_|H-+S5;UD;#gb$PY_Vf(N*y!L68s1V7@T+_ue!`~w$ zyzaJ>*^id0d(@74*`6)g=-~AfmJ?ge`RuN&u=mYD#xkaVe0+Bvc%obJ*Gnbp(LW~k z2&40-<8F+h`H^ctjRu^sG4H{Q5tvtlHY$jXKOwR^%UaEGy{xae?=h$Fk7nKWjUEvO z-s&~A1cL62)HGpWFU5cIM6-95HQ)@c*Bp+24x{)GZOJ%+WHz|~c`VZTHg;nci_mhH zC7(q*=+Yh6MqOOgdb=WSVnCrrFWEA-&AM&eaehB=%5~klnN0f>uOZsXW4IVj(_h%2lJxKSh&0Ro~wk11dIeyyWmFO!3 znT)^-`GAl(OamXRXB+5B-nE4w~3fb0Iv2cxj^3Q zfSQ#7WpzA5*Xz^z+TS2%=zIP*#ccQ?H$ky2WzF!(x~<>%gOkQ zsn{Z5n)_wWw>xn(aOEpLgJwVI4se;7pfRRDH(D8+I<{ZB;p66<13e$YU>Nw@*Wi5P8*|T5pxR<_Z=1>R(W`CcKT0+^IwjX+T($*fwg}Ei98QD_ z3egZNOuYXlgDwpHsOt-QA|>UO?pG_DX66I7ndrL?{J(!@qzem;d;GqH{;bqw^I9xS zPbzh_5IHd?L*ZHd7=R4U``@6zkuthgT(LNJ=d$p-YA=;8#(oeP3qiy5^NxP|_{aWv z+>ZBFbGC5xb zx)z<2pwI8{mzBvT=X(}%K;m5E9pdt(9^-)3Rm}9Mmadx40sEqcBcj48#<~`4g3bgu zQA&@X?i3Mi85=&f#KQlB;4U8R?5tb0j`I(8vz4Gc!Bit2wHv4QKo}s$?Le{ zvlw8Xq8O)mm*e2>0sSZ9s-2B?s^#wEDUz4x?A;BZ#MOTW44XXfq}-xi`#oJ)aS_B~ zx>CF|n;?HokAm1zKp2K#vGyB$p08RSDw04+@-uWQ?rk*%Sn$W1j^F4ML7JjxKUv527=39oUz49Se@F!iS}a|vH8R&|Kel(D zugRuze-Dht;v?D}A7I*c?8>3-V)c^Pihu^k1kEH*m05@3_-86FLAqEs>*n@gw-Zlk zeWiL2*BeJRD&mC{_YbSTRhcQf0q%9AbeE((>wdjK<7!BuE|Wy$J{ID{brg7O(2?7f+Q*mf0W0gd08;8Icv{&pX*Mv|zqBR%gC{%Q$g9jr%(T zNgrc^;E)5W)Z;ciGLoaDv-`D0G}v3Kio;?6y;zo3PlF(H(+WG?J%Wr$JVbaM&bH3iS{<4gxXF92w? zT?=0Sbp3Ptt+w6PPKu2(rJ~%I&q%lOffb3@L>`HuNsG$ENM4_8)n41lI~#M3vf)}q*=Qp?A>Rn2o5Cvd1n0)bQ2HW_(^0c?Yk0@>v5F& zO?7`f@w7(9cW}jCZz@-R8-b(-af2$~O4fAE$L&__9i8TeXj5W%Nu-pR+DGnp=FgoG ztM@dC@SS{3At$QR$80CQKBDM1nXO)~-jw_;&Yu?dP4t<3>}%ok ziSM}&dPnU)%0SJ+e@u|m6oYuD5R<61y6GL8ndf^gcbr+cz-{~DWcOuHdH0(6amM#( z;Fb;o$Pr`cL{-|ZEHWk6;`8nCt4aYeF4h&@HNF(oZqqfXW`Qz+M^U)(snuArGro54 ziDN58N*ff&BXWB79dwwI=rzV1$37^pnK*H!I=JsdVjRYeXuo9DNeG7~gQiZh7s?TN zbI6Bg*3C~Fj7cIpmn(}NG>qG^4fEDd`Ovr5wc88EFg+Ok8%GUWTx_vk$u?!1k~8NV zqn%q9F&a?be|*ON%*))|mna5V=UH$L@6H??-9Oa9y zcOBuYmrNLNC;Hz-rj;OIHOM|vnJY5~MpC98Bj| zJDW80Cp3oseQ>SzhGU~5C69?vt^UFkfD7+*pfswP^?zX&z|Oz8OIyDySM_ud_Yph) zh{T><&h_?_LjS}aU-hROpBKz%An~p;1RsA{IOTgs*Ol-;!gd`y%yp|Xb9r7r2jM8u zQWy645F`VcMS)+*ZQ^Z})7Lj8 zN5uZqq_y6-DOiUj%cQBuzjgicdz`^m{620$(wV_8p;bbm#RUX3;@E!WdgE}Z?sm79 zJa!%*z-q)=hT@7l9A8Wf`-$D@n3?jX0)?7N6^tHB7(lWgE*J2Bubea zJy!4Z*2r1^#7px_Dm7of`qS>uc^(xfb~fW?7K%&DGZ(49r5HHgAB##;Re0c2Ql)?> zg%4cvyrw*4aJ)Ku#%g8lcE){=*LUhxf{2rCi^XoC=&n-9E9i&O=zjA!2yHc-HaM$B zGj>kaDn!cTcXObwc>TN0yZrv0)Wjy^m8%6B1n;Rt%UhP^fNQ~BD(p|e$&cz^aHNXq zFe3Jjup?&_l=ltJiT+)8R}*&5zR-|z*Q>?-iiYxoC~RBlSqJ6T5c1-}k;(Kf5#P1D zQCHIVBT9#Ba+Eb`&Z(*`JxA!Z87roZxLM@n!43fJ+>I|{ySOYsRb%Nlf*X@A%rIfo zQEl59asev8v;zX57c_{_vX1YuCAOSmY0Fi`(5R6=y)CayuSkptYk6~{K0atFIP|sk zQ6ykr!EI++-4I|rf1NY!8&fgoiBh>W@s2X!91+!0RaKaF0Q_VkIS0Z$7p7@z#Vz0X_qRTserqS{UZaLe<+cw# zTJAKd2hL}nB`|9vhfkRiZ0x7Pj)bqtxt!ig$x$H0xxLtA^5J%%w(GJX#tUAiR&}^T zpEtz)ud9z5>6V2-Gm=A6_di1K4MG-|PGh>v%710aaCv&CpJk3I9ENFBMJJ%}?&znt z>BraKLGM+-T07x`A`ecR_x*FpaL^Kh;3EHX$P*s=-^c%-Pd0qnsDN3mR%C=Ut7czT z_lD0c64=&%kDlHv!2<$YU^h2xF;)!`kW!>4H5Sq1+R#$O$uZ`W+VQhg)VY0zZs3@; zLIx?wSZkj|E1vlRA3a)H_7uH4d;yJdV>_&0NrJ%_suo^U>;t|KC(Pn3QBS2=tYNO6 zLb6z0KJ?7Gx?86@CuBGtY!ZLTS%yWPgj?{H)+ssq2E8Zv-=z^jrSOgS2eTE#Q(v|1 zD@6}7SHaikne~Sc7&>z^p8E7kq?xCvS;9dU#Wyp;c^pKB9yHY5k zV(SMAS@zAWgg=Q|f$S_1eKZrKr!Z|4erGOQ1|FU0GxJlPn_`KOj}erMcPcNe+bq^b z!`4%lC0q;F@77z!<8+{Z`Q%`!`({ic>l$CNK9*`&2f#hf3SoCo*wzdOzMf_rC3Uct zr0yL?lEPGQb7F^YKUBj~rv{#*I2iQ-e1M3^3(V9XKbs;QoIAxKgCD921sDOk`%?8j zcW*IpApRa{836V9*B@Yk|0kQh??0&SrzevqqKmiHL2ReO9q*a#0iLI6X3n!qjSwoX zCb`rt_jAkou!AdxC-l|ssPDxcD^V-^XgMQ}GzYy`M`LBHjOube+v;YMW*_UCUJ-eY zWIcA^fK3j=s>CK;#w%C;j^29o&`QRbh51a5#8*9qZCVdF6tDuXaH(k<3doV;jM6^C zO=!Dgm>@4auW06<=f%CCQ)~-aP>b+yKIbvNlrjnO{#Hwp_$9*?wzSIHwaOScb&7kc z6((T-faZE#5&q+j#dL)M+nBdojS+an_qSmlI~4|igfuH!gGuP+M#)vsdSr@h+WoykaI zvB|ra3sURV(c+@NQC3HiaqPRw?Yu+cllTdwa*Q|#pWLHdkGDBp`(i)_549+aLVW|? zPi{amCK&eUd_SX>PGh&VyO98St#Dr3O|$&$49{);Uiq}-UgPh*J2;f8*FnY5qGF4| z?t9t$sFZ8&MxAX7n%jD+OXf-PUs4SRWbt+RF!Lt^HiY-Pxck577k;4$jottjc;H!C zQ=Ynviw%j$hjLkpdjf`0@xK-ybxe7wxWH*2{$TP_Wt>#!t}}i*z^vbLK*$Wt9M-ar zJv3t75D&mppkuuZ3IGX>3DlZO-Ik-gH}z&UUfbV4g37RMbHn4dIWenT*OMLjn@cIe zBN^Ql#G}0p*dI0BjHcd30`c#g@}}vIoBLrG{Onl9+E!fsdSh`fy&5CG0jd{%PB{fS zUVT*_;%67p8|Sl0Fv3!K%%^;=gHp$@ap+nQO)nqQ7&}ogL=aC^89nT~6p0Am>#IkXfS^(NDzso@JLowCuwPVeY22dn zw;j<*KR(z~4JpNJgjYUZ_|-{%)v&H=>HBCs?#oLv$+hsl1+zY3Bor3CJHa&xuEl(n zv^d55UN6I^t1!c3Mf9_}0od+W=y}tf?e2t~+b4cH^^*OE421+z7guzWrzhovzNT69 zCCSI;ew?0L8?k{~bM7Rl&S1#2UYT=uV#gWdr+#)Bhx~^LTmT> zLp+KWl91S1-9h$2BJE;YYI=PYaoL^ESX1b8iGyu$^t$NU0oSKQuOetNh$ zx_U^mnonq);iNS(!?SZ_nJm8|1E4G?vUN42O&0XL`@I;RISjU}j=kK4GlFNXw@l@+ z5&qDmsmi|#1S-qsNrDXM9L{4WM>)4tz$=EjbBqW1EG)g|N>7s*$0dG57Y}3-~D+V3flT`QY0qZd*PAf}5*o z#_pPW5P>Th+RgyUfqis(l9`<+;4FELYM@E;CQG!c3LH2Ls7qyBJ8Qd_w4A6ujx`>< zGAkvEzsghA*;ojHY8|{>+_eYzD>!rkg;px(_LJRnK~*(8+&uivScu!rdDA7ru13ie zq0pyzi@uc66;^_Y+}fd9qT)jpI9;hOlS#?~Xfj%^tTcJI@xaVScC)+B#mG`>XMMP@ zHrNhLJ|gQLrsI)PyS;kqCtU&_l6-evY`J!Xf?bAp%l?>Qcdj=%?ki6`!50g!qYabh z`NW_CTwXBV8UWV@`B+A-tQA(r`w@n4ZtE6nia9z8>;N}DIDUNS{cxN(00a%4%RnnfhgI>3+ z%wz=E4var-Ve_5a+bpx)3xtJ-QRLe3BJk6jmRfjnD>V8~In+sj7qqn|Y{*WAd|bl1 zQVVkb8=Kc$U7pYYjobA(q+6_f>-B7F%C)*3R!@JQG8^V3q5^! zUyDnP5o&Cd$nDk;D|BT>-r=kFFfAG^V2B5!Rzbjg+HQC8knInM0fjXI6^g|a9#Xnk zzc9BAHm|KRIkpA0C4Q%F&P-_!&G?tc^@Z|-zVHyAxY!d==n4)|k_NlXBrxNbL-!H~ z2SgwPr`}0l{dx&`6QC0lN%0X#S(-bu)GQeN_Du^h!TcLbTHys4n+1*A2-ujyWa`A( zC6IS1N!onHC<}9T8FoG;u@Eh`0I#R~TcK@V;V(jnayl25!{gC>jbrySy5(XfDpFVX z=92MDaB2+#xn|B#7p6@}r~os(4SX((k`uc^==tOa-(FO`6?Si_9S7^*MwD#vqe&IoyZZmeFlrzo z^SzNTDN>;K0JT#kS+SJe`B0XMnX1ZLdQpLa7YJ5-rcIA?Wz)lDE}HQ=Sn(Yq-T6IXT*omiOwK= z+}Eh_CKCXj(lk8Gj3A%30?>4t{k`4*l=NTO*>33%+W*$UlCx;I+`{M>@ps;+fhr!N zph)j#C$7b$5^;@GXvulF$Xik9dGnc+k_0eX}0YJ4<^GG;y=2I+D04`Mc~Bg%|S za42EfsKs?`LC2ARKf&j5S<8LFFvk>3;#<1T6wuZ%i_t|O8-FSZ&;fP zDu{f40|&VRI`$Gxwyc>{2=i$s-j2GL&X2%m3hdk3G8M~E+#3M93_jL|t<2ycAG}L3 zBb=??_Eqq!xka#MT{LNAMPnzei)|0LE7;>!ABokqN7p{SI9+oMS^PO$GN0h+O7=e# zjP^~oCt{IQS$A4Fee^vibal67y(lX3SP$W-i5*z*`{-OemFG5e=OpuJ;@KU zZ1Dn+1kGzh&gO7B_PmODxW;y5)vQsq4a{<++9t>vR~5wZEU*E*BxGS02?l}4cK{?5 znEeYDyfHI$!E2-PFXNP)+ggfb9!LNR4tH2tlauS^pC7z<_foR%eb?G8D+X0FG34-@ zY%`n9sj1l$Zg!FOjlRK?zA5fjzlatd0-G+iz?$y3^Q{$rGyWwfVnCM@T~L$P@ns3C z+1TZrXEw*=+^x`HL-L!woVVUmr~O%jEy*T3QC#Wr(sS=EF;NMcW-ws^0%|q_$`X1W z6%|$0e+6K>a7z24XWcO=;kF50&&5A-XV(ciIE9@LT@E`|?OmiZo>@;R8P|~cJE!kS zv@~JRM=P&J2R{k`*+DpU94V599V%_7!@BH2D<#9A??_@LAYS;hVgb&(lB97$- zbaws@4Cn&He4pf(&*2XbL0g?qqmFl-7*;H1#WyDCn8sdv6~7v;!jv<*3h23N<$)Lx zO?H%`A_0<&F-&A#tFd^o7)c6Qvq0olQLU6$tu0|)T1Wylmtws_j&}v>Bdd07wBa4Pz5XS&n>`+pGY{{0;ISL(kBg#YhJLVE6B$N%>u z)KdhQ^aY^MZft{)7lEDcy*^o9ZaNM>niki5u#MWMKK<=~vYr;&Ai3JljSOad?@ZQf z;zSXusjF4g2KdG0ho_~`QlAz78*Gc;-AmQE(KR3+xTE{=L-ADw(%eT25@=w8K6d_3 zQVD4CBek6rI9UWh7ket%J zyc+e_5wdELSo->nI*a|jYP7}V*gdwt%VQPzJ#t^1$Nbn8z_)xu?;_FyaosJJ)eoO} zPUD?t3I{1TzF|DSp*N9VBS%%;VYrWVR z4)XSqiGRBKa%b3fF*dbedwk>zYA;r8lg2v?_19$`W%}m@-T{1(yzGr5_(GhBMS%it zR28qw>)3KHmRV=Or(WUjjxF_=kN^kAYxTc@0`he>w89XS0S<8^=l5v|_5uF)nWo?U zlbKCShyl^ii=h_zdPzMaP6M+q=2vKed$2u*TKt>A`*`!8nQWa98kuv!L5=u5RaQ-)dq;E%m`3>8T9}x=}sgi?{?13mE1DT8CYyB%md@V>eaoGS%18hY#*1 zSd5L9Y4V}Q^@8NZf@av;08^Q_+x|nwYB9^T!laW66!|jnGY?lm!C>4FUUHl=bz>J ze*0(3X3Mr@o$27J5sQviBN@xVmvFJbXrj^X^B(1eQ&lM|72 zp6a<<>ad~0?q@gZD7j9%vRH>*$c0$`L#wPICD$ad%0kt3i%0I4!e+NkBKJ~S{UZ<5 zA9YS?60+CHs8L8oj@1u$N`Uyq-f}cMz@WQi_6owuhWAP*6^=&D|d@9t(Id&&>>sy9QU+0F8n6fTyGI* zQi$14CVr}o0Tpj5b@TKUi2pods*(}2!-Q}!IM~jMx5$^&xg=!u7|5V78g9x+SpOj@PkUiVRb&>2>dvas^~{xwVw6oXu%JvkK)?M(2eZGKUAyZcLReX97+3%}cOPVk!A zeuz${S|429)fz0=FYo1r_D%V`%b=5#CUH7PLsF*$67}i2nDe!mhAVieFZ8j?eCqMl zY*PJ7>+wina`n}b{R#NSpLC~5wsRkjPb!X+nopfzni~=vj@;fwk)oZO1mF|WPO8sf zFT@KFjOsnuT2n1lUK}JOo4Yv`zXBRxVB_AKn3g-q$65qUK=b$sM}t-BSrDlZJabjy zL+9OYnaz_x2I3BgpTm14d%bN~xhJZ2sT9{ED0k&ofOEr2g~ddGeN@U4 zFw8RCV#Jl)waxI13A(DMVoBJVPPqAgbUKz$CRb(&15%>QqM81!J!6oHIkF<+4UV@g z88nc!6s-e67YhE@Z8FNW8-5H*#0AE&@IS^Lt{9&fK>d1}rbbvQCu8LWuhq<+Xv;kN zND38_;kU}E(B+viHOIAXwGg)&u4X}|43-AbI-br*+p$knwVe&5eP=~*OgFwXIUcT@ z7~7{c<3+PU{X^+K&6C=K7{HaXNN^AzR0U!Du}(7E`vAX@T-r`#YJL`Wj^=T#MvcH@ z&hbRDH zwYMIDeHdkI_X;&KrKM0EZ%G$EN{86X@?XFPs`zQQ7a4i1idfz>|S6yIsMGwyDXQJO?Ws}q%u4HRIzBs2bBMa zH;~A09feh;wrI88b{@KZyYj-XqWJctz39FTEt^KH1&5BmEYuDHwZ^s41ear#e1XFp z<$!tlyYzpf0fI@>PkWVgn(0sF$Me&YYwlJTObZecaG>Xe8uaDt~+O*h%_GJu3{1W+Qtxys=iMxM2J4oqB(R70Yt?V;E228P$ji`o+SPT z?5N#JcBB!^qsW$P@7a~w-Y+dy)_pWp7`7H35+s!YQ>LIC&9G^C%h%)raThrp!%$*Z z#!wl1O`5djKG`{tyq+A?qTLjflRW74-lB?Xaib(Id4*U^BMo%VN%EUtAqRk`XTdcG zTo>^!ll@bg?el_ais3`8puOddEyKu+gm1TPH3K*OV!Z|cwm^gE&pH}27j}_F0|A_wPO$_M*jTI%z zRSFs(bs}4TedZ>w=lCPTqd_#K%{9Q%pI6W)S!-$+_Wt=Az#huSq#s?)`g6(^0kGiG z0HDgswKLWyejQlZlrV%Bi{&)PssLXn42+_jp|wEFQFci}Mta&M7^|5PEOK zPQGhVj>W1jt+dD|-hE*Mxt9_>oxpNFC30mD9U99*VUu{+FNYWr?)st5^PlyQI-@%n9w zPxdZSis2OoP*3n6hFR~>ispQr?-+IJ$6Wu-_GqRN82^ zgrzbtbdEI74Ye`fd1vgphy*&14&@Y2+-+#AisWi?;^Mjy1G=IntK+j@q`e<;^ z{ZAs;SB*;eiga{RU8_dNOP|}W#UAO)%Rd}jcEQOfy=B?WuO4Vl!8Sv_+yTjWRc5-N zEYlltVjpc=N|HO%y~|ttp(9}-XL38MFcY>=0Y06ThQz1$kKjuU7+*2c!0X+Rv!djP zzQP9#dO3_Fh@>c8y&Wtbw;uPNe#!l6Xi>gUYSH_aK9?f97w`3@J?dR^tWCoXfd-u; zhhp*JZ%T$Vq!nhWbtTUi_J=KBKELYS&kLfRrzvW4OMg(c0IgWm7-(#=aOM zb0=naOs8W+2(&nXZ85~L+z90sme8*(9@6)A=Mq659{5X%Y{R%JkF4SUs+btx=MxLO zM^zyy{EdBw`loyy{mU!1(xqR2=yUEvhp^O~s>8db$M3$cDOejn9-rFq|LIXaWq_1Q z9xN~c4o>1XDNgdIx8aXQ3LvRQ5$uty`l zYk;S2^iRqv+77|{tZxH!sxLcz8H|Yho{K!Z2AN*}AS`S0c0Q=x5pCFD}Dz|4fsUbQ$fKBuXK(rtXe61Jkf$E!>mSg(r3-KL{D*FO) zKyYRb;P*$bd;e_gb)?9?0CutI5+K?LxOrb`fQkue?WK zL>^EySAH4-RSv9GTyT&TfPA6KOnfp_m^l<~Zg=nyDEw6mUf44ClkNSrbbX+K)VF*7 z@Bs=g0hi!Y>Xi#yfPc@at#TtbFm;ZAU#;r3RXap5crboUR39A9fyvDX*>$Zjotjn( zlRImjl@%}>t?OCr0{P=i*)qm@GE)l08GcB5Z?O9nCy!m{nrnUCzX`!1iST2%`c@LJ zeTl;|RQpS}`@;a~zQc6TlMD!ol)WPS# z<>Om;WSj=u#@poNOXa*MTDKjiX!2J2ldhqI8vUgp|?ilI5NBQhyP|1BW4 zfv-=comiP@F<@FH88#AS0erKdde9%=76mf;t~$aFEXZophJuZjq*SrP;1P*)4TYvL z?YHr)hj-&;AgV^k${v*IRE2aijVfsZ0TKAj>4QG-Q5P3FA3oNf@{od{>0a(o-1ca?11-09sc_D{4{Wi6D43-!vZt` zRWNVyV2>#FP<`64anBT&k!3q#yL+WeBMFmMdDvv4hJ=X^$w_p&uF`k-KDUlJ-y^K{ zt=Fw}vjZi2_>d3ywOZQzCVXzk6ZKFoSwsWU-g&4&b30?{`k_4W2~@D@I$d6aNPC|0 z=V@xWyiK5LVi^^UdxV4t>q*B?56q6b@zr3rh=%&WXenkVVSifsej~H7u5m8x7+#~g zlYtvmi6=9nO_m5=bz6n`xB#`P5St}#HzBavK151G>iio-pqqrOUl(6|q7wzkh#IV4 z`&1?mV0!4>irXUM6Jr<30*CEDX?Q02#fs+@s98<%EedpSn}DO|DQ0loNTaC@ zzJ+t}5SA~?^WQs*bz%`wuXoyZRkV9`LRD1|yyUZdyWT7%YSfmN8x1R77W&0w_Ef0J zmTubQERc?r#KJk_9917s>{P_xkFLH#_It8m-V#(xI}WW1oEN}~>aadE@*L`Tf-3T> zTOgW?Kqw7e2l~9p&`Ko&?EnjS^4z3W(DUlcbIJE1(pOO7&k+S%XEeZ$oY}M3?h=px<~tkYPO4SKqc8 zH@ZvPMrrHQ)~4C#-@7uJBwz2|D+qWb{`8vh(y^+vvwvPP8IYg0=_^yZ`!}EW@yzMC*nu*9GcME?H5?XGXz! z?O%3j+HU4~$Sr-e=b}x-8l;){`=Ef(bR1QS(pW<`7Tg-Tl+?EfV6)|}>-9QS@sd8i zpjApAQ6QQI_KO4{5q+$ytS_hvt=1g0Rq^E)rx++QAId9RDI@v<@h@We9m-F=L{OYn z_5PL-jNXB+Ovrb|QCA;qRs8iOKB|5jpp)NnQ*3GH*Si=FVUd@{Iywz=^r+52zQ%E1 z2m2gmCFlkB8a$!X+DO4*{D!anX#GD@|Np15JGkKBDEI$kzoUmA($wk$(8h}qCwQ5n zcs$U0K*L)w1UGBXFg^`Yzes#b()+7COW_QFC+RQ0DBlW}cmT54`W^`J^Gf|Od;>&$ zCy;}7xW#n~fu=kF>kLWpYA9iY_6$ZSEE*QVSl>auC%=g^Fyf(^dVNj zX4($%tb@kZNJ2VC27+S!R{3u=tj^-tq`B9rR~b#t={m;E-2?UWDFkOd-R&dU%uf2# zG4**_Gl7ROf%=@==QZF)wo#J6*A5K$FArhqWvBmH!b}EYeX3lR;aG^<(+<@jV_L9R zM+y_FMLkh$$z1ON_}4Kn+DATDjzgc z^rc0W*lI}9`sH?|&=OsI{QkmkkOTMl<>4WUVmb7$rXOtZ1;Rr>c8}Aq`iFAoY^bJi zDP7D{f8QB2n*sVV$z7P2)d#ZooV+wp^DW)O{%HkK1m9Npo0u%0s>&(k968$VkAiNi zzb%QLi+w49o-E5xb_ebOb=g8m8zY#xEG-HTVeS#tChg7&3OrOlsL>{k9HOvuX?>_) z#o*R!@u=|9TzueHI08WQy~)8er-K-i>1~_d9Mi}YG23^{H%sKV_`7eX$61eW>Q{_Z z*PF?J%EniSfvM^(dgSm{ z9=b?EkSx%N!2`$WAYd2v)B+^f2mqhn0vRGu@YzQg#?0P6;6cO; zwlXZ@V3uCY>6Po!8~5vT_glJ_YrF}IZ%^dkR63>ait}EU!^{}b{fT_Ky|}lSwiWif zeEr;|>6=P#O@d&@x_d#Oqc$?bSl;xVv41v<&ue9^2zl(sJ?O}`s~(gG#0$G52z7n4 zoPlESXSCP~RYR5S%Y6aNA@G53H6)T&1qhM$QRL4Zz=WxW7PxKq{=_W+y@EX;FSkH% z5Fn4GpZ)G#o{mBEc7gf56N!6?Vnep6gxd|DoeU0!eT8Dd3G{QBN~&!@R4`~2<*oN< z=>wNE#02aN55>3>|7j{i1`K`B9otiLOJ!*s`vek37^+-G+QpJR7V-S`WX_MB4QuWN z?x)=~?TH*N!w4qVVN#xW#w~s(--kDrt)^d|DL;gZq^xThJ9U8DW5cD&2i1V8f#u!F zT=XdrOFaK7394_BpKBA-avBl|ifyG=H#R3Yrls_TCe{Tpo)fHWrruR^>ri3*u_--D3E=*#peg1&zDnvNE9XZ~$jsHXmHS-iXTzqc$-r3IdgG^6w} z7ad_J5;kjS-h4XJO6ZC@lLu!E{0#5r&LpqYP@05%^BRrJlbUtCJu(HEbv;^$4u06z zX2nsB)!3Uq;-1!m;K=Ar2Poh(rQA)uNvWpt&Nw`)!K@s4liM^)~o& z5VWtWJsSQyIhsJM6i~Sj6`s%A)=5 zvxj?g`BTgfyl%gyZdQhR9}pEX$D1_)^0^?Oj4}Mt?@j^5rUq3TDbT;@)^8g#Ax3}Q zNjnC?KjD>BFU^GxvOAc)U-r`7YpI1{s^F zG)cgAD*An-QBLC${gJS~>A#>^L^WNAW6@|CNgZ)-P@bE8o$DPOIu#+&txd#gI%u0qFw^xD$=q zCmDa$to4-8+YT(V5407t&r{aI$G32g!EHlU~mj^z-`K+}r2M-)(Dp0>Gosmj4BH@YS6gnaPP>W`{ zjeN2=xj5rKYjQ3uu@`f&%2%`U2C&-@oW940}~{}KcVp+$2L>GTGu$(YoY$CXTvjq}s*rkyxPQmp=+tzxyEGjS9QQw@4c%>$%y_7eytslIvHzMq`TjlAp5Q(H7anzGiiGcBP1(?%Hxo z2iX>v6b8eUW1h2c_?d^?IlBHQMrTOm)Q}K->?iU9l&7L-H|2jp=$7U!=*oV*vFK%Q zXZBo<+CV*SLMOyrm^(F*sl(##s9~}`tM8qdZ+cA+g`ZWY)fqN~y}u#xEvUdf9WNnl z6Hu7*~_R(EFm`2cs=HM zvp*xC(97a<@_-SYAL*IXp!$##QD$j})TxgekFZ!YJ6hg<&#PaiQJAh{q;FhJbd=Qi zA&+a3XuG$mQ2)Ffj+dF!p0}l0=dL#0LDw%<`n|u*ULGE2mS6Vkh0OJYvMz05oMZSX zfrIq{(}H7OqhrKEFzm%}-sNW)|9jFF!WqlFt`f#u%dkD$B(oeH6*Hn?x6cF@Ieldm z)|l>>_tufSD})gJ!sNn>)RCi3VVL1Z;;2bf)^SQPQ$c% zKwb;psc9c~KktQRg$(0;^D21%gV&<`x7OL2#;*g!bF<-M%}s&l>hBTzv*66t~vrY#*wR zN||HMMXoMN%|7y?mhb_izbxzVQYSK2iu8<=7h2F5ytA6_%7LJ~bgD%SaL_S3k!!-+ z-URK|sR?^Cs(!Y$VYc#JPHCLC*HQX+B&Tzc&}KyQV?b97ty}6cVV@jSIu{sLaO_5{ z+&L9bsEpf~+sdfR&O0c5pfA+WY$RvG-ZhACKw#~2e}}NQ_}z-z%;1+$ z%v3|s>?16RT!iX={jS-r-Ub1TJM;}dYU!65Uv%^a} z<|Xt1&3YnyJ*{~H_dR^`tBWnF;Y5+9v7A|VVe9azCO$1m?`*l12I|-v(3_!H1R1}qK=x*kO6o}mVA|gm9HvQ%`a6;0*^x+JheC>fEsf32I z_g2#y#NCI7P3kC`Dc;~x7+T#Yo!VMEH98pC$3HE>wQPu4GW=;?7CzCTK{Qts+QdjL zs9IHnCTeK>1D}@Xga~;dPPa}5SjVO0_B#QAX6Qsty_V$$<&0e5=X$~vW-S)67>M(W zf3)VzOZrMx@qtsg|IhyGp5!P)JA(}ArkztJH4@X^IGBNeINK1~sQqbO?WBO$M%&{- z>~GO~M4unuLcU;(KA}TH^XaaSe+JZzke7T|#jN#Sk}llz=u^K8)`Mu-?H#6r{e$^^ zuNL@B{pB0uld`&mz}EA>EbeGo`95lV(b?9p-b=fPFibFMNZNhkw_UF@z3D(VjjwA5 zer}b^qHQ^QC{BL1`8KPS?yk+gf+6C30Y2$>pusR&=S8mNTEDunk#U zcBk}d1O5^SKfRgAna;`jiq^{aiOrDh%7Sj7Aj#_ycWV3^_$)Mcl4p|IZkUCL(%`PA zFza=}5q)V7+{ZV%_hLYUZD-&Dx=XKuV4)LnqLN_0Hxn>eh!{44OFI9!tNuWMd%)uy zMN1R=OZ7h-zZyalDma85CLoZ*WoXc4a0pEt2B#AS1H0c$Rx~m^zXUT5D6gD9v(&h2 z*tGY#xmJH@Jx zg%m2@zdy5NRsAs1^u!JWm`ClORNCM*VZ<|#WF50r zmtG^p#?MuA$+t9kFN;hcKT6)ZHdoXzLx}^1r@dCb({xK!(M-em#@deR-sXU`_6k0< zZNwcZ?(ihST_WE|jr)#9o7cnbxlz5YJmpAn*-NcUqeZE4(e${VnsUS&X5B`apXzTE zspHm%Tmri8s7$92BTA{(bAN9FcN!F6b{NcVniF&6eus0i#iX5!1@}v;`ydI+K>dJe zpHT!DB_HyTBNr^9J0({NxPxo0_wBH!yjDM;^^9$w18ZNWsmG1$Rtr*uG)lwd<(;Nc z%SDR^*E6Dg-8||TDBf2LuB-X|_GmFd+;pZ&jdFP<>1 zSFJll62Px`2p}18t;6I z8g03A5YV`25bYNb{;k(XTJv7ofjQ@qr$By3GRA}MGe8Af`Tu2#3SVZLW|g>nYTWoq>2MQ5kfQ_DT9gI*(=nSy zW)k8vTw(YlFL^&aplB(Brlyh~B)d-gM|}o*Xv0jpJTH13{^ zdl8-^6HFH^zw?<|!8f?S(oevtXE}rFh0EJ5qBrxH7i4uo31L*GssARdg0x8qG6ZX*+F1v)IY~CvIX;5aFAh1-;M=aT?1+TaYt*1JqP5NrH+19`0d0=@lOXpdfp+Q(8 z*Op1mH-J+(+WBxsSMI<01)|rk&KjdF+TL{;&#y?IqA5wU3%i$+yk8urlyu&&@2BQP zJ9oBW*UOj0ewdgH2^K3zQ*dtk(JbAKY(8yHvtM`IRVyo(s!`&cP=Ec8JmYdBh+kV# z9x5T718p8A48F0kd+;d=b1T94;EZ+WRD=kPEEIc%=bfw_4LtK@+wC<7BF2@KwFc@| zjnQ;w`oJSu=)$^}&gh+SQ&RIAO}3YTb6Fd#=a>cviX-}eBiNV9zbb!9UU2UZF(2F@ zd!g8B_?l(k$~89xJX5#$+reB0t(p61mq)YQI?1pfxU3Bm^ql&*^+jhlOnOsSkoVO2 zulFeyZO6_eff#7={OMMy%rLLYQmVz3pr4F0UsnT>rkJ0REd={12iy5l$zx-as`IeM z@7x9m1fp?HXVP+sw*DzsU#BOWhni-h9;U0OXWCk5A5*o-9lnOcYqC@H7(l+d+<$y^ zE`lHD=s{c9cp<2=%(!_UGQN7OwKvF}v*ef2arBhR(b)ivPdM^OW=#vZ%YiuD5)tMN zg0fYvIg!;rVBVb8#GlZ^eijE^K#*SJCGds#u_suHmC2B1Vmb>%wFcnOqv+(8zMdP> z(5uQm30{>M%Ms1Np&Qcm*Zj9Aq=qZw%^@7~9)7e*aNfv{#Az0q%4_;MK%9H`L~!J1*z@=fqQ6v<4lU0r;i3sj-PnEG zgzP^h@?LDn_{)~*0WcOV{45nb7OU!Iid)}X*pn3VK(1dQbt3u;A3z2kQ-#uTDuyyy z_-E4l#X7f>arLnjwnI)^;+K$_r)|ft1yZbs_+7N!ISuleGv$)(sB%J zL8Ctzd9Th_0Ih*v$XPqZphlX3(<=tcZzD1lVhh2#&CYkUv zPufPM6qxo(1iI)dKlz@q7S?I7;8&W^ti^4e=t?MaLqpwr0PFO|>91>|q~-J~Ne?Q- z9@At>F|-myI`tv#8V4db4^{(qosr1v>ixaHG89$^Jn`a(d$=#e~7na?yys2AJx?%pnfK zt=6XTSWr;ztGi}F_R0%gK1Xq9$DGhqA>>)^@(rFFTRX38Uq0pcs1s@qxAIq@0}rtC zuLbG5@E=GafEWUdE(+K8-*FIQ66686uMm<0lEYcV=#zj*^Zr7=NgXxX@pxI_@>DQ{ z&iohT{pmc-57$8VkENe0{347Tfl=G4&KvCKzso7;Y^6Q& z1}mSv_5B(oI5LQNb*ChX6=eqkD|I-A;+s%n#pZI9YnMfKdSKTmvT#jB@kvf8X(v;X zI@ksR*z=a!1qLQ1&Y7^=Mp?k5qkcqhbb3QAQbA8{2nN}H@?+!9Mt=FB)qnNX-Dvtz z$EA8%e&Fa%zhAIfdV!z=s~x?!K#ZS>qhM^$WsP=i_AbM55o2gb3RTSrF7c9Q(%|Y>a;@0yE?N-b7 z_mqN^WlDS+)cRexyZNptq2g9XK-Q)KIcgwpqvJSslc1m4Wq*#Mhs(2OHwn-r2)IL0 zF|as|6~nWDr>_XC63T(B_I=10u|)!S4PbY{WoXbALovT0BK~K31-W$~!??h;G07d^ z2!Ap5tv3Y?b?Ji#?n2}TYwi~iiX)4yKjuK{x&#J4+y-$KY)V6=&5tvZ6W$0(wUUMT zT2IrmO#_j3(clY62S1L-rAf;J--82(a({+C#FSV(SRP3VK&YJg5Fs*q8*Kf3z#L9a z1-3#fjDYq{oxE{An*^pkH{rQXfdGVmt?e!6HDByWr)z$eRf<11MGxD*Vo>a+#A<;Y zV2vpKtA*eGft0}D^!SGwc3ND7Musx~%Nb|43#!HN&U<>mxd5C5h0Z#M9S=p9QFCx| z%!yd+xE@3yUmHD~2asv0#Cu8d#UM4&Q@E~0SR9xwx_`a(Le)cReIL?Dpr}nY)U;Uo z!r8LQ^s(O$Z|yNzqOiCI$f*Ezh|)9kG`<+`F=9{Qi|rmIKu{w@I0ZvP>pp#YZtI1_ zC&i@|LE$1RFaC|OgxOU5=70k`X2DJD;LN&=7agq4{-+D)K6djsIKi|x^lXiGK@JM4 zSv!WNgU+A!OccSsG4yqhMwIfP=|jK_y!RwJH1Go2q8J_n4F_A_vSVPsXd!Az`hWrf znF*qkBG^-T=HyS)&I;7+m>>w zCK#+zRpl9oZZsL+K*oQlGF{s^gFWe5sKm5&N^3bA%1>UYxnjGvnsKw`7o%MwB}HGE zyWYwVgs5Gaqzw0~xL_p61;`^57JmU*+<~j@gR5s^=~p3Jenk{Ex;P)#ph5!9bI*$>#+CiPx)EQ#%&AmEW;J_ zi{%!{q8pmbKyX-!6TZpM>C0uihWFqmL!TF?7x3o1a`@-?{bu1NX{2|j)>B#-ijfMj z@vaU{E5kk8%HsJJ_rL|jW&$3g^ZJ2}ea#9NlT7uW&1e?(8RqR`0qq+{`&F~5sV3an z1XI9f%oHo{I}m+z&uODP>OJd0ooNe82G6EF)VX4@p3!r$0vl7y&T?<3pTD|l_6aWM zL^;r^D~)iQVeQa7*;pS~2f;9qA$32Hi}pltJTKwioaIJ;2_4N8cc!-qi*#mgKw}<= zYdDMae^{}*AH7xZ;z{vnnk&d+Ytu}8=fz=f-VsX{!5FI+F|KEBfJFYC-;S0wHH~caZMlrvVyeDv8=jg-_hl5> zq`$D=pd$$hbemIJi+z7D7^Nm?vF1X5iGnq4?)*l z-#UJruFNvynRCBmIQLj$wA4t!T5t#Be*d~Cm-wf)+cxmoO>R0rt?sO`x~Z?B&?0td zInMl9w3pRrrfSDf=>j5G;44%iYkT*cwnSC!&<&O9U8Wb2LSDgR(p=!z0xn3a0-aPa z$L6@y6odX%*nob==sw*9vVhp^U!8b|j+1V>*)d(7%1`kro|%thd~AnfU*vr)lsO3e zwCRenydv*+!J`DeyOw7)fpd(|`CCsH;Fx)UKMH3#k=my5l*WuQN_El)O0p0TYx5tE zX#w$;O(+DS5IncyLVD7qbFEBMN5H#@a!c))h877`3s72_)Kw5O`Q?T(;f0KXyXD30 ztm;P9UiR5MPdrTKBw~S8c%pi?N(GV7%7CHcvOLDiE5j9|L?z#%(8aUo#Q7o8|;S=f! z(Rsy~MGX0>)r*#5-e|GW*Ak@L%WEC2*oh@Y43`2whVH!;8Et)`?Hajj|q@tqO6*ENnP_g%ZjA3 z7cLG7w^=0zS6{U;)0wumItP#IZ71Nb(m0AQk@ZMprLO&5Pf-##qn=K{+kUmXQ^3$5 zEiqDdt?QjEFZ8PGgRUN(K}MsUp&U*OZf=R`o{6WjDZ-2tTMDM?(9to6Ir-UoIhx5?ml^zdm-V8>-lUSR{14^P(F7L38MDGaf9Nw@ zGoQczZ!PpsXN=(zK7IQ9#Kd*mTYJ)N0h);d4bQ}(046y_Dxlq z{r=m}mTxB{Fwd#MPFvML*JGyqG2E@M|9`a7LDib#Kaeqn6qrBRpWN)$@d>(Z|M`kN zJlXy0Pn-+?m^1(W#sB$7a2@_1U4)9Qt`lB|7&TZB&inHF9 z`m-^eP4$;@p-^T1`;8{_hkg&R{~G_j{3V?K`fnm2vl{$&`VjelG76!57+{?r7-Xa~ z5XN~V9;UZhgZU)-fVJMyr*M!tob3nxkEh*#prnGJ{55FKQ6wRw*#9E_3uKzUkPV82 zT#)Oz^>dtmt7B280#NUbM>7k@0+$`Ui0@XAbK=0CV6uaToVhD|I3>%?y@g%v=g)Yx zAAS_7)&v;Me>1RByfPo(#^iT?=gkKR{QUJ_s?<;&gT>bd^%^Y264)Nl!sQ-+-;19rkrp4M5s@z_+`bHe#JO+su<^H7AJx$+Mi1 z|2H6po9B6kkb@bi=7Ex+eS~!FLulCP=0RZYp`nwKvlkrce&~L>VfNLYQwyBy*~6pP zVl(mzCeH~@`Wyzefv6FuP5HC0l&do8v%%r_z|y#4S3J*dE5l2;l$%-@xk73%NI9U% zfZWQ&KaF{ZscztkuPa;{_m=dyq?PPRaS@`Cv7&+DIiQn`Ilv_FURnj8WP4cb0)?b# zGL1z*Ged%mQyKVY8&EBsZ15@Oud{0?W<32TIP$8`6iEp<8zq)b<1$=4mS?qMS%6C= z7HvlS;&Es=cQA!E9o6W-VTnCGE$<~cW+B;+QHO>aB~B1>8cQz)wsAC9wfPX3=Yknc zViE0xc3lb(t#F6pdAy3x$uegUqz4&bp^>qW_e7A6@8@+;9^1j5dk&As*4XEXv!~if ze-cD>|DsQg?yq8ygcwf$bpH1bDZAC?h^c~s( z{jfsyU!o8)cA1n;zp4gFInA-W6|Dh?yOunq&>@#RR?+ftRCrvJpWk;-uhO!rAcddq zu+s0T1fS8R&j@D+@CJc_vCE>w7??0T+DsTGFry= zD_(+|-8#yMb`|$?!{f0$TAKgGQNB0OD|`T=22@^q@OqgVegOl?@-~hcLX&I6hjhI?U68CslJPetuAzOxp&7l{d@vEN-ZrTf752Cn*Z=|MkcvwRuQjs_M(1jMmN*6W%o5=ZuZj*Ct$)L>hGuev8Zb z@{n=tGyJt^x!w@RmXwe0yvY}eM@fNw$}N&OZ-!1b(7?%gq}B0(aev}06mZz<`j0*Q zBQ5v27=;?MPjkjhZVfMoiG(I_x-=s!hKH?5rk$lkKD8ppv}lLB(?-@}82_o;10 z>8vxPshfM5c5zB`^A}_FO{u29jaj$oKk5#w=YW}fOw-f_(sR^609@`(RK-*>(~dEx zAGFK`cfY(*x9mB4BUNO9VxVL{i>HjlQ3RqzC_qqe@|nz!?Tx?fxfH5F5>i0EnwX)` z_6vS6OGdJC3AP8}*kFv{-`vX{ez2fQ#sXOk3@KE5Z`deiNqWrdEF#X9{Q+1rz)E;A z{{E``wYW&)l%A6xs5P9r`%OKC_eaX~s-6(0M9E*Q_I5=lpywgIIByXC{!Bh_k=sgR zVj$~-xkzc$B3AGolns!v#nB3s;0kcE^SAZN9RbL`M=-2}!=CV|-W5rB74^vyqOGK=U?|6BijU>Mqa zqXUvI@^XcQNw&-%IHI1)w*{*PH0Y+^fj0NHH|`CH)~8^tz0Liq`d`2u{bl-C2)G+N8rA)S??K#p^(;F90nQ$c06ZfF#HEiv? zDAuD@_H)^Ba`=fM0bw~ep3GX1U(3byvJl> z$@4b?z%DL0Sz?F?u=YXG@``-M$@m0!v=bS#W6-!Jywu}yLvjV<%5nBhOgnm~Hhs8n zgK1rIWm5J8tj%lN(l9;qFzD*;)#>t~sxBj#+J?JX;cz6_DROzwKD%Rehn}Cl(}pO+ zbxF-2f$6&jn6>@s$u$tS8;~HjbQ(0jpGvr|`XMou+yUJnVgM!KuGF0s|Cr={2Je3j zOwtw{jiKL~r^MYFxeWFv{qdQDSJfO0P8eWYeUfPoQhOUpWpqiY?V#fb|D`Lj17?-v zE6WE;`s}lugEZSmMSCpXZ7Bp4pQ)HfV_~;p@cT^$PR!FTG9rTcPfDw9 z+deR#)vO%5PmuwlQC9rs8e5<^gaf=mK)+5xul1{yV~Sg*pwE7AInmh!R@cUQ%Rug2 znwcELoA4*?n#oOT0m?AY+Per0HvqW{s5_&Ubi9evK+FTS%fs7ep4;a0JcvqV{+=l@ z6I)4jeq$u9KN5rf92r{=!p~F{&(jo7DcfDGd|4-_S+#upH}!E@hOZHqCg>Ed9GkpM z-!VK)`3Vev@I=*r4=lhnze`|WpjC=4K+UEPKyIu|4o*G>+IGXTJVU3RO?Oq zU#!2z#jQ1dahlE8DDPY1Ap4kHom(^koDlA)_VCGB*Trt~%mJo1F~bs?@J($fW2SS{ zQIlQ>1hb}x1z|k|Gb9|Wvul;fB&^JDX=k&th}3Jl|3 z_-MGXg`Q&K*xtqiXuCM)oA=Bd54~`_#t8=PqqSgY1oM$BiMw%?RQEPaz7JRu>~-Ic zu|6_v6xfJ}e$B}RTQB&@PwEtqK9;X&CksH}Pfyda9ZTXJWo(H?Brgj-y9h z0vkd{!G~_iJ6StN_nm#;`|VZqW+RreOd0P3AT7<^zR2bjGN zAaU3(Rkup9MI%acV#McM=&5ZaaGL!wdA*;+43_!2!z5X^hjzm%9^Z58!;`<}&Qyqz zBZi-Oi@fb;FYvy|Fmvx@laxq}0bVlv1(m6IfW2?We!r<~Elf$CmmxIl)OA~8O(#WC zSpS@I8~PI9;1I`GRn=9OUWN`Z6umqZEcHRI4yg-V&@Ev`O}2b{E+lC5xctW$5AHes z#HShXw5lGXpqJz9v#cnu^VOeccHA$I#=qy-L0;lzLb+jdGmolO6EH!#Cwok&rsSv2 zYwRVQ{iS^6S#)Qt77v4&#Id&^IAO4`l8gNC_s1890%y3-WQb$&%pRt5@Ir>f(kstv9-z_~K#MxPM*)2WCDSmzsTW8R284bNxRPf(jY&%CQQFN+r0-ma2P zwL#WNWR}O?jPJ2*xn8VAlN9{3+vy|Ku_TY2kO z-bPH{Ms=#{TFMQ}QEp-*EEnvpMN16R`8&~i7xZacK2|mud$o7<6z|->Fs_gd4iH23KtOr&}*R4%alA^7CH1%74I>`FxRt;)YXGP*Nk<`8g}H2T^^dms_R;OO3+?N z)Or~|gNGLwA=<8S?Tz7lm|Cw!DZ2*cdUJd+poGum!d?sw_kTRjm=_f|*U}}~Nq1nA z%J2Q|nGhyFm0&4D%Ds89Oi&^W8#sE>46}i=Fju0~kr?vbTZ%1d$gQctn>^@p8b zYU^56LiXamoU5*O{cmNIJ)ye6{JPw|&?Q9a>Rj0Sz(lv529AuGJ9bgRd=C#+wKFQr zbkz-(^otR0-!9RChjo)5vzzZsB-p27H#w{ogCbF76z*&?`;YIpZ3$qsCz!z+RLrB; zo|ofwD))21fq}lE*WE2v@5-R7-Z_RsgM!&Fy`%P$rseJJsT?e8Re;bwe_LM6FbT}h z7GJQBHSPX$plutG`U$R(@OHJQu=3&WX*p(VSKi6b1uo`Wq_Bvxk+K#yFsnOvc7#76 zF{ZHZt&&m|pxkOC!;&dmU$VkMny31NQ@p}~+v|VRb&yI`9OG5mFH(TuO-L@?$|$0y zp=2SsZU#m%>i_KTkJvMGTmY7|B(beOTtD#v6fpgaYHg8c6T=*~g8F-LIP2 z(I{o#t$x^K9%cS$Oaw`%=O{6>sJ9`@6g5(T`YjrBVeilOZ8^&qaskpHp@m@-AX++u zu3aE4Z2z%zYD@KcPxq^7W|4H+7EkpM11`4;c`+obnUIZa%!dUw6<`&spQm;$5U)k$*Aw&7A9v$b0OdGx#7ctJ^2S z1mnf%Zf?VNAZE?_aXrd-?HB&tW_Qhq|1!BKY=m?$;=X)uXSdD6izP9CHf7*X8aUrB zJI=*0154BMkk$E%3|Wiw7GSz&%Y}2$bj>bsco%CvHwUIokdiEj@=b4ii;}Uu_Z_Z? zYNpwpKgkr8G>&Dgs(8ioJ3(Z^uC&N&cZV|Wx>Yq*>nsDN3grn~T_2J9-xx^dJ-A#gLoAt^5oiUXc(50@$rS6i)H~o^_en0y;YF0cc zSniYES(7}*>4xTzqcwhx6&eyFQI^LoUp6l;%K+o8rY|Q7N6n>7dTXiERo4_z&PXOO z{I(P6ezrA^b(18yZ+?r2a_Nx~Ad5L&#k?M~VSv@)=RS0HR7O>qIfFF(-ukuFecZI2 zd0-9A_qwY=@?Sm38#4CBK`(1-&QKEGqHexmX&!pq<@Upx_9-wv?Y^jV3V_+oS_7fHD_wmeF12#q-IiUo{w#4_?i|Pc>&$oQ~y9GQPQL54)zo% zT+9c&>azP30lf+cGXfg34IHFa)3?U=D?YpS%GkFMuO5WuB?QZM`q67m`#}?e-V{K? zh1jr5NpUMa2pgK_y^LnQ27^C{J8c?I_};n}ALqna;ZGeft($egPc^`ct&O)-F)qRJ z`gDd`7I%^CGXc!{r+6`7FI+{!n ze)gUEqh#3-)#UR1ribu9JPKA{InAWWBSK!-J?Drub@sDCtDDC@Y?>A62QYb z&2~2y1Y2lN*=_j6MBj|v)S?l5(de`}`3jTI+AkR8dZXxVw`!3tlc^|8%EyR=geq zQF;HE`EGa87Ki2j=7k1k1t{*@-~mJk2}lp8kD1X6{#q{B5U#nxO`Wu90%cc>5A=9? zW&*)RP>;?vCfLDh9`-9H+w{a>LrkT$p+@t1P5@cG>%KF;kxo@S|4YT_65 zxF%FCEhR#eE(x-+y4jrtvDYnp$?Asq$`=7?p(Y!u->=vG1leZ3C!2U)Rp55ZhJ2Q* zX__eacM+D020hv5$cqNowrgw}*A?t$)g*`xGtxe@^1E?qS<}pp1xrgu%ER9$ZL&=e zU(#$dC;P$v7kBR&)l}DZjiTZ$2!eo!h!iOz(iEh3kdC1A8dRF}8hTX(l@0b<;2%IP(e0~NYO3o?XZymd7Mc*B>x+Vi6sv`7pdVYo2VP$VUC0y+8cxK3$ zv!v5>==G-ng9)1^Z;es`Ey#EUpjTum4P1AhSATuls=(zn{oLlG-?faXRN_j_+|M+6 zo8m@YCEg8T@FQeb7Uoj_o;S@q;$$~OuhO-OGPBp7_|QRmM5zu>{Jg;4*t?)PR>~rRVMiUmwYC4s+42SKvE;ke4J7^Go4}^fIo;Zz@mh{zTUiW% zC&o3S-x2phb+9<`zV0{vH(r)J6eI%tWXKvg}$;z81q3)^CdG4704pnvkbh!obbf;Cqk5Hc4 zz$Z8%!Ek*1s(Dh$x~sA9x9i$Y7KYf5QDm|f`H`w}K&WOs^BuKDIQQ1(4MXQyD)C0i z+ZJ7yQfdA%QaB7|qs^-Nkv^VtWr`t0^twb!$Zh*$=JF8gri8f>Q+-pF`a3-n>R*w% zH+?U?><{hn=t&QQn@IH)ITle|Yl9OHM_rLm_W6+bNgCU&ev2Nvr?=^WXf4q*w=c!B zS;BF;NkD)QFyPMp6PRCx3yq zafPY~Ro0f4DDYx#DUnzR zQk%>6&h>k=1bm#JP7ieO0MZFd_DyTG%g1y@5tJ{ACViJo*H68 z@77xxT@m_QKxdk%_OoirR`m7v9k)GeIB_RKtz0Au-W8w7lP5cEYt28Z z1RsS@(nN9)HA${t@DkO`j8Rxj&;KYVc?!y8f$&sQ&{5@XYvGdWY2pYd!+ z&nOJ+lo~|3G&!+KIqkta$nx!|waWs4!r&-SBV@aw+{i|9#kl-1I~nYx4ZEe=B=YA* zZ1XBjqH?oDq;m+eMIVMtkqyoy&IAU`o4;-f#YdUt0|cVZaeT@j%@#kfrWTadHQRk6 z*Alv0wU4onbp4n(qH)&S@`(pv?kai&lMn69Y4v(u!7QWVNi})b6fSAN>3Y97!f_pY zdrr1+y<~7Qqwuj#J>26j39jLh+#APo%6x{~X=wr4EBwFgFz_qK=_#j@6$b0EI|)A| z(nu*dhR-{I0f9G}h`IzP_kOv7CNeTL9OR^jL$b%I_vM{fW8+t;KlW(sxGc_uJYgld z@>@Yov`4(w2{^9D?Q#s$FtS|9u?oirHNG6Mp4lw}5=uoH#(@=1Ej1d;sTWWhaUVa{wu;~Hu5Mj0a{8re4X2%3j^sIX|GJV~*%GJ7==C6iNVHhB-DU82|(!5t6 zVTCuho3lx$?I zI|aOYdm_*)!2I{FL9wEcb%sQ#BL(|KInnFpmC>cCvVT4N0F4`#eEY9vmz*OlOE`B& zRCFPHAi399x^|zhgApt2p(i_+Fj21VyKNEwtlo_MlG94u>IXc1it@(A*=7;&4~z*iig2No4DA)q^f`XWcEcu5l==h99TjrYpFMPt{5ADi z1Aup)7^S2e=K*1+$B<&vUH3BwJM{qzVIlE*Ml>MfP3fPxAap`+LvXSoSZf0P#r&Td zuHe2|X2H;L%h}%thLjA82>vF=+@07%5So7Ffs$KJr*-dAtf!Zo$S$+q^_;U&uxHZ! z{C+dRY&^3;z}@JLb7MtY>C4j4Ch9z|dvr6K{^{O6o#(~V_@D>RS`_46_xj8|sXr1x zql!T3>(0dUvaf*L_D37*0yb<$KE*)F3&|Wa#N3*GX$>kxtdyQt(1G;&&~xBfvW&Z9 z&fL`SE6c-ImXPZiipf~=C6xb50`AG6U9oTgAm4pDQ?f}+ojE+WUmuzA;cc_TuC1NH zXxUr5zBoll&$!83M~0hx%VNWf)NBk?^in53GnL;5A_}egyRoU)391SfB_ZB-Nv;es z-3GH0FG2clRsW(`$@55xlDFyQNvS4*fc#7@zhKZW64?Fa_d6NyC)jue9jlcsP^tk~ zTYqn6sQZu=CPiU?O07{7GmCH)39s1k%=reXd*fEAy%*F07;QJSjpW}r@70`xVtHUf z02Fee#T%kC>=gm!xM%p11Q;M&8-hfn5(lLb#n08{r-0oi)bmnb`a0Pg7orWti;C`( zN5Q>#&NcntkC`TmP2^H8wXY<3*&drgxjSv2dJv06{Z;lcg8td#=wSh#9u0rB6ft51 zYYAZg1w$UIHh4Ggf18ETrdIb32B{-Ujw1;E2rOeDZ}D0vCE)#$L}PkemF`^iriZ6~ zm=i}B@efa_2yJY8coa$@s0CY|M>Gv#HB$>z|Bf2}bC0xf*8&(OzrREwLjx*1froUw z00uc-HSU^p1U$J(;Z($hAuM-f{p|0b=>nov-(qNTQrR`QDqrctLn{@5ljzY>mZ0zU z=P2%r0wUhe9|82(C_?tBih zHPbRuJLUA%M+986;nHF3SuT)LgLR;oAv1tGXcM#X@)QZC`a^gkY|PVA#?sNT(P~RP ze7BKNdcYzKlpl1kRQ=qj+KpP|RcRZ#N<2>_{^qZ10ni!P+&)XGKOYkMmwqZ04qgsH z*+c&sftyaIDS!))P8kv3W!+rvd5O{#%z(!W{rXG5xtvRf9V`7aNSOHEfSr7q$?P8> zEwYvEbXF41Edkit|8k1P`lZD7DSYzWA9avq9uK|6A>-*mk#|3$x*Wx4_4~{cx zn=6RABEZX4zI!1@XFCzB(up8R2cruTh(Kyu=UW55EOt5pn?o1g?~o|4UHEN#EguA9 z7QGHtA@4?fs9a^tDFovdpa}Ns&gBn92)dMNJo)jvMs1vHNg_Z!70?%f^Y;bF$JRLZWK?*4AR5xe1N&iRQ%?E^~Dk zF=gKI3g->ObjCKrU#QxdtdKcd3Z#c5LBiTZE@X1hsZ(PSResAh(hF3qOq}eZwaaEV zK~_pZEr*$>Sg_l_Zrp2taqdK%RukDao}TzJDE%Jpb>iHta-}zDdhmmOj2nX1*pGG(V9o5sVirJ3_&GvAo+%STvF@b&RH?*h;1A1F& z{ozKZ{m7>v(0L4c#>U1Ig8LO9Gw=Qban^h&or%DvsFEHMl)?!jG1|}nr)?yAQm7!1 z2emF?#-Rs-)_l&kB=Q-{`9y1yH!sf|{!yyAEB_jZ&!+TJob6ni4YJ)PU?F;gmhDT; z=qlkQ90Jfb@8vvcSVxhg5sD`n)SD1b&7<#_ZzzKz6&Y9NzmA7L#T86in{C}?2H~CT zEbxtwRBJ!)Dz2TU!XK<7+T96QWLh+V@c1_gIgm;)TxT~7+{=EuHmjJq3i0o1I02ep zK$BGlQDGv5GyY@5ygM82d~2ECcH_ltWqfF9A+H|gx`^LT`?U3C*;Y%^*uGbj~ui`Bm)0`Kxs{w8rg3OSu<7J0$r>k`NCJzKV@n@Jcp-1QI zOzVFduB9jNQ2!6n&h#k?7iH6{&qhDJf}Qo#%YTPF$0|$ zNX$gh?_2*>8}|av0L3PO^X=U{(+$)@_BV?O&U;ce0t?MRnhn4t)!2K7{%6Ho{u^Th z)zPMYK$}bvdkWTW-9@spaVhTn9S=XIjb*Lq#m@5naVabeeHNFi+i))a`M3SM^Hgh4 zCE<^AES+P|L}pX^>tI~m>*Q3I_x$O^8psW?NdMocB_vBX zFv;G{AF8FO{#MPtraW{}m)`-^p(1v&H%K7q<26ZJt|Jx<-~M@^c~`GGxJ$LE%_aY< zUK23LKKMCIJyTT~-bh_N**5n2Liwk6fv=Me_&n#AlrB#$19^vf4#`jDF&-2PLWdhd z`a2YD>GBY&RnfFgu_ln!d>|sxW|$yGouA75?Q*q1s@PQI_LH!A%>}*-Yrt;FgWpqA zM1SIJ8_DcT5#RQ1UcTLLewXoOhk7&?rXCg+S?7N*JKg-4zF|9>^zK$7gQ*h`j>}(& z9f<6WPrgb$e|V5Gi8mkb62dHSuXxgMPskQ6*Btcf*tF9Cmm#fFYm?=*HbuYy(OZnq#AGC< zWxmn%!9X!uhdtm}dFk`?D9T={>FV^f-ex+->1YdMG*FN4h%;s!w9P1y$-K}a6856_6+~lQ5*RkC2diN zWKhNiZ-6XG;mfne6`RvlB&5t^d%F|@TY=)xc4zb?^PYkcVu(r;j&uosnL^hgL2}^S4Mb#hpv5k5m zX3ALHyuMfMujH3sL?&nXz%!`d-eajO(55r`Rl0)o3=A$q{`9?88dLgSqY+Xp& zzWd>VajZq0z2}Q^$r|?{z0SaHEPfJ5_BW@Eo5;|33}i}U9#)MHNvr9f$<=+c#|*Fh zSFVEcS}oC!G9XSQ#5h}887-rnYh_s6ry}D%r}_Y!R;+hOYHncEk#1cwlrH8{vePMj ztexn7(p+@vJYC{8@FfqFhSd1SEUgLXH7@bPY{vZ8zjrh3@xzwsCLjPGEZXNoG`llT zW`D6i4cdCx>WL0iA^9vNuzye5;vUZVtqAcuHe9-uUl5QlE^=BxL-}Fr6?6<8pcLWI z8QPQHv=>-n5*XM1fW_-~bK(B!wurdZJ|n$=r-0M(`7TZ3vY#lt?j)*1uPr$h)MkKM zQ2%AjMRV>WFT{8zKiA~uos*@=^Yh3bx@C1h#HO%>%7#JC2^fE^m6OCf(&D$DCr$=c z1MTrQ_>VFgNcc0&h1Ekz>zIrZ0hmz`Gav?qs`0NEt^sS=69F3YcBw54vS^Aj>DIs` zJu+mKc@>ZO;dA_kNX#6Ro0kuhmGmg*F4GmKjpW^4ezN)5N%Ff{^KZ&QEAw6crlB42 zg5zao-Ls@RD8JbRz?1g|CJ?p zDA;rfh+0l5RJ)Bqo}`Z1EnA`Dto=Ittm|FAT)-&3Ah%?+!r`*}KoVD1@j=Ljezl_y zBhKD`fnL)uGI2!ML{QMQv+puigPF#4ye9J9WN=27NGP$Xcj|evVq7S9%SPCGPx_un z@p53`7mjCIe|lZ!A7@M5DPOh(w2L+f4q~%V0iP&;d=S0~gn{ z$)IP#i{Od0TgkT8pI_--11p5~i5HN1FMI29wKSWnUZcLPt80;otS~a@p{T-2c?g1MzBJ zh)4z64iEdySsh3OBTQ?tmgI8YqT0Vr+XuND`r*X$@)xa*Fp_sj5q(JAdY~u%f-$-` z&Fd8&KmW#s9_-TU$C%_qiK>+VCa(u{pCcdgF|m`B`_F66xZk^wM(nEnO-#SCxuV1| zgQqA7?Hrk9;1)odf^;RS&V0g5>5Vbqxe-rAzJ zB6XwdQ4jJ9vRK&sd>0n^l(p+tR}{I^A+nIzo1I{Gzkt0)w_h6;nT4{~?=LQC+d8bW z;uMkU#918EbK^KO9gRk0h9l3#$m(vrY)D-ojm0RovrL^V%M!_n2KTF7luk)^AkNU+ zOmcaY;L`W`8e&`ALa9DA*!Ybo>HJ~BcJ{7Np;W1LeEM0IisrPgAV+)!1T1oTvK6-*dri4J5K+nX}A1Lo_vYFjI zUnVR4fVRz*AeqPg>Ysz^gqUibMi5$Youb`5yN1%`?S0n~I|sKz>pXj(D0Jb*2fmi` zW~zfXQ!Ue-QLa!x-CcXqNqJCTq+%(TZf z#QyMGINbf*Ht_`fm;$}SvTWSWF@6Sp(6(9gxFJO+#bdAU>U=cY_OY+uOiO)IdU9q( zrFDJUa_ebH?BrDC3?Nh2024|oC%>86I|D$9;8_RdgV!mvPWL+amshd}qT4r?MdFon z1Xec~Lv`*k%1WxPdKgiP1HXaj#ez$VMI0;%!NoOJ(NWMmtyH^`fONEJ-@OLoqk{x$HqE|IZ=il=j-u)Pv zGJj!dgJ4PgeEw^xs;ZX-qXS9Zhtd`Ao>V4+1I$Noc#5Rd-N<; zh4uF4!%k}WeJS!E)@P&G1TMzI@aCle)!YI*Kg;=*UPwl)r zvN#qJ0^=R*WNipFutZboCAm_dehE-FYDyOxARf^&dqIpH5i=aY>zqFmj6=<|Vf961Y) z@4ftWVpG|ttZQQ|zS&{7XnuRLr`?Kb=T+KN)sS~9Q;+;|D>*c_o_*<-!Vla>mHqNo zu@Uxd#&2||R+AH4P7s#gAAbV=Ky zm6ELjyo|5jHN&R<`h(^(+C&NKuzx+fEo)2qiOjNNo~B}h%Rb$Hd}wKQL3YL2Srntf#R1`|V|k9ywH-Z)eFM;e{E(Y)Qvddd>h(cfEyTp~_GA^RKS+5fb%eF4JGscCk70g=jfCANlFQsEJ?X~$Vt+lICFVAc1 zJaR`*tVGrxNL>%hzYe;()Z*cBM^OUjp}`_Y!%4=3T}*Z1Q@r`n7eMD-9H_@BFt46Rs5GZ;DPH5xhTSVV#-28HBQnWXk7a3ik?5X_jth zL4INNZ)J%K#7L3QiM@>;r%m&SBB|@_=8mjaxwK;M(~(xht<(QJ8wyewryoI=_E(c% z$CYQ^9;cWomZLphL-#XeCxfpK9!-v%({7C$E}yZAWF?f36Xo!OM%pek;gf17soL;l ze62fxw~v9XFFO~zI~mzeI|aVZcFpwfE31E~Y*4|A@QwG~NzV70v80E;bp)v9pkPiq zUx>H$szbq0qM}I^-`tZWGtc4YLC*|iu{Y8W7{|_)%Zn~VfVzd%*(_cC?Fc4OI3hP! zhKOiegmCFBu7&QgebTtnyXL+&&9Jq8=$c3mx8B&xy-Vp)i8bv3yEW(jyKEiLBr}E- zT9v<|l84+U4#AyQblsT>-~2r9U3`w&C|ZrmkMgldztLO&%nHkpmptbcRUAZj^K+N~ zZj`;Hw8IivOx}D$qaLb1%9raFU#&i((0DdT4t>c(tACJG33GNmyQTrlV=C0NEj!@{ zZyHZUN)>}P3pNK8YQdCdo}2g0QXXLMJol11sDONQIykwcbf2%q$6Y<#*Gs+TujT8U z4E2QSXM?@s2;Ck(?gRKe(ib0>XYc84QydwOV1k~9Z;4l7UVT{e8(!YgagQHn%^(2!+x_IRt}-?YsF6t;i-XSuh&G0CctckZvX& z8uE9Biw*m)>FaSeM{V2w;5)(QGH$|opaZUv4+@=3RQph_s1?dtXpPend1G7Q`Nce_ z&O~=-vtr*}#`6kA!O{02ioU9aW>;=UHFP96f_@F1`L!_mr(&_Fi5*$*9P~8e#KHXS z$>K<6K~Y;@dqAPu_<8&!+vumAMY|V1a!B{TBE??PW%@DYQ(0S4<#n}EMEi;M zSV$RnZvQQ`mI2XR$!|YyUC_6|m}=`bzvV91sJ8=O3_(9q;=k;3#;C7o6QH~pEiGqd zKptgSclcI9SGf-|c6x}W`H~9z&#Yr9v&`EaKCI2?)qu^x7%lSCUBsDTWBFmO+0L=dGan0^g7pj8u<;h} zQ&>Pdj%@GSrR^#qlVWJ@Xq!UjD6MZR-qCqgt?;17X;jabgU2(ptB}4Rr50;A)Q3mYTmoe|5)3V`bT{vC9{+yNQ2qQO{W?MU?ZP)rBQKG+NOn&}5N9 zs*KwsmJ-2X=;%Ek!gMw$HFltT3v!NBELuDZTI29yzt1JPX#cY18BgW;ZFAoVo%>Au z5{tnRtUv*Y&A)}dA-^s~!?{81B|74<%4XU;(!4yZ2iaY>It$Sx2* z$TxTTM-fcvn;*9RfpE{$#VPrl&q4LD$*EHCJlMt8bf}r4n%$=Z7it0m7QIHL4%21F zY>7Ypa(BAgc)z7+5uVsCdEE6PXy$({7OMPW5jC5w_=DHecN))vwkx|IJUR~}VNxI7 zXu)-S>+cwby2enE@{r~Ax}F8H{DHD|Jn@5jm^F~(oXqY; z8vpc*3hx{cDuKylk(Ghym?{jL;X%xM(V9drn3|Gf?x%20uEz-3v!um1%)}O>2 z@uIMs!Aou8%8vGO^p{uur5>{b2XK`q{lT4s1y%`l*R%ZR7m8jV%4@y+5UQ7J-q(3aaqdEn57JLKvr@y zsU1nl;Z5ca4!F)4<2oX10{+X99#63&E-F1sbT_f^*lnwyb=;@iiL5 zUeBMoSrb5SYQ9%>1>+fqX4}egs!jBdX<}yg?Y%@4yGecin33otmN=Ud{g~JK;e$UI zfseu?7k9Kg$1vUOs8*(uyaXIVqQ>N|i+P;I0jI&!kA5Xeg0>ndLuZ7!{Zl_KW#_KH zLf9tKU>Lh+){=KsHWPKv;Tq+li5K_Tna;h^I1E6836&ein^D%pqNA1q9MC1d~w(!-UIIEdxTmuQ<89yAk|NJ zWQ-rfQWkbgDMxzlXQiI)SWccmF;4^a1H(-s$}@8Q!3wrn+TO*lHy_?AMW65g);yR$ z6kpiM$@MMz;91fw-gA=a-ZNE}$`hUuq4(OOX=Q`Zo3+EMVSO_5{_q=_kphXCAtH)4 zJS3+Kfrl*aWw57hxx7A`1=|tNIQEm0M#r$}&eip$$771^8-ys}AP6pXs}`j)NX5$@ zt$gtzra+N2=gX}3l=rEESMNi-c~bhD2lQ}5QS~Y1j(eCSGb*OAt}QaDfi|!7$pgtn zF)yjSjf+I2uRjhzovQBd6`;CCi6C8RBZmP~hpQ4HK?x%6Ux_uSA6qTbuKH;V-!z^Q z4zF#VwoB%FSQ}0p<~eh%GzSXm7sxk)Y%}>WcQI_ZtkT`5$9CJP+D{&mh?vWCiF>A^ z!Q!m*yFS zNUb_Jm1nd2b{o9cRg!IcefhCs16eRomW4V|+eX z*V3g(MDRH33B-6ua!1lZrQodd@@yUm%R2A$(r3tj7QEx4ycC6x>49ff-*fL@_h7kD zS-t4V`f?SWyVOk(sLj!-pVI`=cH*F;^X}E z+PKpu(_3>trJd_z$w-=d12B)zzY{BK;(pr7)Qbh?Kq~`&7D$%2(=kWls)m%dyAj1^ zZn+RQYxFtwZR5J+J3%$g&Ei=NbMRZ=MNdz&ony?F8-Dnm8GfuZpXnXrld~NXLn?>% zR|avsi0)Wz=&t=BQU?o=_8`^YDA`J=lm>D1^4i&$tzW%QIhAHdcNTNzEyD}W%=SH= ziM2cWPD^#kWjva6*$4Xw4`cIU@AH7T)qmE_ZoYz}FUpF)>ffGiOPePejOhRJNX1~* zJ7r;#l3gL%i!>dvVzLw`{t@`^Tz=L0r+SK~U?ibRTE0gK-ZblsMjb7Wxh zwj`}`6R63ZO%|N+v)AX}`)Mt}Heq(;{p31dRtWJmC))IY(y}-5GR*wIk+*$9`F#&w z-NU0k_N!9s=vW0gHrbP%3t($UhN5>k8rKfm^)y^z%}^ptvZmLOWqyFfokJGg3H(jIeo05 zi-fPrbEO(JIxn6mruSs__X7un5_H6GBtJXqmkIbJEO!J#G39FIWGYm%5u`BrcfuC@ z#gIMy*btcdMFp2AHMe7or1vQt-VT_*jJ)Lq>mpH0!A(i~_LIb9)b~SQKafi~`~7yj z)Y<#083U4MEU|Dq#|O6CerscewIJ?A57)k%`?T)4TiK%%r2WKHrE6lDhQL5WLS9|+ zYWJU9c+JQmSuI>E;|&d)vTV;GR^ayp*Zmvs^3Aijo#p9X zhXt^IFDXu4rv2?P|GraVN!LuQ%1ikA({ta}g9;WjXF29I8*WkRsnSiPlxGy813u1( zfm*F?o*qe+9oRfiInIdakFVv9di}15ODCC~?Im#rdp!h8wiri&Cu~yr z*;P`GROFeAmRzmQ>&frCOlA#iA*w$+yW%=9-BQ_bkF?rm{f$g`Ik%4I3)KFn=##gw z%KIdmRF<4LSw4;L@c~PRtTEHsTBCZgp+BG6XAY{*aAqr|Pi6bfV82bSvWCplKo_Hs zWRJ8JwgQvuv)6vhy;)Cnl-+FCe__!YPNdYR2~}S?D=8ulP|#5XkUs3SL;CU zSH!hQ6y27}C^`zS)@VM?ifZrtV<^w|iy2}2<&l8}2=lHT!dDURH(S}T~$=XPFaYuhMI5{%PPNfUgGH*Je{EUiP7760jEl+rWEtDRw9 z>1H6UPlHq))7W6T8CUIyY&6*#W*F7u+#{4FlJ4-wuC)7Agl2k*Da2emWjN0GB=zD` znTBJc^FR2f`GRYsRMW}xs0N!u4gjU80$6gmf9>FkAfbOmXbT=T`8fjsAzY{}U^rlNcXdQ~pReDJsO?lRxe9kK2{GB)!p=% zJBG7;xzcp%XI)?Cmo?b~tglRCXv$O~>c|nb7gy$+6q%8{albsEA-HoDYJPP5bLqzx zx27D_c>`o&VkHR=KTOFqV_Dtrnca}vb`)6lmVz_u=vwpa^}2wQG@Yh5Ltk~|Va>1Qb6Gu8Z1tMgo_mq^CN^p#QDpN*$MSuVa${-JY;K*|BcqU@bpB^9 zcJ?#1?r+QDIl1d(4f2wn&QAR>f!03BNWFXsJCRO0m!VU<55l8fTc%CJ4sHFwxH63y zTgpujSA}XUY5qcmqw+u>BR^d;2*?}OyfAx3{w>lw*F~-;m-8D}b{z$ZlGSLPk3>jBkzHBOnZdS_weJo^Tv-THjwUGb zsQg3f05X5PTcsK(vA4J{#0!KF;G0>){m(vyW!G8dvL5{w{O;%$_S0D;{XYE=Z?jHGsCdjuEMFL5OXwVI+46#vH^ z*0RrKG#~LEfM~e@gw*?RIe}rL&E#_RiHIX6^BRR2-2TlDS^weB0zx@Ke`uG$inI~{ zJgNE2z8Z6*$;ljYolp%!N5*HB%xiveB(}NJ^(S7wUF>WO9H$#k1zKhFRQ--BxdSa6 zl4l1I$bjPg_cvEVkm05)L?p`=T@8BT9op=x#CI84ZjAx;jbUJ*99)e}T})gkQ_t?@G1HIYyDrBmxlOb2Jxhav};5Jlf0m7_D0N^OlP-|opQX9$FFnn|yre)kK z5k(O*rU?l74w$AtA7-_oq0QCGd<{n(54ia&qrUfc@i3C-EH;g}$D6Qzf#9mjG>#Lj zG2MSgS>c3e;zE`Mm%pXgw&7Lg3;h*0RFy*2IY}hw9r@`jg~}kWOg}B|!<-F|$vpM~ z?hz5S3#dMk(>$Cd;>D~tz4z@K=)Ra`B#?GNsiBT55)J-P%FE&kejQmvrY`FEuu-$^z{!jydIe_M3p<}`n59JXoPT)q4Z&Hnai(IB2eA7=y=R-T3m&wi zfiB81@7x)oI1j7tO#ia7CU@BTZ>76^KbrgZbl6-S^)x$%7hzYs8Q0DX?PQuv4DzO_ z5}=D_`mQo&Dc|5CHOy04gtf%`2bxhp=uLnzaf58`A=Us_$*pR>`FC>g7oa41KltaN zvnb5wp?euipqVnKbkkAS5H6KtQ6sP^E2|f6RM-O3TCsD{qvCjnZJWc z&eZliEJok8QJci9lC#2DWD=pQc&=GkB zCa_3;C!2fAEnI6fk!$K5r)GAfdq+C;k;th~oQ7kg@M?EZT87F0o?e4V*rGp@JE5Vk z&lr1t?2g_d9T^-g;~sI%?)IQX$Ko%q#S1E}a9|IS)hpc|i)q`GwZ3Xa4j_jX?2#m4 z4WoLEQoNQ$p;XIRTeo!>@uGg*Yf3sm*&uJQwzjSYjO+?!<G18r z;njNiT~TI2yMAC&*VMV(>Gz>2-+OUi`Ud9WheNoDhn3sa7c_~2E3eHC;F}uCb4eBa z5^c(J*l`3%TXYffZ6xkHbYX=bhfU#@#ykAZ%q+Ayop&agH%dklS6AkL!9G5Hvkj6U zUk2Te0S;ZJVWX+ll>UXTuyO-r?uL!J6lKN}Rh8nD$oQr_m81XZBZQ#G>bTh$XyWJL zV=U&uqig(9Iot^j_8qn3Cgw=Jf!OaQRW+*om%GGo06z=(A4tn5F_=J&gJ~}JerSex zlI0Xp<8OE8(L_H@nGu);yo^<-+=S{#M4*Y6u-uGF%{Z=_J>1hagPMC5Hrn#QiUZ6+ z1m{={M+N{xqWEyFo(n&0m`olk@R~>pWYuM)$fcoCe>%yM_z* zu(~Z$!oCT6_huX9cTSj`GyGrXmuUZ`G)jb5ME2K!Lio}M;Bb-r z#xm$J;`BXaO{~-eJ(yVdqWxWlQcM!Rza*=F;`4dXx8fwFpgcm&Y*`-l)6aEuhm6oe z09dnE3~W~$&wjZm<;xW>$xPqkWN_qzHGA+!>ic?;vfeo}ylCqYwD$2@_n%sw&^rs7 zTg4x`86O!LNEIKa+d!?ZZuZ#kYx{p#|F0lmPLR4jDfv%PPd~jCaUmM+okq3Z&enoy z6L~5aIPTOXQ~Rs0)k{|~<3`Y8L>qL>i?C{%U13FTpqu@xZ{N0R6ums($IA$Fv$3#p z+-AMVVB5fl62Iwl>Q|OhQU-sWRv}}_?pI>puLJ$tXbAu(et7ZgM@({I+TA!hHnoS7 z+otPttz0+yWL}mnKX0Y})(unf{`4_TNrBCgJL`G~t)B41G zKo-I0-YMI;0vPE>S8`MgI_cT~ru&mfpmi^q%%4X+bka-S zk&TOw8Rcd}N1$U>Z*Xpn5P^gCze9!KL@9kwZtYzra~^)bEg_O>0RUWy*Z2LRr^P4%&-GIVbDXoPcr1p80mJ^sU> zG9914?fT|-1KQxy&GHDJge}s`vYx|C@Xa0jOM2_-PcWIVt|N#9sr&;(9jmn=PgX+c zFIuEjX*V5@(0H!I{Bte$FR6yDck|=6m44jx#=E_geJ>?>SY*3F6N0Ald0wEmhYA7% zHD0#(;BE3jysDCKa^MCZTj(dp7qnAo0QLWJm8sK5bQNqvs3ntLF~{^d^CJ`eqWGo2 z4BXUgh^8!=uO{xMPU}Xdwd(jd$6-HvTRylV7P$ULG~ufWQ`>Eb3A4fMl~Ts5mFh9W zde3@r{I~W@P2TaHerH~2J%WdH^fC(Rp%W(To2}d}4JeGXe45Fn=q8gYpDs%Cvu)43 z_UEePmc?Qh`+UKW->?3kS@vKNf!otuqne?iKSWNa&Sj$7d8tM z+LrMj58;qg*CBEtw-<2`H~#8t>oVt4c?xUMGX4e0-x7$7`BYXYL}C&n0V-LzHU&?{ zs1*vfr_zyK2&N%rj-UK!V0<5>LzIwgN9@F0jlV@eOml+HIHbz17{?AW3VJM-{3m%v zNZDt+(Iu^5C$6%aY`SN?eXm99*FliGe+IQDbaYd24dkcZAEJlb8x}gVzI(3jFb$}> zR2R}$8mYbj3`D_$ct3&626$8>YJ=V}w9cS1z%JReF!_~wJ6`LbhOa->qIbTSo8=^@ z9gJ0A*vAoMOzJkOv`uZ7NS~y)J}YOJEIm6LD?^7z4o#p>-acY&l1Q5kN~`sG?@%1w z{=zWBOnQPOvXlUoeomM<$w1PSm%r|i^@>hLOeA-SBd(n8Gv-$I2D-N(mw$zPG$fKe zF{v86LwvA3$O(Oy@jWPYve4?Rk^!2?bc-Ggmc8yq9CS=dfOQ&FyyMZug$&V~0%3^6(;C$Zza_RulE zKRz}3O6Hs*mQS1ktg%n+tBx5*LTS0Yc{py~7MAp?qayOkr+L#vIf@Sq$;aM3hOoIr z?MUBNlnxj{N8`2P{`+TrIzL6+SCq;IFJ+e8B51RLSs1TQK0DM2c@MZ zsz0pL*6nxPAkZOac)2lrxxGN2pG~)v{dze9D``P&&f4;!BqEe=M``@3t$|YjIep4x z?J^tuPjod)ZJ6~gZVKBj!yLQeZh5Q~*%7IXP;UKxVkPr9X%QPfj@nq56aq^Xl{BiZ z!u4*OI^`;da|wpy4a&U=^09ogV(Zqx2<9DmyZDvBvds$ni|U(ik(TS{mfvN}Md)(( z7c1=PB$H+})+%nW-nE;dLDI9~;jtT3zRW8Hv!z>5{u}Rmgezsr4K1at0xT{gcf~y! z$a{o8q3L{OYM2-x5MT*!*MzS3?v4Hehh622;fSICec-LykJxu{O{_pH1r0QnIjf*- z<}s-y5$zz9rmI%fx?8P!Wst^_$u1?xw=?*no_-pgFkNlz&@l8`>DtK5wY3H$7WRc% zk|`zOWY=A}Fz#(c8pmUz5o!Z@jbh6M(eB{0KjY3*9jCXGhP0b4cS`HCTSJe zjIXHI-{t+q(G(Xfzw{?@kaMQfy_Z3Td;886uNrIN3>09BLs2lND3YfJ0{q_i(LLRM zpmm7#Q}~`AdcBl&O*Z%zIceQPAT}Hy_y@nxuZxaqOE~#x42_0hKDK{ohsP z?*66?pTA~XXWF68LLLRdlE3Q*I?t~f6f{)`wg#5pK~uk}b1+TZR#Y7FkV*zQd+7K> zhz=CzyK$CR4#H}dJC4JCTH}Z!wX~T=!pKjm`0l5kmGo>*ZXadA7X~y~U18JOi?p3wOMG##T zCt=MW+T~Cjg8E>5t+jnk*(YD`l?0f))5Sz( zvhwAc4w62OGlt`XA;4~g!2ElkPY8Es>vi_ywEH&3Ch$m&;HE?53u^4aS8**^g#QAZytQtzerBS)FBVFlZebW$Yo@_M8r(ZK z`pUG`A%$O*3Um&M==-!_ei}^lI_}715Po1{ap6teen_9r1;6KsNKl zy$bOdthK2sbNCWNjDIQIYI#3BCH=1y>$L)}EP-JvYfs*0?OlH=HO!ZLFLiu`g=olN>Zn=V4`sMqyuiFRY>8UH)Ck zOURR`S1gi0~hxW@@c3{|p}rLL!Zz;vdUbCuA2 ziNGSya_Onmy{5(N$gAbz(#g#6KE$zILF8gJuD-4Lty2V_)Vdo_zfX(%bv}9b@h1<^EEYHI|^hA9S@~U6$yh7-EEHt9#w;SN3+RG;e32W>UKw`NUbs_>s6lDH z&J#YsN33w_xjEorYU3ll8z8m#o1a{#84fj`Sm@qObZ=Fr1Gi>b8Lc1zwb})3dS1`} z4_-*Yo*wR)u4Q6L`CiIxT6MEN0YGJ_9mpKIf9@}Xj%Bq{{E|nMw6NpsC78C|;6!JF zB~gD)R9z&bw%-|!kQM7tT)ig8*+*QyU2}G27nuk^&&@(tu(TV*aDZ*zC9BaQM^x1*JcRt zNiY_P&s{rB;2IHL$Xq94L=&%GMrcnQ`A9H2>Ctt}N7m`IjT~>M&?O!#hds75| zFIjhVn1@@t88d%cF63b)F&sLfeWY3@(iz!3Zk)^~%~`>szgDea%_W%^r2c;9dGjAq zwXq6$fPUQ)tD1UZLmbgPu1Z{x`54cUciFZRtnn|xPC)0T=aF>*4b#0!luV_@$#qf-IH;M^XGs4VQZiiCKAmst zl@N3eBJ*od4Q=L+Q>0Kb(4dqnQqnQ*(@`_u7CUO)2wOjO9)z+A9dG`eEMMj1m7YHale z&7YJD&tJ-xH#lyq*%uoMpiuoabLU8$SWqJax$&qWbV7YrJmSEZEGu+r49HT3iNN|4 zl03J>HCJvnUd}r0ch#Uudn0^#2N5;s0@m34HER`P3OFLuS?4D;dvAsUZs-m*cvNJj zg9Z9_X#XU(};}Ax(g+Mr({O(a?U($%PW7a;{j>li#n4#=i<>o2=ME5zgH8O^b$)IOMzu^tYb!?nbPQ0g=^>go7bzMHXrxKO=^>T$DrGzxzA((e}{K z1xsq#hPz95qCE7R)uryUMEMuZf&FX_aG?#|o5~p^J5a?PuidTtY-#4%L4|%sM`olZ zLdpZ0yh|omww4b~4=jXq4a$Cd(4-1>-?Aox6y!-B=BATe##LT&uB)Vcv78>-6E_Sk z$cdLNSwxo|ke{C8qQWOMY~H?Q>Nav8p<`j=#QhoFtkFFvt6qqAY z)2a&Ms0Wq=$q1CJE4IJrUR6?xE{#U+y>ZW*X|ldu7Kr)?qTo7sR%75GpuavXaj*Dv zBn9Hbxr#KbUblI2la93x4aU&iV_!FNaK^kl^a(yMaxPs<0t>D0>;&~5#&SQuw6P~l|ARKbY*n4m<*3mMVh zXQz{02!GFU8Tq?Axw@de%b5LR*LkBK=Xr{&-L2sJg*6||o=gpPG>SybcMnOWX$1&) zHNP}tX_R<%);U8F>V78J(}*??w%9)ju9-Y$9#Al}a;$h*XEwJymGVwJ$=wqaN@s#% zms;c7IzJx0%CJLScf=kqhwzW(v9F}X9L{rkwV6z;-h4>3PityVTPeKNYJ9+Uw*qw_ zJfKxlF*`S8NA;1Np(MAUJ>JT4kRvs^qU2dDe@&ve>%Qklc=qY0X+u3OR-2jLzN&4e z<>i0`B1#Cjq{1mv6YWn37M9cYn6E@9w>-{^AH=jWZ%GB|=uk>@cCANL47{oKJk6-& zz6CgXHL$RuPRXGsD1BR6grXr8v5dGd+4HW#X%R1FuBycK+8DG1F`2WXyUt0du>Unb zG6j%Z`cv7XE4fpN$7ElE$Av*5azDdM$f-toF2O>+)vow`RN$$ z$!Ok_)9wG z?zY+03UTI49_{}cG;Evim%Qz=T=@3X>rjGTzpM_F!7$fm{9^0Y3Zp8zs#|F&#~I`X zsyB=lf}>`INA6!Pe4#YsGp{%BfJpA64Ay1z*aRM?LML<&LLiDpR75B| zI-(QzhWEL+X-4-jDVaONIi%->+M{v77_UsAFE6_%v;K4TPQV{O%FJC)1Af}5SYJm;jz4tnE?Q3fRR({1n$q)5#VK-4 z3e<78wPd1{fJ5$3nJ+b4&sWj$jR(Fto;Rzmia1+l~)W0v|&qm*HHH9+EDBlpzu>P`2vLfPT$E z{{iR58#+@5_#Xon@&&LG$p^(q7zx_ohOp~($T6r%ZEVQ1G+Gxdgc9d zX(A^-pcv5GU26KG!1w977H39PXaiU%MqV#3ls0+5WSHk?AAtXYWOSHRM3cwaWbd*S zi@bgbkD+sq>Q2OUi^0YaO*UZ;5YMiK&OdM zHwks`JeI%s{rbRndhO6hyv))ahoc&9_oXF0+U!B8FmKKFF8bRliuY1z;re3Arldlz zio->vc}!~`a&z9!Wlb zDk(AuwDm9w{fQD>%LgLDgy!86eJ|%AD5bzIgT;=|6`Pio>(|Ngo|{L| zZZ<72EoheDFBM9gL&YTMuwKdruPHxvRy8#LzAD`r;RF34M6E#2jp z{+I!l?Zz`z%DhoPRp>6cllr+0PxRCXvT+{0 z9Z&aeK@P6sz2iq{mE{7r)rJ58MM{$8RGzlSq{FBL(*#@I$=HP&&+k=vJ=msH?LJb= z+W8Q|+C4FZQHj%%JlGjEm;bC|<%<+n3WB!8e4sH$xKs8uS0a{YPRcy#Lyim8O(Nog zs=?bN1ion!<A^Y4V%3wYJ7^fBtBU$uElU3+IrsiM^4$aqrEI$3i_>*sBK zAq~KAiBSMm%yePSF~Tx)EZnI#uG!QdfqvySGtj&yh}{FFa?8ECb+RZ%m0jPGht5=g zIJSIPrgvUKCB~J)mzC{#99!vNc)ZLs`f|OsQ<=thIEtAh+NMip9vj-fIwbO=H!Hfr zpxKJ3JI}DM+><%47x}xzFxh;#z>a2~P=WbN^z~uS7Lzb5_`BV^(~Lwx!MxL49MnIn z3w|##PdeoC<|3ukPUy++IM5P^T1Q*b6rA_BsZ{@Fng<^Un{_zS%rLUanUS8YFg}^Z zq#S}f$bB8cJD8ZhI@4TEZepX|Ke=^(B&jOnMX-Zl8BfRGmX6-&7Fjln=dqAF5{HBnD%|SH9$R)3q$xNwp<{;72;K@@{JlzGB(CA^yIT%$nRS7=kbWu<;nZ;qt**X+MIdI$`!&d?uUH z^YGOhXZ5oCyBGj3wwpv)RjGf&_BuP=wEeS?!_7_7gz3*>N zUz*G^1#vLDm7lCE=B+W3Ev_HdRJj zU*Q%Jw2Y`R5pP6wslx})&+l>-5%LUGN^J)EbUaDYY~}=YpzxW0aEeh;5!yXuJ@u~u z4pYiTd)vz4^Zd1uh+Wm|_GyP2PiOaoEr>H_7{)uW8<8s1BDJM9X5CnPJH>$B$3%si zX@WW?z3V;CDnA)ctQM`5cu$Y56o3aF_8e-D`QON<=WyK^1jeq`Ls&(MX*aOIgUha_ zEUQU5vx%(3##7M#KR9vr5meIT4mH zD;JsNcqpkwByc=zrlI9GdvdyG&xFUBK`%@dH-Q9-VF*mfx$iTapyEdKefzZCXm$IU z!-(EYs|-_O@fCDNwVABAB?^2O!aX29ZrnOXE!%pcN;eVmB%oEC^B=9E9Jp)C5-$uh zT_SU>;n8t9Y3G^d0mDbHSx&v8YbSUj>~gI3+TkH_{Jy&Z>95| z$f|WRV~QfX<3J$m9Nn%2cp{tU(gzJr$4T~eplwTQF!wYyhQJPvusF(4{w2t*4sk_B zp9WaRvLq^d-4(3E@6(Rfpuk@}qlwnD*cRZb7x#sCpI9dc3nlVAE?ox761{LUviBeU zDqX;#>B`JqM{Fcp6%R}41YZY(CEc$$!Bs<@i!Z+1_FscB7K8 zDC~7u+DdB>4Vq4N`5ooX1SnPN9FBQC8laQzLPf zVX9lFqQQ3L3-NW}`g|mLY`m$x-VMyX11j(AzV_Z8n|WMWHJMs~VU@1rYkqu5Ri3=< zcT{xj*M(Ma-Mk=`OoUl~u`dPi966a)k8hp?15#@8 zcd&yI_qUxW* z-Hp={?v7X~zAF_tMYona2&uwuO3U*+fLu}#M(uesm2?uG1`l8}&D{kzfkqA-QNNs18m7ixAwAWvMbV_f!|7) zRcj}pdvT-4arZhv+$c4&bCR4#GuIe$tlahhkaXkQEo{m zL2VYY%BNQ@n+I^AGkm`BRH{U`EJS{{{{FVaLx&O~9r&b#0D|0E0B3he5;34~HzW8t z-0E_7ekhJ0!;;1seT==clXoDW@Nj0kj%;~*>M2j8g_JfOrj zwrW;?E(edpNvMf^RDm1Qri?SCrRN5@+k)BdbUn3BMX{^vMHcdUavY1Qt47+@7e zYf2Gw2yfW+wz-5se#dxO&M@wM#^$|IH!tGCTzhBQl^)L#bEV_8G>4hDwKbybn zY{sJNSgzrTd5GG(V;tJ2;<4$zR`IUrpeZrK?L_)bGt8R3^K|bB_aR~p%=V2lRXjj1 z=2`gMTrr+>JeZVf;SDYubNbo1W_a@**vh1sYCRDu$k|H`DDq@>1w{!rhYZjR@`9B7;}s2YNx!7fG2S}tKVTbnmA`=bK7DE+xLf_q7$e6 zWvOq9-n%u{p}+XRPJR!Oc-!F?b6(F}={xI)RU-j^P(*^vUq^u)>0qP~vxA)Es05+H z+I%^bW3hzWhxR-j_tcl1aX(6L=xv5sR&uvs*7YVH@~nD{a{C=k#ivtl!DR(;kJ7L9 z>3u9Y^2T9WA6uz^BP-W2SX(*urVj8IK>uZ zLKxX@`JkG8J#X#tZe1;6H|z%ICyR&^$amII%SpxW1tdzK#kro|JDfiTRT6NJVy{7c z%qL8mo-HLVFS4Ie*l>BZ*=d@Ezg>}I)^@`2@)x7W6&J>OUXN0#%d+nZBTND-aX)PJ zQEA>9N%;vaTP0c!!?yaC!)Y<}UK{;U+rm?{n!1Y=I9d7{iw)2OAX@CSl|Ln9VxKOS zj{LfRoAj2R$ni%|nS+Vx*%Hd9<&{Lob_t{!HDrU^JQaJqD-a?R_UAr*F!{Pnox0tI z!hzwo#o_n$>#arC{wz$S$GWKocYBFwgKFMeks59Ft~H>@Db6m+ag5qf(da@>$Dl^L zqvk*7Ht@_`X-cu9nXz)f0AqC&s%}^ntFx2Insn%CU|0(G3w4wee5vuuWr^3ZzsgX{ znU=s>)|$9p0-_dL6X%_i`lDZXSp!SvcBEjDrO^afuStAcO*DmSF+ET^%wF@TMg)6h znuHrSf2m9?e``ueeayq5`^^cFCTd_Jz}Wg;Hv@l^frH zYll!re5Y$IR?}~<`x&EmZFu(-@rkGT^D2j_k{a)WsTWH{_L7vfz4Bg7K+@LF2b*M{ zo84Xyi~ba=9FDJ(j9g`6HYZ3{80uU$vCml7#v2DJ=SK<#4*Tb_A51U61umDNtVeqV z%owX)K|&H#m8iZ+-K`~X>ZM{k)_agNYXa&B{jSWL)9CuRSgJ6is{uw@l*=~9ML&ti z4Bh!V0urx<=BiVxpGsEWWNv!8IJn9k8m#`k+<&l0c(xwK?=?H^1DyQ$HKgv!b`3FOv99Foc;B|1r`Kw;5iwqjvt-D_`rm)&#y+0<8i;y7)y3b9_-GvQ+k=IBbnet4ICtR)Bf30PJ(-t%0%2Clo04OnYU zGMy=RpL59;8M-yo+O+57ncvg^9L6m98U1RYe`{j`+P1Re_?>H-0cJH?NR*&3F)2lB zvv^Z*))|Zf^gJb2C)PUr=KJ?>gDHh!vxrUZAe#>tkn+E(FMK?<^6I>NGJBWd-M(L% zK2yTn#@7LntXMax8MfNqXwdtFAQc}fk~1enhj*GjwsfX(UFFaTh-!*#x|;Xif=wf+ zOXB>G;_s3)K+NeM9?4yM!D(l~lXo1YOK5zd$#-D_Dv;7V`aUCx2!gKVO5&C2h$ahN za{eD0%?7P&S1q@?W||Al$5!i2XUkN8$DHD@Nq#^>7yr8_Yg3$mT?J6E*D#bDx@x+D zV*Y)=nlq7gakyKon!f{SycYZbXF>^wY=vn2Y@6>|*90|OD+oG=&nezfzh6g(;4 z8cs_qOYgPy{&t^v{5Ag2%Fy`+tfN_X22^tiILtl7)lZD#R9ck6~UOk)efdt-bpOI&;=FuL}`!O@+2 zS7{!}H-)GmeFUC!424@J-7{Sq|GAkYcI)udLOSnhc1{gTlWWN}ydtboJhO~$nLKvk znPIZVu71fn+J(;k3)IYjzSqd{5{AmtVg!i~GHJdQvVhg@k;MEkNWW~%ObH^-@twP< zzvU+z?)j}!!xLGo3uz12f3VblLA!fYP}wRg4hoHvD$`|Js>YWM=7@^aj_s_)>{J`# zE<3Jdz6QXLZ@1eRFeeZUR#kPvd@%o=d+-4YRr#A%YJ)zb5B{AUx7F@YzoWEg@ZR$M zporprd(;NVwVHrNS-7?~z(<3jW-5xi= zK3&Zkjuf9ehM|8B9*N_P|7H9x?sjf|H-;6u`DhG^h>cP`oa@&~W*l8w2kXa^N5ior0JOIC z^&M2jf;x5;k5&iKQ##s_Dw;^{j{li<0dCA0CKM-!SMC>8^8-{q0|P=ymrA{HHD)f0 z-#-)7F;jOWbF=Wd^^;;+DqBaVLkfBT;FDcThgN@ zXq9DcM!MAv;CQjF74d_47#uGAIEjUQ(6TA>!XKK_LwJ+f@VZBR%K99m-;YPNd3KjV z35b3er8-G?&@Z(%4B4ujx`t_3JY?g>J?0NcLpo9%J&bE zyCi{3_raPKe66IxKm@(&Lcxzy?I}8e!S=si|Gy`O&QA6JBWLLYf4xzC%dBqNu`v%6 zaaEvtVlBiN)G0vs^5+-sd~GOI$+pV#q_B}2{KKRaWJCiZ%|!Vvke}pf{jQnctR(+4 zNRCm4Fc8^7qs=F>EGsPFz5a&(bC7ZCTroZ0U+cYZ!js9UH<6+YB8m<`5w8;4{qi8G zo#EH6=itk3*{4OqWTVCMDl}FD0Go0{{|geVWw60)V!V$kvSs8%P&p%27 z)2SMnCH%O$GL=VxBI0u zkAD1CpCHMa6Dff5bRal{^Wp-LHwcS@_^=uX_F0skKNfLlg8N%}C2(p#&OgynHyHx# z5!D%1G%Ph?+-h>PYVqiIZ0=09Z3pQY&r=Cj&0?1#6?<`Hi_z|(z>+gv*b;Bfr85fH zlcfZ$0je@6A_|J)`I|~bN4iN@v)rEFRSTkElmW4hDX1qvKM?+z3=ZK9Fqr>KBQZ05 zTl-&NBaF66YiT%s{}UDl()|IWIwA_CvGs?fAR(nT8Lx+`=a-R4lOW(Z1Fwo z=FaObK{~bDr?s0qtTU&1(;e*48tUv7{^@_CYofsQZaE`;wh897Cwr)L<{PhRfIGtq zfi+KKkB=-3W?hQfL9kFqBG2>xq|aR%oCD^A5oEQl@a}Usi$niR0Yhghzv@gDgTheIa zFC$K7w$M?P-sk9t|D95i`x6ggHqaNDbs-bn+)VvBPPnW8q0CgSb*A49&ey}|C9`so z;xjd&Bdq;iZ>r2Z=E|}y533qIyCIzB(}I`Y+_mJ?qP8H6d$gHo`Lll}9EN_yF?a97 zk+Q;Esg44U9@%OIgu*`*tg_San`jm46@RdfOBJ|=Rn9{XWC2z2$tn@$PnX1ezk^MF z$cGdyYU(stgSE)y8pr^fwW_4$N+{QFw3`Lu91uCx~2h!1Y z!Pr&!&fF$E*5&^eh?ItxY{Yc84eaMRgFHEF>wHxRm|uJPL3riF#yzoeYVh{*MCIV)`E^)&P6YAAgOZ(ZGREau2S>-oLal2Bb_Rhs4)4s*Bq<|@eWs2^A>eHqjT zCHFxbzUwC-bS)`xuC7y0o^t)HVcMCIuB$d_Nzcaum#MEN^3Chfiix>}B#mNO;Tp3b z@Qr&-1o}+hcW!r3ahNYtS?!u>pH#p%xymU-!mGVgJbtZ#t)@(9-NgW|SwC3GlD|B1 zQj{#iabWxVV5k%X#x2oSNpc26eJcSbDE+A~i9%K&`%Czu5vd_rl9%h?TJ%iD8C)Z{ zN!^<7a&La7>Fvbb7F9qmu&&t~H|dDFdVw&FK}Tw4(m+A$Vl6xr`;oH-C3@}lu4A?Q zouOO+!KcKK)UL$u<|HsQQMEZ?RkV~lp2aTRF>Vw{+$_zXpbHa1HOA7es@}7rj#8R0 zcas}F1;(t)$V+PkM1S5l^;_eidye^|RMyK6@@EjvRmroiH#;Af6&!Vfgb=yC>iU!M z8_SL~j0`T_!-I{UVV5Hodba2F2mr#@b-4i$)j?B$NC&z%#(gO?Dx|BM7Wd-v{oS^~ zGGgqOUZ7pEk(kw|F!hFANCN%N$_OX);qk2~Px`}pOA?ORie?ew z8a;>I2SACZe*}ige-Wk+6$RMYWzuxg5BM)~EZ8WoANgB8{#mj-t~T}q81Mw0jBm@3 zc;P-yg<)eZln#0ud1xlgpB@BeE%mjW-+ukp@ORZw(rP&U(SR%q1-g@{!sj{17ckOh z$x8mxl;W0*0)}lBr~VW-g6fxkg^|JDq-4#1n8>-+Ip2o=lwI8t554NTB1hlkyn1iV zo44(WOu%4Z?z7AkF-E_ppsg)l&2_p_{ZYe`;v2))bkA=TS&K~Wf4LG743pukkmXFf zWIAOP`^ZpS-DFMm*9*Pw=ocejrI^qnBkmROlhqM#-;s~DQ@udS0L5b1TTp)vk6EpG zXZQQ^f(bJT5`;6AzZ0kvk=c8XEp0W;hlgk}DU@>xI)4WKR-69&mtzr=XOWbUNd=nS zc(dkej(Mi^k%a~9g0D0uW!a9pI!=zoSBt&EcJ7KMTW~XKOBSKQR{qJ>>He&g4ob<2 zJENk+JeG)bWp=lDP4+i%wgT(4DX+Ds2biB(NIz_8o&!7c7Gy6s;Q%|Or{%-R2l?k*Q|N;Z#VXaGN_F&boQiJ(-9HT+!_6x9FZJ7p?ErohQcKe za;8$}?6{>sSwz>eWcgZvz5KbH|6(8vx#zR5QBOEY5}CF+5n7sS5VK_@V_$AomgK*; z5apLlO$52S)rjjKR!^0^rOJU1Rm#7oam~d#Z6hJ=YE_9xEP5(A@f|fMC?_(*J7^v~ zTuaz^U=$_7O z?y+~SFneqZ&=n_36Il=lKcca72E>BTXH<#t-?gc1N`avrSI_MAqqO!nN*H*6JP2Edq65{U}>71$FM;51Od& zBmx6lpDn8~MKjb@)Id$c?e}1H%Xb~3Z_O3U6O6>>kCHhG^3mL29I-tI^9*qv0r6dmD%hlI0otF37dc7m4X3O6%Ze_jZtrsa*b2%|u+TMQBe36M z=^T)a7!?Y7j)=RE+>cnxLC@T9R6<*yE8rVry)tBTf6V90CB`%!K6 zzThyUK2(p1&zVcDVy5us-tbra1qtERbFg*6c@QZJ?hC9MlS}!r6di->ja%8h9Y@_+YHQNH39x9i zP0p}b1_2XqR*0(t$l<`5Wz$%UIS5wR&Q16gk-|N*!A;H{ zDT~(%2qLMg{CALM<9iC#hIXKVEm)tZV)4tC?Sw|5)M8WHvgdK>R5?i$r%4qg7 z<&OF}Jm2f*g8_&LZ;q*(V0TR_KvwB-#u+BJ)NIMn>fzyBQd<9rPGt5(ztCj^qj@RC zmKe)k(}TR8J3a?BRA70Qq2-K-kGD~!cshE0;l9W8#VH2%+cc7i#L^a@QXIm0pA_Xe zZ&e!WgutV*iLAcm;Us;)s`tJ07%vt?FqIS5KZ7;_e>0dqF@OK5B#Q$Pkg=>TQq-H& z#1oD&*WnpIaMkj8J!AOo{LdOVl_MigyK&|qeiVG0y4Si#vIMjAa19^U#}|3PCIxl_ za$WcU1ILHG6^FUy2!_mly5ulw{kOz@1`)Uk+`t6)!LW7S5-Q#(bd*4&EN#Sbl8!N@ z1e?;3CUKMy7f~xpMo_=z=@z`)6nm_nT!zfO2Lf6F#=yq=%QfvzW@LAb6`HJ!jxZUe z*^JTQeOhj!TLyM+ zazMPn7YJZY%zid5-WX1!5|TA)S|v3sWzu8@7y|w5k^@Afjq3cS(+p&~Fd8XgKarku zcx3kqB+++je*B&%d*TAEAByU(p6XG9L+_gGUj;tc|D%MSg#aH6}aN6OigG#qnR1T;Yn z_LFGDtI8BEp(`j3y4)OT`IJztC;2_mqRq`KABZk!mxPgrviA%MpwyNed_#KwJOIWF zV~Vk7;M68R{0%bFF%&fA9Uq$>_3BznkTj{fn#OAta#YhBO7|^iD3JI{t$^;HC7m?U z*3)A~soE-2h1J>8ml1SkSLDCF6oBo$44Nysqr_=({`p}|vue#oGe(IyJug<0Sg_Ot zCxhq0R@-@N?dDx4>XEFR?QXzfWem(S;EqQWZ`4eT72((7B05xujUt{_&~g4WMIVAh zo5GQ%pdqc)wu^+_xV+=HmxhT6blP7PtEr{0^fccG_3L%P<%RPDsH-r+&}%SLDaprc z0$rK0qY-O*Q^mMZD}d`%8Ec1XI~|CWZK(@}aGV&b?MZJru#jIGLZi@98txlQhY|XG z>}}`hZC=M4)sQxlT(+e#^>|aQe&f>`JMpNhOQmatdj0qSnl|-N0`iJS|HHCmNw}di)-Iel zo@m{9d%;WBcjn}yb6fIbty8ey;f~+gI=8%V$%h64kG9`S@n#+Ku)E!V5=X32BdR1S z0G=IfwWmd6qu^}7$~Xbfsp<$xtrJH|!OD$CLAM38?zi0EzBBgno3l8NjEGd!GX^((oDwQ>&w zYX_#(x~~mfGlg3 zV9UtZm064rtYWVP|ev+V3=a>LFXV*df@9qYJBYB^N_j_THR`q z+Mx7~V%%_g?u?S0vRV!mdNr$M-OailP(XvxS2wu;H;e8ogJqyT-6v`q`Aut{5g+!A zx5QafGI046pF8ftbg3+PCUC7ZXp+f-$fcBxQegM(+r<;J=#jva;i;~E06h2Or3$cVqeo7Zy=CLI`R(bjC!V^h}!%wQ_JLp)1B<#y_@Wrxs|kb-mTpsGVW zX8U%~UF-*MrSyds_YC+dA~I%HeyemLBsneTTj#*t8Sy)u%)gyR=ya`lYAdBrCBcIf z{9g|epiH3bWWS>%_xLiDMAAp9_z@t3U|wJ$Icf5Nx1Hguxce(iQQe+-XhzPvtbB`X zzTU-tMCZ6;-BvU20~Ny4+U3Klq^hoOK9IE;bCZeHMR{Q>5Y~_(FN8?WcMEKn;INOB zV#-^>25#>Twwy=_E(5NQ`&->6*GFD?bd#wdo>;o6nrr3j?Bb}$K*dr83GQ;kY3CiH zT_IOcwlQDnIL_S%U4r`vmBP(uuL;YmJv|HcQ)+8eskBp&Oay^jzcobZetKEKhR(v$ zUt|h^%voK+5xrj00h#e-?0am)ueDK)artot!Err0Wtx9@l?_p30zv^B@dWf1m|tox zf?qKn02-Y-Hpm&|TY%)*{G-1?J_n3nprcT%mO3k{`W1a*tJh3hfVhrtoq<$p_D;@y zs!(7?J7~G__P<|=poICY@%0xW`J~0GGawR3gg0Gi=^lngC4%W|h5}}|d#TzIXh5wZ zVv6&I3Jw>JvZ9z8*2A0!K)Hq+d~RX>XESpaz|6|^E1r#Q=TaQzbOkPjllI79%ny&Mt`N{E%*OEnP-ir>lVx~Kiy*MxG)+#J+I}R_TK;!1A&d$;$NVi^AI7GUA*JG$Xd;J zsW(F}KPPF*;hgw5aDnz0yDgU&nFAjcq%y_&iRbksYNnnQ`TqCcPzMxa_gs7i^o*UkTpm({#w*dl%OdH9$Wf;!?|1FnJYz} zivPx#nCj~|3^;=jn6#}mAUdaG(zd55(rN9p^W7xTp}QbeiiW3DO>%H|z;-Uxa^Vs{ z)NJoEO#@43+D=8U1eN^kUTGVpfUoKzz(AT0_QjN()~>+C-2m4IOXl|;==v})2bdGe z?q6F4QkO=#c`KB()&Q3Vt@^48g&hp)gq8#r(kFHLI)x-KIK79k)t@~Y@0lK6yzCl~J^O=B_7;*Ubd;-C<5S@9-Sf>?Zx!akwq^2Ni zB(M?GLn%^b-M{*uEF+$GW^jP?Zj#u)A_J-$LQRA@Va?CM$!eh+IK}W_+cmi32$wkr$jdinQdt!S%20;8Y4^V=bf!wmxU5VDFLWL zc@desn1*4_(hQodESJ7;UO&=*ig3-%VVv^~*+9c#H=fQ=}KKYnv3rNs!X z>S2A6sqGw$vh83W22LGFe6YO_7jkf_=oYa2D{^!;)LM_Cp1()FS-vK4;Scv$Z9gm1 zt5#QYfzt-cS^}BBF6i|WBiBm1yQp5PZlk7vQX`0s_@k!Kv&-D{tc{I^lQdk+0~npJ zqm(!x}nM z;Z@Tf{i2H#Euh-wLTO}qA@iRo96U>2_8Ft+mA#`=r1e3xy;RMCv{HyF4~5JzS0rM= z(^Z?_6j~~G8Uh`zw2bHrhz<=l%kxm;jGJ|B#YHZVv5#I8b|&a#%h!8np|yA=T+|kE z0_1saS@rmBYRNz*0f;q=s3>OCvXl+pHq>0~V%3?y7xsiuOI#=8o2K6?k*KKLnDf}p zooP-5Uda4~<467Z#K+#CH|Fw6?Ji{i$9Ff(t}Of0BMd`CZLOf8!`^%E394=m9X?@{ z=kAt-?7`Qfj?>1HE^q}o+bA7M@=2!q1hk}yHobU7jkTZC z>*ri3Asv_lByuei|59?r*v5vDzYCE2bjZ1zE1LzHJx~li?~tGm2#pj&MliJh20#k~ zT44L=&I80aoJg?7N$sJSBgGW8LW3yXhy5?#kF7kZmz~HrIK&=?<}gK&D}j;3Xs`rF z0Pu`4guL4L8QyU5>c4mc$I8#uTF@`2bh$#-W;}K)3xu+>g30Ew5f?XgH#GHy!RcsS zFKQQQrUpGX2NG$tV8pjQ-~-C^yyjbeoAes^MkLx6g@IkQ!<8}jU<-0Uhaf`!Lx;!> zL`-4fSMW)s1cDL(deu?8l)c+xG71C?CC4YvFJ%-;e{qMhPa--Od@k;@bQb}zzz|(;R!DhbNh;z}{I905T*w)QRG1P|=m(3c(u~dBN)d(|uSRE&LGC+N^@c&Sv1sq7*|1$@Y@-GMCF-nS~ z&9r>tHvuRR;i(C1j1US+VrU9wRXKlni-H}U$7~bxs-_Bc3&#D&IXnMK0`daq=ze`U zVRT}&Q6C64zOzL^p15xr{m2H+^_Ay2-tW+_p4mn-tOiN5Ny>c7w^^;HDMOdL{wZBa zx~v#;TRX2}Zh-zwU3E_=sGmft*P}y6JR6Y{qzAJ1#>TJ=ht&`QVR~UDj3uRGu5iQ& zY3z^wC>=19&D$chysv~JvO@hJY$Dqt^>GHfN==aiYc+B*u%R`kNlaYwW_?fo+3}rG zj#QwKRUd}`u&g?bEp33aN>Odm_n}Y#*g$~IZzl)ZJBQVpIJ8~B)gg|xvyICP{1jmC z8dRF-el5Wzc;yr04+p*9+(W2@|1k!Gf0lMF$7kp~fMah49>7GeL z&e2Y%~`F`s46b$l>Af!gwCwOG&3`49mBUd@IBsEbQQ z_!vSP;F|zHpr4~@q5L+Y?5kMjy$=@mOoTWbbzivY6P<94*k>>JMDOS`Ck$3Jl}mWjgf+bT0zq6ZAjfA9IuOFNm@<6LP>5|NR7f zdrF`tf|uA`BH{*0%Fw;Phn5=fo`3#@mFJ_gqXwVc_&+{*+(f4(dXnaE=b^JdUH41K zUV!I6fBgIXD!KlJD-V}KJLUVua{hMK;|}z=MxTs-dEY}!gatMY^g8I!o?M&%s^ zM&kc_IaIIBhpKiA-;o^a8PEEvDF~-Jd)r=E!fxAsZ8+-uto^yVvwnWy9vfRH4U^^t zLW^DS+KbsiP8_(xCZVtuaGE8>ENkjI_Z`c9|NUD&@?_eqtO z72N7@tvCBRqLO13|Mv^flbo>7w(s?!^cnRe**|C2_gN>~X#te+J`40ogU2h52^4ty zPjRvRK7W?sT2Rs?gs+{LIe>k{+5u$+sMVbS{p@N;MwQp9K<3y7bPGo<))_-Z-EvrB*}bj;Ceg zof5-ZoO&XR`|mq?KU(^3w7*pT>yPAB7%-S72p(LB*5Oh%iX~Rna1A(MlX2`*&4LDI z%UygZ(=Z#@7{Gzv2Z2bC#R=^AL7=tDY2Qn?mN@?jeyNZF*{7fb+V`BkD9iyFKmiO+ zK`tO2RHx@MOC{qE1+lMh`)GLFl@55oHFlejI;83wuOv(HDqhK1!bTE>P*q$1zwVh= z4(;Hwpamf3MJ!PC@+<8Vb@6;=DMyP`Ja@Vj-~zmYvWZ>}0gC5+bbxXt>5{@h!j-yqQ!mx8W1x+JozzRfcvvB>y2Wb$eDycHEDwdY}m|M@Lfq3Le(m1ckxxIJc?&KqQ8s#7>oC8dp8^#TP>r zB~9R?4lCYX`v?t$$(5ic3V(=}A5jrKED&BQO0Lc8tT4*6t%6efJvVu(piT9;Rq1$7 z!MIpjn465zcgny=+|)iQ;DHVyLBB9IkLt#&2A!y~0jN@GRrCPV@3BBM%ml$}y|U6O ziC1|li%iT1E>_A4uy3Ds=bZ6rFExi*>Psl!pnl;rA3b z%vp*ZAGU5sAAxY~?4_Uk`dz?;G9$7-0_9#A+`Cr3bLeeBBpAp{t+(?o8hR{pT5lIz zTYx_{GyU%5BStMI1~z%O**g=PkGeq@4y97rd}XMG-B;aH*}<1FQ0FO+WZ|1AN>^ll zcs8hk5D;k!n&sf_viHkk@}cHUj+#GFi>s;)M76J>N>kb!zH#KLMwXv580O%27Iwaq zEe6?3QY;*c{kYtqByAO1At)e7`4petHa1aEMlBtxOpYmd=EnZe0vy)$PqH=~DXviS zvRb@yCUUiAuA56j57$C@;lb>%Z!9WgiJ3W*FCO`{LrfgxG6cEgznqTstkrfD#!>~c zcQNjXErWB1%r~tIMt-bG2!sbyfh_UAUN%+FHCND|jC@-yf^`H@n`7qXXglZ?={W%M zcMo#FgchZNT4oETxHUeQ8<)n@CPxk;#h69IRDZ)F4Q9W+)rmXVJoTJkJUFOII#Ad7 ziQy?d@_y?reHkXkI%Jl}i>%>UpAeFaJ{Om}C(FCk%KUUMVor2}`jgB(-L0-P(2Q)s zuZ_n& zBQF8H3DG%&!*Y~r`JKr;$}g#vvM!hS{S>fj4 z`$>y4c#-6+W03PNwgxg6U~xHmTG3y-62BF-;T@t*zRJIG2a2eYl2(wLLDl~L zxYGGGmHvwP2~Nyy8q1EQN#omax1n#`J4Y!*Z~-0A)HR%_z+2mL!gDASAO7Ws-2;~A zupdML5kRcMxcf~_qT_SinJMJ(<@NU(*jU|-POJ$s$#oy9zNAu0U;FqH*AGOx8PhT5 zgyXQbF#BT)kO*xy7GvhvL?_a>`?sah5FTQz#=K zFDiTx7uSm)pfgJnMy){Fb>q|dxMjbF-R$m;HOif#a{*>@-Y4mSqA%!`{(;jf>nRA{ zGQYBLnL3C1m96&~_=lhbXrTCE?VwcM*K6UbSP&E8f6-{81bB@gQN+#8` zNwg?e(XvnYn($F^?|Vj%w4%%dnH#-)Iek4Y5Jp|-USv_05_r@N}iYa1=>-p2uLD}g7)pMi|VO4L5EKx26QXuZb>Tv3ADfU&A;@UmFr^hL^uD=8i4OGE z{u=#!)hsBaV%K?Fomq(dnc0i`=c=}@{+X^`#?5mXw4kyh!J?iL0F zh6Z66x`ttB7;50`;d#IFe%HBwF_#enj_;mjM$~J?^!%Q9JlVW{RcYyOP+D2 zgXkUn)&PkoB1Srj=wjP3iaBm_#{_O&n~>)57$qAbo2CCFJLT*YXoQM70HuHODFsJe zkR0h;$x7I00HWm7SANcRKj&y`O0j!*#r>Sf1sD7e#AkZ)j8LC#7ptB>-Tn8wf?#ZS z4^Vb!+@6WK0lVRYvefQ9NYr)vkB$#ehI~HnUcjY;4UUDmp+CzIK(W24FaLk}@x& z$Ro`4na+Dkyp58~49?a=^SvJ*vuq^1hSL;yKWMXT#Ii&`m@gVJ?Orpbrg$ot8-69^ z!$+X)zbm`==57QDon-^x$%sG>2BN#>-(1;ZTYDZK z;VM$VqbB4ZE9C`?jpL(CwMgx`pp=Lcw})5sk*pUwpvf=sHe%S_sc%YQ`;qi}llX(0 z8hp%);B6o&HQN7R{P{b>x%c=Bo6%p&9cH#3*H*!=RAZQpUfqmRyil04Y|kwq=Q$CryjVH_C9T|%>mc)Fic4(~tahiWN}cFE z7FYk2q!((LbXhZ53XLQoYo5Cz6#sh=C+6Q}U$;-i=$CqLc2;|f=Y@tSwfXej%w^Wr zZ@(v0$LDciT3p&DvYJ@cg~nx>=fLMst8Vr4IahqdqbRn0szXQZtM87nlux}?F1w{{ z=)PsAENs1>s5}!_X8qlFWbHBoTPtA#?&6YO_Nou6ifZ~A&|OFGvH=JM8auwcD>T0P zxMt8)#0YPDd4!xXh>3Zmm@-BF)NL|-*xrO;3$VV7PzlPrQw$%xrf*N?>>iEV(E}?5 zqtx!^IQ#2(JOgr{GJwM2>3SM>%+=x8$|TtT_$$&uGJ5U}$!=CRUIgP-$l@?YliDXW97xxdT}P7g3^tuLCVA+}VPr{>wNi95$jm%XPg1F?P&?*4doJ z3&myzp42L7A9!pgo6pOmcnF)Ov$QH{h7%OK+efw2vYpszxx}9fpZp zevT-)#g2LeuRUo7g+eco5(+X5F#LgYKZ!jc{nYI2a&xoTq-HjlGRxIrP!3-00h%se zK#wZp-m%0G&S-~1mFqVV!F+6~?WFrKjU;ZBIpNyITh6`)*$cR(&U%PCZa8RU@EiEQ zvZ=kN#TKCG^pZ96V>U%O^2`Am|5GAr%;jrq1uV za1j&tv3U#A%{3qrF>|9VGjgH&6d9~=C;GvjmJ-tjA7hPJR3CMVRSz3;cU4^YRdOPQ zVj${Wb7t@5KYpCQT-PHae7%yF?K>wPBJQ^rz>!4=H)i&K^K9_Mw7S)W7``lZcc)J^K3YHq~IwBxZzSI)siAC{f%!oR$G*mcG$OKn`ZH z8lD(VmMUAOG-m{Sy(8^Dq>&kN-2>|8Of!!|$o^-clf7GkZzU%+Wfq?>{`l~%S>j25 zVVU*-S>wW?@zRYHKu>LPzVfnil?AuFJQI!B;45`M9>jC0f^?fh*a5PKxvig-OQmE% zooJpz)V_UB{kubyGkRn0nkZ9pg#`)Fp&b?wiI~>X@E9SZR$m+IN6sYjZ*==cO_CcnL9iNUsY5 z^`5?7CaP^fO<0jTiRFezMF#6PNI3V#Qr#dIeYaScvs}Tzu4FD`Y28^ryMxi0z=zoX zrAbslKOcFN!oSCvR+q@N#QHZa8*+ErlEi;2$&vSoRIS_l?zDZM&%>`KPt1M6WKaKq zQ`)nVm^Ss^KojTt5H}pmkDhW@oV;FN;gNyo2?Z#C82a8mg3Sf9F;B8?YdgtW^kTZL zR$-wwW6c*Deh%v~#Mh?^+b?Dyb`R|a5YAKn#RlW+Pg3zG4kvy#Rxe-u>}h5cea7s} z;t3>?am7n_t;9Wd;S9*0ch)Ui3+sNKk?TMj6lr1~6^dG0!mY!DYvjcCa%7MH=4m4r zqOymsIlUw81d0UCFMb{YjR1fJl+A_`w-*Eb$TwX>FHDF^idlp%fdBbg_K}%U^;EUY zFBf&C27Br+blg7@OC6@}QztgmJz69TLO%!hO))!}2h6!>a=)eELuZ=UfZ;#>)R-y4+Y%zamTnq?DHT`!)bt(MPZ%qesUyE%iWGVC zj>h9DPqFnrn(}PROdF9mFwMv<3Nv(2A=7j9Ru- zuzwAUYn9}MF8wvL(F*Lswc}#|I-CG@F76Ow;oy0%b!%K-jEx(h1gcFgeWYLvhP~Bd z2qZD0#809`V zBd2BB6?HQ{5h*BHIYebmt7MgR1UmCBV=#l2%#uf>4&e`@WBc&Nti=WF!s)QI(IYOB z_L`pE3N4HQz2Ual}hOdSH;mc;f= zl7#`zi>D{_y^H2@iA}p>mSASFYj8kcz1>7)^GJ0s_BsTZhW#?pZ}SnqkDHMGQ-+5@ zjT5)|Jf?fx1dy_~caxSE4oEvqhAGs){BKgYUs0{F1*&MjoM`M&p?%NOdRSN* z*I{n!!1%;T#);@dX_J-VbX{V!WWAwIj+u$;+^DuM0y=|PW^Z^X2fs(TvUbz`!nZ-iYbGfyS9R@Vr7%#TW_b>aa-~-xvXRU8AJ; zRncTUw4z2jIaXqyAO-#vH&ku>kq79P5k>GEFjL#n-t0_U(W%B6vA-u+_(-p>wxzUtHmvGmJnM{n zz79B0Vu&Tn;k1aj7Qhyj)++$5>?DHp;Feg{|`d9-Qi-e@v@@6+Nqj$Zy zc;IN&&p(X?zB(#qt2da^_*xeI%&hll)lfJ6STBiC;~tvGvs2vV0U%DaUryhYWDGE~ z73p~r)%c?dyKQfj9Ss}*1G9S=jBE^U^*3fHn_WcgviFa-FiH3rxD(A`<+)UU4`g$p z2TXz7%ZFHFil$G#su%P1JPC%bVT%%9-8kyjpeMNinZ=i(2OAOm);C0<9{GPSKAjW* zv;Se+6HubH6g0bKetfQM7t0VCvLJZoEi-+HbWx@Ll@k$8cZKWb9`gn7aN37 zMByKI>#~`NS_Aw#G!LRh)%aym8GZ{)nF&oJd+{li^=g8u&>=a|rkZv#r<=Pzm(#(@ zIi6hpapXN;Wo2QL8~%d43D4h(9+_H1xtB^;jr;%?^^d|C)_DU^rY!WYkthY;Lt3vY zC<}nW8`a)zrBlaK&W33djrwje*d4l+R~Qa!gdJZv%;7jv4whws66!b?KQ6HsGR zq>XGVHNQ?-nMkHXcpka?SlWK+dY9@cv>%wSykuWpjSSjzeXxqIlvgtv?;B1w&mjhp zpM0Dx?HS!?g%vxTs)W-ur{j}ftSMssd#Tnh&?7h}^2PQmqC`5Ns4;#xBpox-?Z^_= zm+1#^N|AWLVzIoEqz}18gswI7BUf$t< z%_40-J#_<(gsuskruN#%aE}eJ*vqeCdyOcOJgIL&PwmWb8n??WAVm*uc|H_QIO12Fm%P6w-?5F%z z8w&LVfit)U5Ka^Y$r>L)2Wg#FT**rupVkKYV3lvx?&m^^)UXA+(OK6#^V1pfJAIHwtDqx)<|2ZnoY$0g`w&)Kc6};v80cN`lSYLmXh8G z_a2F;REF7pcf2_VUetMxsu+2yLtW!D9TmnmpkZ+)BWtE~+fK)C_V~>zfohIbG6}?Lk@sIo*dA+sJ)haHlYq!%OP@H`9DPNIxVu#`X)CI^D@kSQO8& zBG;RJ$r#YOu-!t*>RWQj-EP8BX7Zm_)M#&G4C(T`SD1xzO&<)odC07^K&mgaztG7H zMbD=It1dg%k=yc^>l~TPq39P(z?RW*B^%WE&P!`(gS`28T6}P-XX=BOR^hA?FRtS; z>CGUtN^MetfgI1{rq@kxPP8&*ZKhh#=+>6DmQOQhr6?_bt&?UMXx-wSF<08jQCaL61jX6bgj*=_>ZqeIBKl3WSZ^-hBPA9eiYv{&$0 zQihy4IXq98*{2Dk2fq+)r&NolxKVJ88@Bgoz9pW1DQA~Z;Ikm2)v%b< zoH9^O?D=b||HI7I+edG1cH2<|NE}|f2vyrokbHdh>jrfiJ;#k`wuXn!qr#x$9+4Uy z7VIdj7EpR*2p;36MM7Ik151Z;4U-|LP=25P_}7g>DApm{k2$cp%uTJS>2*UxI6R_mv4eLi%b8|p z6N6`LtOKmbfShZ!%jS2a_v7s;ve84YQv;8pi3GvJ*lkcra2ns+0kQaIYH3Oxm3lOP zVWq`)WXLnIP7=ls4D$4LD)m^ zWHcQ8nF_Bgf7x1ex&{3);)Kt%*QmoIr=vK=SDi0I8gYy8EXQt34v4z}87(1*BTnQ^ zO($oZ)7B?j+~RE4tthAOghws2qCYtBl8PiO1E+LdtBuud z1T#CX%v$@OZq?t^5yMoswulSyO-RE_ROnnhfFV@NsbVPq9!wu0@UxHV34XDC7J~04iba7Ru}Bw9}FhHbS`0n)Sq1TY)Mn z>vuKPn$=>5FrJ_3pEt2C+M?HIOPd3_1(XctED7(kx~XpQ-+HieG#~pem$BP-9%#7U z+6Pj-Hh+b-0t|ZwNY){xkYJnW%KXTLDsLjG9Jm!Vz5nl@Dq035@`N$xW?XM`U%%F; zQ{vc5kHcLMq^USj1|1Cua|)f1s^9LJ0GXP#d}9^(R)Z-P^iKrH@e!+)M&l1?L_F|P z%i4S4Gj_k}-aVUyO<-;dIsx@x`>j=Xrhh__Kw*JJ5!SLSCT1p6=H(wXYTp0EIzB3k z>Uq`+9mT2|(3X_iikGVX#izraq(f8iJAQGmvt~;aIe(wH zFQsqmzi4gri6h-5^Y7+FlQ!aKOh4@L=lx%ASF-DOqYskX%t5+4 z-PCXiRb3l$$J&X`j3hkv7#(HEc*w-ku>Z*DfGan!VSB&#u6-<5M7S`G4IqIT_RV8r z4*~s+4|QCV3h6x-R?qm~cO|4s!NJ^22yg3uj5{@qge@zZp#WFxHz^z|iJ3nXq2N^U zMPonK^Ynio92m))fv++ao;$7P+Z^((Rtq`UNdWi3qSZl`C@Hn;&Q3vy*4?W*%xH5s z=XaF2m?}l#%;!`cCt%8`2Ho-CX0SYqNa(9OAKX<0<}K2+oH`jbl^z9t2ZkXxj}%5w z0dFn|c<~YBoEPK6A??z~Nq|P04-6%=aGs}_WD$dhxraSCA&vJOCP&}@3jaNw-OMj> zL!s(<6ogO~uC)<7Tq3L9P2c=kl&hk3VL*7qeAZWro7DvL>0T1l20>j#j5A~XGCHi51`X;H*2FdOc^Vx$wO*b6-`;L$LGaw*r#(W=nv+IA*F7C~6!7j(2i0_*7fwVs5Fz@YQY7D(2i~+!R8OM>HO)1IJIw`pp%lOd5x$A~$Mkn*E%ls-c23gNJ7DY)7Fx-T@ zviXs$7NQe&VaaPuSC0B(DZ-hr@;nIg>^$g=IE35F3+VzmvqejQ9T>;R0*N1Ri3D2Q zT_pajn(<7ASKmv1y$?$?-VHD%_*(9u*y0Y^X+jnqr%~Yid6RDcTa8AsdPEREU%?vU z#NDQus=XGU;NbRY@6UY2cE!zg#Il^DXfn$QBZe^|wm7-ioJOKtQ~_qP;db|<&6fbx zjWZWAExg!uz_z(CaX~8$-?nx;1FTxyo}KX4t=K&$VQx9^ZJCt))C~MJn#VtwBz43O zrW*?Cs>FYf=70T5P*}8)I!Ae>^%F<4S=5tQN7sclo`VGLTY^_tsiB7&fIC^})bTa) zPNj3oMT>0yr;Af7Q?oLS?Pm3F zFj-yGR%;S`Tnc0OdB2a|6#sC!)2j>n;zh5{Ok^tanY>2B-+^9t--ta+QhtU-DV6Z4 z)!W{o3|lD|wpsNny^EtnKwJ0R{J5aFX=JDDg&7>DoM?RWi_W(b6VM#wi%t< zK3wOa3D}GBZdy|L1uv;@*7Dm4+1|w4H8k_--Z6NSoO{UdVSS2V_pIgqznTeSU)Mj2 zU$8-@3k_s1tHbf}%GfV-`SW*Lw2Un)Y*1??XEg;H2Q_DcL{i@I)yqIr6Tr+QOUs?x zxevcBPsc(F+XqbYccV{#{S`f70f-+K$Ju*}i2?1$1#?TK1q<)Mxmi%Yy)3Sk({hf=Pi+oUE$~TP6_u#N z>_9vo$B1*HBKH=6ZSo(J)O6Ov2vit zx}+O#`l>qe;MkyNpl9bXb8I;5JnApKM9)70`Y;cu?=7C>Iv|kor0};U(1_uj+5>tb zdBJyLVvkxVWgiZ0&`e;>NDJ5}IwrVpGUKV%k7`z8nq_=b3`9VIN* z1J{AYdqh81ja|EHG<#AFu5LYNr?FcSg~P=FI|}dYExfI(q^_N|oMUtk>!3-mml}}! zG3roz?DgHV4|R=MQbsPwr9IzErXGs6dO~DP9C#66Bs!yYS?E%!~vSh_9C)W)OUZ8CGS{XHPuJfZ|UueA!Lp*G*#8eBsH8X-_|n$448 zIm51|Xm!0Jcwo=q03vr2g|dm7Hr<+V!&NBEP-`8$Z=Ona&7&@4yEO;28XUEHX|sbdcv z4C$J{9|Enkb?;g)zpKC*$gLl3gRpc1E>~j|v+9iZ(tbi>*7Z}O^VY=~sSf^R66Rmj z3!VjcyGp0*-@7N^;AvoHAc*&QIl<#2<%laJ;)Vxp2=TG8sr?RqQ$x0h{gF4Wm4EP6 zHrT=XE@ORX{Ua#`ZY>0ZXZqpz-h-d37G&+_aHS&ypFfRMO!NwHtmQ=&lxjZxQ5{|& z6I~#!^VMeF*)yhq)1Tc)8a#jj#hAQyQ!}&-@#$gusgLCa$R$T|^=hCG4(8uc`Knc& z-bYpHvL{z8J6t?aK4-bW4}z@{3z+Ej(2^k~WZ@x3hZd^BNB%7goD)0mSfPr&D@Vo6 z%ikr-&vLsk>@V68KpAFSX^6jZTWapP`f5wcrC~@`&cr$0kziSwlrxE}j}bA-7XB~b zO|awqs4=i*1(;LI-eU~mE0a+rdBX7s9-~!a903ZRcPVZhUo)(hfe$FI%TrYm?D2 zMM^{w8Jn#{NyXeQT9A1`uLpn+ZBVB>FBPSpO8Z%5Ih>xWMP5*rr`!1mpja(;4`2j) zSJk}w4x4s>>aj$W{P?GtNkTrl^d$ExX${8J|HL~_D&~&vxR$Y=zZe4`h}t$-gC&qusU?yH2`HUEquGi zaN*1RPf?5~BFdk{hpZ$Tcx>5}-pmj+l=rwIIKY12%c%ExQn&4^bd5DE^Gu#UIH_b| zr84NDPFiyl(lcAtta_cOjrh{~Hz> zt=12IP2H0uA86i3?R!G;#9@O3M59{NbC!SKq>9ZK3nECmBI2ub8e6S~zOD4RQ-F%|9~_#@p8<}D`coh8EH$vM z7Eb(awjY&eyYIKNU?e!8<)SJ%o;N}Y`auO}8!%=AXbMMyen{eY2gl;@buf!20Lr5oHptD|+wxWKdFG4ug?0 zEk}Y==nePd1LV)6JuK*XfzdgR?^z2EB<|T|G1>}P_dgxE^Um|Dh((0g+o~$^OU8gW zIt~ZFR_5g8seufUI|!MZBy2w=&&P$|3LemOJ{np%ulI0y~q5+5dM@b6%p@{ zs%0rrW*ng+(0I=~f3nL?$1YstgZ0jT$no|buZmR3Fx`Q|*z}^wEH|4~*Oyf3zX%RF zwB@eb|Ej2vsj3p7<_CW?FkMT}v-~8>F%gsjde3FY#-$tnBQ0z!`Rc(^WR`sOVTG~H zEb-qysLN}Ek&7^ssJ+u*BN@?}Yqc%7)UyvvKlGlQ&~$N6dLvj}T^P;D4(^ZOACo)` zvfQZ0X9=NM9g%mi>$hMNUe@I;RMr7!?uUY9JX_oUxDeh-b}*)@`m-k>h@YR_uUdSD zNWT1r8DXOS+zJuC#Kdn2olr+*xa39 za2tC~r8L2)K%(~|)mVK!6HD61cuBqJwsJOpx(a>ZJo9vQKt3Sul_J~Y@``dQ>ZtUD z_;|aBTV&RzuDHK8h#LRK{kmVTQx-8g^|Sife?wsU*yB}}$_R?DiF+1DANj+@-YqyX z7b<&zIj~j2E1!fZK7@cV%?Z{kIDi}Q~J!8A0V+&4Am13v}*#mH2$UN5K5socF@ zyk~96uT;g|^Gb$+8}3)pd7(WiTRV|opxXp?5Hh}9Zygc0cM!+3@~Y7KJqhrf|F==hmb#W?+vPi;^dF$4x&>vNkskI<9<4J85 z^w9s(HdrAmEpX7vc>dq)wL+H~bzlK9#*ZOh?O|)IN1ymVip}c=MBD^%+j{QX<4o6V zO(mJg|8~JA&QG}on6CpPN{V*o=a*!bKs7Bwn8$LX;7eGTZQjT{U3M` z;NS=vQKiZ(oYSJFr}rJiy*&HbRm*#0n`d7@ZWWCYEU1op%kdoi9E2z-m`e>l%tK~L zOcxe5FBvDUFBfW1(c>ydl}>PyK$&lSHw?v^txrq+-<(v9QSbzK2E7pky%(}Wp8t6s z$t5uzn8&Boi;^;BT7rNwi|9B7MFAx4X% z+-FKWay<;6%wppdPKe%l(v(HraUNJ)vmxJ}i};o< z+jw7of%+JO0i*(~Jkf=e_a;aCB23HIYnbX8Dh zPGM2%^xRcE*Ad`Yy}s)rm*0jZ9{n8j>clu3S2xAs!vWYu2d5U=48r9fXHAr<+x)z! z);qc12;Dcv)gtda^PhAtC!67BOlsD~2K9OiU818>Oy9P=!E>+?_-Y-H?7#~>F*%cS zYr|IugxP6kox(dGdk^9Qz&8AOUD8{&X|IhdlZ#eJnMYJa9Hr|dWB^0NlTjbHO4B%$R%QuGBaU-muK8R3Y9%c0R z|MKRPREB(bP>+|hcsNOrZaV?kFx3Y;J_oYFY3{yff%>wpO5ZtaK(*5Lsn5K?4N8EE z9nu<%Iltaz8p;p=WModjAuA;zACriDuq)k>BYyBd@8e93wS%9|Z7%KWFax4?UNsjP z&v4h4_hz0nQ!YPL(=h04aF%4ss%T6KdwCPdr-meZnD7c00gDHFmn}@RqWuX80 z^vb433y*3f?R|#ouO2m;g>VK$7UZn=@i%|ZSLS`=OXY~o274SN+OK*p-L2#hGBOY* zZ|nL-`&;f`rC<%7e-o`j+qiIUBTt0;3enCI(TGV}y9$maX2Ri^`UJYoFBBj;Mft-DcHXe?l zi(qGTfK9$_a=x|}h2mlWE)&Gm`C>r*r2gV0zkprTo2!092+CxroH3}Tav(G%tl{f+ zcmu#(GwP_{a5cNN=>ka-K%eG1J%+Crh)z(~czHCwGbFjJ6pUfWkX!2O0JR)`qy5tc zHvkpHk=-}uOeuwY+iCk)nH4WQg&Q~C8h|Uw9hKDoW-^3nfccK+HvmocQt4VI5;cu+ z_v@94a^)n{uYYh@4woBT-Ams_v~DHLGWL2J_}H^RYk$tewPX`6Ov1SE3MUv}dz{U8 z7$>!WfF-GK;%uzT#Kno6fg6>s8}yC;mk6<>qjUY5+tA!k>;;ym-0CWmZ5Q`@KUt+5GQ9Dz zF^Dj~99X@n!`zuVj92Db#?qMvOorpyY9`PoQQi?#8eaqHru9ZJFIz#}!kpDqb)xLp zuvIl5UflAImS}|I)VhmloFI>{{KZv%Yh_QS({T$C`u)U9+8M~nszn2SdAqkh)JhZ8 zoXs4Cp3;uOY`C6W(u-MCVH}b-Q%%6~3&cTadzR{9XAG}Q7L!AVe@Ly;%g>Zf%zcKjw zQPBOhZ^S|NmDfWJ^cC6BhBy0OQ0hd{5Ii+!_iGLjUgGCmvMtX#uY(@zcu zFH182wenVSG{66Fvr6!L zVmCW1iPhfYP_8p%-gKJ%es=rz+tVvwpzm`CNzzOtYkDiy@29@D*Z;_Sx>i!r=hk9v z^u7TAslcQ~xS>lFf%-_@Mqi5MlZT?k7i4w{4POC*9wfjWLr!KVHl`x5Q6@uZTA;<} zWL7q#)N2*(37I4Br>HU${ZNACE7&IYhFa%>d*8srN{WMKhM#)UsE}bP0uX7sxj&h%t z+2%netZ*azq<(;|z4X*k_GIUlTt?~Micarn^40t&{WUrd??S36vpJ&^9JBf^dVl&Du>}Cf)i=nr6F+$bbLn(aveD5G< zA^^dt)&VQr@`u}#X;GDwVko(V>!Hm{VZW5BTB;8NeKAA*Il}=bwI&z)`wRn?Y$syp z+kysY>YZz(xebyKha!hKQUAK3eRY3-xPtQsyIACbnnS4vWV-xMN?xr>J+Bbxb!rE*rh+HW^_)T+zyYzd!Cw41$OX!IBeIPulHg1#L##Cv&hf z>i9pqtuZzJThrmRp)gudE34t+3!0pyQ-%B8_!}dL&=wgfTLWQ6X(|1b-P7d^7DEzP2#6;-)&5@Si=O9;j+(> z6A>Pj@Ck8v!Yd^ewG9)i#)e!Y{os6)54cId8?=eM>(=<4A*8gtD;|G-O|_!K>~{L9 z)8yp)lDV2wz1Ebi#Bj+ew=Kv0tOp*Lr2ZtU8z)$9-Uf+y^r?t4hqR0-DG%Wb%hlYG z$$!yJmC$_xHA!w#r4h*FCO4_&DXqF~cK|#$8iiT3d3G8OUsdudgKCC`NepBvF*Kzx+o7^03pA!MG>+8ke|e<5Fspd-ZpY8yyudPblcxqGXW~ytXWeWy^`F2OcI! zWg{$=>%kumx15CXxscs+<*U`!wbOpubzCyVy&+`R{m?wui)ips>a+D5wOkkJVy+px z6ooWA1SK@;wz^X~y`@R9&u`2gy-UFgA*1s%l)QzC87F4-Hn0b<@x+f;TpS)$a51L) zXDpRDYxKr&-JOA>vIfF8UQmh3Vt%9ZCQ&~af%ls(^YO)jn&#Q~{ewa1 zAm%f}N!^-DWraj5ITA1M4#s%s)$WVqNOGqvu0FUs6I05%D2qUSiNj?KiMUNqwqE-h z8m1s(Kf03{#T>NB$2+?5>@mdR6G!{@Q>Wd&FU|`jcb~YqEB+{cFcfOngXGT{^YBZ0 zm2PY7UHay*CPal>+H!RL!`gYR^H3H;(9RYQKKj~E=~I46W&Wmnq@EDT+L@WX`qOjx zi5v2KPH+a3POtBgYhr5BuH6*fwC^sc)>N%ye~hF#b&9Jj&ggAwnFJp8%*&!J)1J@X zj+`ixw_XW$#O@LYO*SM?c1?8)KhqN&9SNXO+YEZw3fT=#qp z{iGmb?Au2pxPEk}`wxsn^zKL#pVFxEbI9#b%h>(M&1-fCIoI9tngV?~%6pQU%1Tyw z&L&(9cF!E|!{{ybiD(FN2|GVJjVzDUZx9!|T5J_xl(U((CaYTJ*jg1=j5dg3mexC9 zffJ{$xfKy)6c14o#TjsUf`v@!oC#zZ1hZfJ`oZ0%XxNfkE~U=etNYl5GrBnGqt{Jj zSMaD5`%Cn_%6H-A_0QZs1+<<_X7|pc-%noViQPmZ=Oa!(q6p(%Q}Y%(@7qq_*k=>x zRUROB0oeNcL;UCL6W=D$o_r6bEyCa+qL}Mrq3TF+^Qno3)40{JUjx>d$q{g>)cb9Y zKpIuOmyXl0`oY-qS-Y(=mg>+P2>k-~$5w^%178!1d#Ke!+n}S3%!X!5SL(yCbcD5c zST67J2;{qtOEh}+=5-|BXZ9O}coFUakDK(9)PoQa`1B2%VUAE z+;r|@3kyA^go%HqxGMgwR~0Y%NfL0OcZCLQKbNt%yDCa7b8rX!*1@5<>QnUv5ssQt z9|7)l0U!Nq{e+=b$7ocdGP>-nKD5X$$u3pZGR9J$3)?rDkTW*owdVu7IZ%o3<*@J7 zv>J=?!EcP6;Q|AXBrp0Y19g zX#4m?yxtt#aHRx>oYHXvhGZ>D(^J~N({tUI_SXI$UeQkR&NH#@uQxNLx463~&5qK) z+4nUrlW#424h3KKQ*bxKUB-g0v+t+IBGNXIVtaYyBTE0af0ja@ZUiO!xlXhg6i@U0 z-U{*%z?{|gEE4+|J@K0-kGJ3IB0)y^a}>%0X2 zCne(<2!SeOc!6a<$BdZObhscM;ama~v2R(p3Q@WOm-XZFPT0y1aoEU?aa`0jH?h3M z7jus7=N6(In#uJ3B6ctAxE_!U@XYvnOf+@)ZP1tSps)A|i5T2VLcY3MkMAjhF!kH4 zl;PIEPKHOV-(kBrsWZyq_oUJG!0fIE8Ii>q_ucQydsd9!H23z=$L>v^STcba7~ls?n|c$Ri!3%Z$TC)xduwP-9UT9~ z2rcXMu3}Dgg*;M^X$iQ#U+W#dhF1>P2I-Dxjrj=eRL3rC)7{$QzxRtu!<8;~QJ8*$ z73ryl8{D;%C*(E|#~)++FH0Jq2}0ySny+W2u99R}|LCCiw-l{U7)p8NJOmE%lJ{Ts zJG#Lb%kGA&6tW`*8j5OBT5{Kn+Qs7MZ)A1Eez(r16U|?39wlDgpH>q4R_#h!zusKh zaOh^?7ZANk3CgoEh5Cra{&FPb`&WK~-{*`KIVDEb0!OUmriquO<_HTB`;ncLs6|&X zus<9Bl&>wSTwhCht1pn3G@nIeo&)g#(QGt9X@%afU-+ND)UWwJ>3DS;=j_#($G1(& z3ZyrWmSsm|99+BHFw3hTDRW;-Q^2(9TH2v(c{F*h56h|h-Q@)}|JH8r%%zdt+})Oh z7+$xa1qKt{nVCs8w<7(^mpU^pYQl9oXR(Hbegb)<3iXl-ux87fe5>wl@jVkceV9fVB@TrDSuD?fz*LBu>ZCM7ULJ^4q^`a>i+uE@ z$XZSX+`bywp?`K8ne@ZrQ!@1m4>()g(Zd?w>C=N?R?XN|)Ut+0BP*pZmizE0+Q7fw zLLO5JyG|zFFp@r>rYhq=+A?B3rF1qifac*`5+Ma*df^|1OIlXx_XMxv#lU?_Y`jX& z*u1LG?pr&l@oB{-N@>m@M!4Wb8BIH?iK>_Tn^_uaD#A6glN2=)=X#d2C`3Piti46` zd9$J&!YSTa=}ZYuYEkoX7Cqk+*O9wKl{}{8GTb91TO5=sJjEe;a&Dwh{xiCDVzOlT z!yJB*QO(2Y4!WdeFT)(r0ty{=-^$;$8pAB17kZUh-+9=|&y=5&)s%8p;a}cw-X0-^ zlyM_a%3TzoZ$S#(qKepm`kMDe|4kQqaDo}QPhK4%CvxXgU>UXdZXFz?o@74z=J30M(7!sXrzKJ=C88mJY8L9Z%6on1nBm+DUASH@HUh5l z9rNe~wVsQ@dO7!{+!6vZsK_!F>#tW+V>I>Rxds?89v%rHy$AA03HnZiL21}28Mko= zND?gqldrQGK@#t*@C+wE72G-^Dqkw1&dJpY`RySTnh4t-Pntn0hEJD&=+SIwa@-U; zP0c#3K<%z~{5*|A)3i@$l8D{jVi=w}?X%Q<<0=$<^kIB(%H{slTVr-SJV#HJ&7NK8 z*V4bl<|eV#mCJ{>jxxcUE->lD6oYI5kYjKXNe?4}3!?TGyp{s#< z&?tx!EXmsYVbFbxFjFh>!{Ky>it^mC`#lGg2PEGZYc@p<-N!K`g=)gh)0HQd{-M$E z#=@ovYK^4eBNx>op5o@AaKien()7rEuMPVjrFTKWtEIMs)8X4$q?p8}{bYjRgl4hR z3l=U~6n3|Zuy~k!&HLx&_WI%ADwe(Ygx&-x#GwE+5xF(8^F69J@aH|NVnNO_Ug>^< zSShM>=0r}F6nX}$SjV?V7OM|2qk>^(r!%)kl#(>H-s%&1Ga708)t()v5sWA%d1)%N zSX!a52aChj{{r%u0?^gzCOR0_1+rHVq89WB^x&U~IBip7{c8EH_YS@ipnyFqKlF); zozX5{?-(q)G4)1!g7NJk>;e&X zYU|wB<~lJR-ZN)`d#TJ9df01v2ChHzS@@1K%g0ZWid(vc2c;ifE_%|MCsO=0cp-}G zG?;_l5{VmbtE0le86R<~lk0_cald=Wyzr7shT&WNFHP63+KF2ZUA>kq?J8rt<)gfw zK1C+kFtQ&ypizqEFTO{b9e^uX2=({@F5{G*|L?gPyU`sJ(&mSGqBiC#Gqf+xvX#26G_%FPR;V5w?9XG$4!)@l2T zZf2O9w#ljROGAzfYD#6m@dry^!0p?&e7cLw^z2B_{3^J%hDgcqPC`_LYvXki%Kj5D zpc0Ums9YmiY|^8 z!*a$na?JmP_0qTedvwa%r#>-w402d^JnR{nr1N&|PPw)7uG2C#*nl|E$JFfmrr}P?{UUv@r7gKTT%nnXq6v~P^*y8GBC2S3|#wi z?*X(nRrOf?WMezAi98%%g^Vh7Ch_J(GC?QvE6M0mY;Ur3fBAU!5dV#qi)X!=9vFn2 zpk?Zguh0pdQNVzxUvf~oO0)X~&1B5HczhP`f!nyp?i%OW_=FNB3q(|zLIl66F?XH5 zzm{K1(G%k*cjRoA?*|C68PJ^Vj)zH1B4}u0wF1Go@!ql^h2)^3BAb)Lw|_&W6+|TT zwJJv$xUt#$HnwMf{w7cfC!?*qAo~ew8Sijow`3*c6nCh8`dxf-pYJwf9d!d0LfhV^ zOr|p{D5M8hKbv6`Q-JHEO3`lgM&}HOXkS!%dT$0sR>qtZ!at~b;dAohBXXInWXt1r zdKPawqnE!9WVKxIqz>ul0Is?k$dg7C+V8l&p+#F1b$U2uSCPKDKTuH`4Jo;-%`gVg zmXwZMR5!c(-8wlHd5rxoI4;<;+7fU?OtgaJ1NT6)i-mIj(%&cmc568QE%~ASbWD`4;@@O(jiFXt+q9;c6>BFL0#xDCV% zHXC=YHbnN_=y3Vh+$B(V)O8V~`?Rc4&S_cm@uT80Q0WHoossuysXo+}N4T-=|6%W~ z|Dyh$_|e720L37rL=b5tB$fpf>5^_%q(QnH6-4Pq8YP$R*rf!KSUQCzq`SNCS@iAu z{rTSec-%kW-tz;o`#L>m&dhV>HKT|mQJD%MiD%MYy63YEb`b&z43}Ay)pb!^z|>nO zCC@TimOw2cE8&)rc5!C(wIPISeUdIcGN@&1p6Tez{0t?1jC~%D!PHj1HJ;Mr9}O&~ z%?7uK+cZo!bGc#Ln@en&Gl$+uyyYr=RW~OsX2Om#BZ*U6D>ydkn9f;6Me8-ufVvTYX%kS6}Lk ziifK{NS#c_m|?pj@}GQX(d1tX*E2CHLD){)^DYrj_Vs@;Jp0mwcN6uEcZ)Q@Fz~zm zOyc8JLf03ijvX9#Uu~@~kI_HyC>lwydlPUpyUYI&@18c4vCgsyvuKaLG3GR^DM}?T zZ|CpmmnC&Z!G;~miyP9pZcgcz+bJ(q9i1|w?(NnoO}^sLB+$y>&wMcNYu-%oZ1 zTwhlY+aHTAKgA1TB`q~#WR5yr_0b;~y@$$UuebYfrqx}KifMWpeNU6F(Mwsv$u<$O z6FzGV;Ac_#t0VF=c76ks*h2&OvhX)CP4)LA?i!+$RO70vaw>i<@0Ob2l$fe(DWf*o zh;zC=?NAUQ}F3JQ|V8pOKR(QpBVsZ*N7=b zA1ORs)U&qCk@By!$c#4T)>i%%DW9j&vY{paIv%^udU>U<6xD^Etk3h@gz4?&Eby`G zl{w@tZMB9RJ6-rigaR;w@kk9&k=^$KB=y#bd!+H*o)HByuauwiI2|R`Xs<8t$y7|dY!iUV27Vkz4=Y^o%2c=he{PYqHkxSd8EU1lH ziT6Hc@DR75SbK?D6^k;oMCHbmY+jge_c>G$b_DpcCr(wv`?Z^CwDP>}$f+VtZ0tTy zx!0Pu=~5rxgy4?n^cM)Xy#55o+wyLl&)+32!!JwF>L2XQuKqBGU4%=rLd&l>%vV>* z{MDB&rQSX1DGL;R}a{|M>tEUlLXdtb?hl>DLAI3B6IDxH9) zb29fSkHd4Zu)fg&Q*Lw1U(UzKjJ#~oi6`T|HbSDQL9tj&5|e70B$EO}SkD3pp@%mL zIbptyc3%vZY4HNWCzNSO7K;t-O_Sn{XzR>I(9pEmjMB-Su>m-8Y9D9!j&Wh&ae{8j zDEmk*P6ZWt&`)%7qplpvqic}1Nx;Jncd`|S>bj^%bztyO+W^2FPv3-DicXwc#Z{u&z))yCOcma@r#KcR3e>LJ+OeCD*obL?Yn;%r$l_vgN?W<>?2#i!A3giS}aV4)H6OYc}oeQd|-^IC*tbJ$=Z8$*K= z%`6;190g~c8Ci)eE0V5U5B$#4Z{ESSYae4%skJfbZe=ghKyz#Hqc6L830eOa&P7Xm zk?(X~3!oBF?8HHhnvdvfJco%nTghSLcwzh?yI76q?ay&}{b=SMi^s(~GZzMSe;>>& zD(2}F2nmL(@8p8pf00Fl5?-~#*i$cf>%(OJUmGYU3{E{=Qnd6GJEpVZ`OS0?^^EEZ z9?ES3_xAJ`4`hqEu4UZJ^(~Wq!gfxkD*99*-WZ2yth?Rs;`yy}iHX=NtLE^Cs;BN1 zwtWMc`z&Q1%-hnl79+F|JYG+_|MM^eay~ga*1$r1Y;Twf8e88a0#DMNEnDOk|2$oPjkFuh;lo(dlMt16xVyu(^Z%kJOwe+iic- zDMON0IZS(6rO7x8o}Zk2Xqd=%A)?1t>3*FzY}a$~at*HC>bc+UYiErod2r}Tj?o^q z-|vVjB*>fB$+-C;87`B+BVK)++K@&|@W$d!4NFN7cKd%9&r##jG-8eJF%RQ{_-{IM zw>~6~<(6CKy3R}@j<52@*o$*_{_!X~tH9PJC0$fP-8RhOQolxdz0uQkbJK6CxIzKU zb-5PrlW=|7ncQ&pFlD@faSVdSxIZoW{s(*=?n_I#vCQFC`rh_X@&McYnKRMp?8)G- zYB2^T66~c=i^^Ja-MyP1bZbqrB&Tv?0eyvt)f!stoZYm)n-yl~XzLDLsoZ}a&0XEQ z#j1Iw{>fv*HUV{WE&I~>PgR2+KqmRmnp?*j7{+{|F)p>=IZBqsum8kK`rdw|TOnKb z?fj<;uE2h*Zur}44%@z<`GOImsHlj#t(QZiz6ne+xZG|~ZKHW}_H)9=8YkH(i{GY2 z?8B5%M#?i5gSyVI4Z&1(roh0PhSwuD^|9AV-fZZR9eMx1Ad3EMD)5@q~!#&p;mv~0NRK1tA1FGdB1V$J>i#2~>+ zss!<|cx8;f>m};9ZTzgxpg8-JwjZG!?1$gXqJ9#Sh=3^LA2ihpR921;8rTYu9CCC1 zlBV^_pG3}mI%B41wSx6IuJuSs6+JmqkqoA3v{6AJfW7EENiEfMx5PBaYkoG|o$UI! zw__3J$oP8qFZp=B`9iF!QEv~utsv~}WW8!eh>0c+B(1Z&9y{1$x+KU)cMtbto=$Av zg4CU}uCPBmpXBu<+#$JfC=Fkt)GT5nRr4ArQZ`I*40l~Mr2vOpEWhobk+MV_nDwdgOzNOY_s0G9 zqM|4Mc%Xw@DsFEQhF!Ox0|?WOL*jo4B*&&iH{((dMXaGS(GAeS>*_T`&lEB> z9hlZ@Raj0UdH+LEKQ6VEb1X`9UzaLk^=Agn%at)hHJIUijax5x)pu@w{CnVEwRXOd zWY48;tL8XgKPN;KcxyKvoKE0e!BzEwvOV;7w07(?iIzEfB=GAvH@lavC5K_1J8D06 zIgFSA0hD2M*o2;HUsy?A-Oc|$`nHAuJ>Ry!v7H3_-(vmiN%u~s(34fTl*^m{LGU4)|K-*+2BlPZ2nllpDuMdr6fDa zM|=!dmJU0bu=)@4x?c6lCApY$g%uX^wT^H9+WU$ zwnIq^FAa|KN}f5EpLI*b7=I(Ts4h$)=@)GA=e{84QTV$DU_k7DrV|+iB zl}kuu20rE3z~XC6fM zarSQbf2ww(fSC%f4zLx(N6j+Zx5LOK#vY+kur;4II~B5~s(s*`RbF3P=;T#-zis`~ zA$U3CsM@W&s~EjSfaUg@Wm|W8gq}VCwYG+!6ip5*9x`~v2h!ed-~SR(Cu-&JeGmgf zILf^GWqXWAF@h2U_;l+K=2zG%-&*C7o!PTutY_5`eI-0&lF?XF*#NVM(5_%s=clYND z@j@rls5YX55~;_IfJ`Cu6v)`hjz<+G8$qYYx-EjM=tp954R`+KFM`bTMx!(*{cdSd zYrAlDMiou&fvw=>EA=6qqa)>_D@WjX>u41rs3WCWGWmvh31j}$C+{T-l?4b(w^s=sog$FQE+=o zmcJUe+VNj2e4U4&RJr-#Ap`8dXLstb#xwYat!Di%iPwur=yC&z(yCc?S8a4Fr^}!%TeX^uA77|GmZ*x@!$LPM*=`9 zM0=RQ!IP#L2YkCJ2i^V@HpNzFIpr0lVjkr}?kcy#SsLy85j`0(;oBVA$av=XkKHfN zCp6hb-(npk83{P!}yQd;9H?6lr z@K?|wnzprA3rrgU;uS}PmtQ;ovq+D1O**C)uDjqI@XR#}NjYgT)Rlh5~XpyMg37w0I=fWs@-T^(Q7{F`sz9+g{y+=?_5h`Qp z#LB7MHwV3d`xNJ3Nm+wp zxR5VHy4W-0fcd}I(=V|rXN)SUPeM2baGB|>fjAn!j?d=wf(D?zQ)#%dW zCLFz{V@!PPbW#65`yO%=uh_RHRfg(|Js7~u?M=`|0*!f8kD@04XU_iss0l_g-QuUR z1wHQQR|(JnHFMB_;y)9Bu#&z8IkGf%#PXAy6$uQ;G;~=$xi7>u12hYWFP&}ggHDy) zPcU3G_xxfdp6fW}+=-OFjws7qV(eTi1vg#K^Ob3vB1v~T-)aW7+lar4_!v;CE7PnxbLVj!j; z1>g4U_QvK|HI2)C*R;@JfK6T0=d|ZOGoWBw@T~Xq8lvt*%052j&IbsgW$BRag;40{KaGbXMFn&{~5Mz$V(LNw^(VK=?@IDWrpve@puY2 zmjG@vm#%fFJ{47?K_{E7YDiCqUG>LVcOA69{L7rCN{xQ9yzQ?dSTX{QqX|1gI^3+^ zN=3gkr?2eMLm*1If!RUV%jSg|!d=D`+y1k1!R%j=q|TTV{|9@a zMFvfUlCmMdPRMol6%hT;3+c7ZxNUTXG3YmFXh_q5TV3j^L?%sMe%-%RQwaQ7sBqv_ zUhnx8#IdI7ij~5PY``p=cJ8`Bo#m^KIYar4+Wg1U5g2KjhGn|&cirm~Oo*p{`Hg1* z)6afNoH6%LB1dVV*6r_%cdX~qTVwR-Yn#CQKQs?99ZnS(4m9%J1Ec2gPKy-x+`RH+Oe8VhY1r(E(R6m1e;LXrHJoy$-??oS;iO|+KxD*%-XpZM0oz^kX}eK-k zWs6MqzFfXh`DT_(u?v&TL5RQN<8>Lndj;p$UWyjIc*n1>Y%=PvzVC(mP3b|0@}F3d9#=c%AzM;R8BWU#{=f&8g5J z69~V;3@O()#kU0ja3V^5T~JQud)ko|JC(x;l`cuItg~)r$;dYhfX4l2iRUue$&2bO zZhWf;r*?UM%SmB+(lC)SD$eFzxu%T5#UJE=`mP%pEd<}SFpIcrVIEO7u*}w%z&A?Z z(qGB0RRDk<3`^hFU_eBT;)Ei{Qt0gKbE08`p zGN2;zFq|Y;SZUCljgg !uG)&5Ux}Z)&x+Tv2E6kB&Gcw!c zq*dG=;+_C<3q^dU4~7AT_~cE8dm@?dV!^>NuR>dE7@W$pF zwDYY$M&VCg#kQN{?vY34Ys!5xnkLjiqQV@cvQbGh(Qm1V|J!ba9b{m(5%uG)SEv{D z%LI6(;;jo5?c%gj#n{b}jgvFY6kGuZ*;>$#g)%Sie=oU3RkE>A z;d?+^4Uf9_S;KP}By5{X`Vonzwt1rMva=V{c8Ha6KJBh2o=b-c+zNK7v{zlR)-ZHP z;MO9y`75t<#yT=m6&U^GeP{pEtm6ppGBx>)Xcy9$p7CHOc9Z3*8rirf-^^7a2%|M{ zQXXEvOj)2hobaUDIm}LVwxr*x3D(Ho89hZ3j^gVdZ;>qKq;_y=SZ=<3nZ4y7roxk? zu)7uLMU$)JpxE)?Q$rnrpVyK-+`u`#2Ua~x4ricM_qjAitLB5A<|sSI4TKE{F=y$X z{-RGnp?*5(Mh{A`Jcd7i#|N+&D{ff-pcw^8@M7U2UXKGWpK{v)&Wh#FaiqI{y*V`7 zz*#HyDCr+Eyspg_SK2`mt7aI`L2xT3;r4dBqvk~Xtxt_#yN$_^*%g<@hRRH>s+bHs zS_K`4Wq8a@BBTT|B?5cui?dp;0SosQA;`4uK3I)v#sdx&)rX$F%e#Xwsqa%h_+}>sgacjfo^Z91h13VIlGc8_BKo>}=w5i_j%V>+cD)J4&8*B6 zO4+6iB?=tc4G@{^=P_YHC-8}8J5!TL4wK)XvtIs(bW+N-WSTe2zfYFp9cH`jek;Q8 zqrS(^MgnY|j)5+C<8@xR#_|S1UY{)KT^jElwbg5{Y_Z9s{uVv5be_M`8JHyJ?__Cz zzE=ZR%HKyJ!FK=um;aw#1d*xJ^KVk!jE!kt$Y4oATv+Bs?(ny<_`+w1||v9(Cj_s1$_94k?@G^hd}CMGB;X7fit$%6h9HdqQgO z0nNZ7{eIWC+mK()T(bA?5v<&Cs)#meDR&pyV;|9EwJFbKWTQwYg$f3NTETPHwDCP= z<1!(z8EUQ6dxqr-dN+8Vt5}A)aoa>*2gCVY2*_|`A%apu2eXJLLVjD1hqLE}&f-^4 z^DFEo@XjE*9+_hoEohD2s*)YR~*klUdM1h zb%qocKi1H4-VuXIyb;A?VFLkrO)A>+e4>;yf=UPGL*)OYEGl_@%fk~BfuN}Fj`u&(e3y&197wu<{RF>2m( z2@ubW6jZ8>(~j@RWjlSIlMHvH1jPV<`LlSCFz?6oeUO^f+}$PBn?3R4iD4)F*j{ps=duL;rG+mM@m zDG$*gE5=H^(&d;wAB^cXXIka3)OPZq?$%!w7yG=R%1yBPFR0N)`1I($hdnNdiuX^M z;ad7frd(EU5V`-;w5_m+p=WN$i$@(!f+`X>NZh{WLXuoYY#J_b>T3$X*rE(if0$W- zg~V=Ns_>w*9&)bTApkFNM1N-Ltx5kDHtr1{r|YY?)&0YfZY6Cdn>)_i6AKb01yse! zM$|<$PZhQ7+>O$^M5B~4Qcs6-MBRjTHvJLrdz&6y%uJ!A)zf}|h@@rBBgob&a8Epu z+6~+1aciN}&3%t~mAEKSSzM(N!~(G`%c5riWX}FW{nQ7?Gq!Ls5|LdmvJisM+0Rq# zSuotn*qxR=4Qzp)xJK~2@@i>n=E_~n$dLz;;j(^kxn~WP=CSAcQ5TK9RN`KwrFZ%H zgucl3W3@73hs7adr$gZ7jXc;_-b|NOL-;Hy+P?Q_#uc{U#wM_zuKm?oL{=%9=Dm{0 zmx|ZVK)%3*pEU|4<{DWf+Lf4cW~17p5+vL9H2<9h7rz#m!ORz3%-~DiH?ln%9`Z~S zm9I4kCBG4?WG;m?B3cVK@;Bk;S;=YgoHd7B9c8oL!-nlY=ieTZl3HuG>^Sr;KbfgA z?h8xkXnO(8b5>X>FhmTC&t_yl6TL9QW{I~ri~FGCE*aU)sR+bjE` zsYsV;b33&EmxY<0mhF;e-I=;J6J7me^(PjUF{FgyRm1^Q?bwi z0|n_8k3$#jB95*&KB7C9An2-xYct^|$-21X%gX!wB(zS$>7eN!W&+0d;c{!+ii38qX>Ih4{FTzGjyMpXAGW*(sEV`3l z`dP%16uMcM4dt!u9g8|o1&kfvDY=a4rGSr&L&FbzYIn$US4E%4mN5<68dZPT>QLBZ z5qLCJFfLNPS`mTjz0I=PIRFuS{oog_7n+ZP=uCy@m+(SFZmx-$UhPjN$FRS ztudm^jenhp5SLuIx|mRT(0PQmqUSv|)WJ;ls;`%3YPfondxx&UM|(G)pM%R-*GOk2 zY}`EwwbVXA5Kdx=7` z&-id;cXALG4!8!FKRZrkP+@)CZne1d-oMUPFVff@2(oXu<6GvIG&K|xza=cc3*YVq%l?Ne< z!!9tHLW=#K?EMJL8`teG<%tY&9k4F)foB9ujC%)4PZA%#(}Ty1o?Lq-3z>UxfiDan zFlS&6+fFs94Wk*tNx6ud2XkxuBof?C{3`5Kye3Ox6iu^E=&vtDP(w?n9m+EOAzCuE zG&WnZJdIg$ecQpU+s=Fjil30CqZg8Ir^VZzEcqIZtq$|gSI;*dt&&Z;2zZkc?(^g3 z9XvT=U3A~DX73BBZ)<$lI`}m<{l|5OtNYb{?W8(hsUU#;MA%FD`Ds7J_RnF@&ne3r z27NYi&2?;#KTzK)&c;z@l{}|EDAahrMOvmDPX$?V4Qy1XZt?AR`7sfN_yaJi9cR(HMZ-gi!X0x_7ajB}-Ibl&hfyW;$= zhlQ(0u#@(_OPiiyg35{wMTZr^2CUnd>t(dc9%YcjtS+qor1?p(?l|W#ogRGZb8H8p zmRrOhd@3mqaNOVx>f!yl8)1D(g_>>w(EZ8_7jT_o^rFq7^TT^7$)?GScdOHp!a-7O zL0Zv5xDM{ed!2_n5_LWUt~PJvj}{ibnbIP{Xs>rB?}-`8SH$NATh2-o2C~nzJndR6%vobplY-ShLZS^lPpYuRk)-c<2mHy&^5 zsGWTLbk-m``Gw<~rl%L6H9zY41crCVR8LOPWIu$F^2iXUwfh^4`zz~+2NXPNL6z4(5s zP@Z}(YHtg+pbmX;b>bgC3<<^rvG9e$T`q8=c-+gY`qvj3dw%4M*StW^W#2+>h@N|I zJ}#pcdbIDctjxt-hV)P8+H? z5XvXmtD!5WlVScU-Prrl2$<`0)$$_!O$jB`oOQ`*AR_ai+D54-#!&0M1`nJ^$U$6_ zlprOnHo-N>HE&qt7;dg)2IX4l_z*gsfMVb3D|GTMP;_LqoViC5UU0nmAgXq^#mtsg z?VU!u1+DJB35M_Dta@pE`?8Bm7$5U8hH{g3RtyLp#Dr=?m@E6s$5I}`AnW9=&qbyH zjH5?IK}X?*N=7c0sPi>^4czc4Zf@~fR+nBym~XD*ikrw@m-tMnRRajhK+Y$i?-4g! zUbUF+r0qsvox3NHr@WBoAH+z!%FB|j4Ptc1>1Yh@h@msk>kii(TCAdGKb^lOQwH`d za&dS^sr_x8jYa>%KQaJ_YKe{iLKQa4m&A~IDS%&21rnD69rw^8b#daP#qDJ}o;8O_ zfS`$`Ub{=wbF^g8_!NyKZB|s1MMs&U1(+E9H3|-skh)!>nG1qN)sKc# z4TBU3TZ!BsXE^ptXDOzfj!?g#N5^6sTq@zm+XxUmnR2TT)xQve5}VayRV6kP(9g9% z%^3}t7ZW&wATn8^E7}#iiV?TQcXtWMwTfLezB^e$X zcCgPQusW{j8t!v(vB&Y@T4juHnsss8ICI=Zf{+8A@XB+Bx1mkQLB{hc$w}xyU;xqu(vHdtM%FPlLplb6-hhL3kRHohU*N)`PwO`$dsDy{+ zDMDF{i)OTk+NZ;(*GM<*4oDo#8;8;EhCwl3C0I_ilCHu!Xlzwaw*ubMZ(xFV4*l)m zK;YcxkueW?fa})JM}ShW4!#hmKWK{*3)0xMI<;-uH}!f3cY8de+p(>A)zzX+$c8Fm z7XtD4f0Y5Wlk%j^7|PT=nof=O70!Z01xxIhyMXBPIdJQ$+)xTKKAelao4VMfI~JBe4qF#&g1?#NbF3Te4_3<+s*B_FltcWBwm z7(nIGUuN4#W#QRUmY2Rkg1b7TQ^c%2DH*#Dz?>m{chZRnt7zyL)se@;) zJ4iG!sh2B=-IPN*J$mO@A78iBX%d2211iq8?AXoz0{Mi8)V0LY<7yje#zy4|?QN># zG7om?$Y9X>nGfx$mnAodLV1ceQBp2I_CgkNRBh90dDF+)+5Ftc6fe-pelyu8neR5C zjeoZ(TlE5~A7KmiH6Z@W4+Y~mAvX-Cg5MQuIXjD;R_0F+mbuI2F*w}kzX504h)uuI z6Ty`(#V4f_IXk)sqL4fhtCm3;w$R9J#uGS`@w0BROr+YRd8t-~9=qy}Xu}Gdo`mVn zMh(|^iRjv$-tmAdq%!#NDFaFVbx5w;`UxwVZJ8kR;1da}M^2uk%1oQ&ua`vQh3}OI z9-vgm+mj*#m`9#n_U}|$XeK7BPI25EnuXc1hVRRS2d4+WN=&p&zwjjf%W{8?DW5m= zJpc&1BWO;&c#v0VpNW=D|5{8$Dba8G66t|hmE84LTpoShkpO~0mCvK17NPpx?k}9( zR&B&QYATQBj6v(oH{zM_lDZY)=Bo=B&k5;dY9rrIv#J8U+YL8zrT3&(Nn4&5?9tZ#Wa^dE3A)bJ;%J}fRK!T53 z&hE7D`*X7F^qYA$^gxUqbde;XG^(F$(eAFq^U3x`13yW^G1a)YinF?Z6i>m4hre(s zQ z;&QHWQ3>XoGx^J1OD$&X8orqb)ibD}XpQ1@zY=FczRt)5gKZy||IM{RxR}27xLkkI zLtFiYj2vGEqromBlC@Swvg|BN^N|M{Pph-DdMU{`>YwM4N9Gdp=%&xNP{pf_lzab3 zJdrk&Q4{cCy9>7O`AU-O@} zoy?D@`U2lFCh}*%9i!w~B$H82rV4v33zr%TUO*u!F?blsINM|08-m5FxNs5fd-DVz z_lmdWqX5l)ISze^h_@kLRRnOu3oSL?oz-5Y4Qx8Ffx?AnYUiH^nTkr!S?#tE8`#<> z6{8t(@jcRB8&&3P=xV8bWzwRUT1ue%f)Q)%C+>`xys08smL{(f**eiFuy6rFN%nJ$ zBEQDsY(CANDo-HtF}4ZAC3$i|l_7cX$k&qZU1-onP}poieF|ov862)R{tY?TrqWT* zq3<3+aZ$Wc)eiRcTa#`0b>|ZpqwpXSc6zEE-emDF_(G~<#x}?1bDY|WkP;S!{@W+e zv;*Xp^2eN_2e8wdOytBB7m2AfN&E@ab^N=J(mk-;TV%4|jrOx?C^Ph_a;8YNUVFW?KVEG}F^wP&?~c*q~CLu;wUp;76+k@(tAkQPJwk$9hwQYg&E z5>TQuvn<TPE8$Dqr}xhwQ{36($xpV1gf2eShdt10hQ?9*wenv=`FhR+Yai~ zl{{8bMusmzh)W5V^qlwUCxl{#1RL2}wiPBhj!?Y{Jp{(yoP%GbX3E};31q7pasQ&& zgOWT)A>`5hvG{CZaxndu_;*fZ>6hUvNgC`BN~Xcnfs(&OiXGL)TKCoMdY6GLc8|)1 z&S@YWkqo4xo(R=Lr6jm*_G-_;3AwZ*jW2_YF1C6@ypEx37p|LO1`x;wl?))_sT{6; zHqlJU)pA6v^FR=?@1hS^xlcN61S<)V$1zhC3P{VLX6w0%#)MSS$hd+YJN<<>W^8r4 z?qaM(&_H;bMf*V66+mVM{~@zy|95bRl0PZ|Ca+~Xa|O2Gj@9Agp#5`l~pd|8v z{6f>tiQy}k<0DGSc=h;aqY1pqkefjkt0<)#Mi~8GTK~sN!WBo-_dT0hay8Nl@$Mr; z(>_esEEM25oOfSOC_EK>^d%=|tQAjj)SU{QctVE7dYtt(P*vuKjNkH%d}l}VtQ$Kz zABGJa+KnbwbigRs7_gXuyXbrf;)JCP5s812D>{1PGsOXWb(GuV1Q+<-?68#{V;#1-gJj?&S_rh?qHmEQH)_P|mBHyvd`nFm)K$TGa0#(Iq$6UOWeIPZFy9 z;>F$m;*5&ToYTFdgSL{eUKP@}UH@WB=3l-!3PlxcDb?BlL~@~qnO_~~*d1dxT5b4F zZ=seOMKO!LCHUr@$(9#@eEXgUe)9Z=@o{fPI;nQH#HOnA4MDvNe9{P_HQQ?|C6zUr zeJmAPL6wrFp6MEE`CPn$$PWa%aT@CqUY_ZX0qme3^f^WJkxTl|!mLCkpd=HQu%1s! zUzF23Hg|4T-5AL|sJ6%mTwvMCaDZ)|xC7=D7f2=_9FEg$d(E-`X&J&Uap1n4QhSI= zvyK3}36?J+ygg|Nt^y7)QD91m{8Hag6jcV{B;wmmFd(Axu_ zHftRGd7bJYFg828{SC1L`d@T$IFeTD@vE6F+`JK^f3aKGY2L^J5VxK01OonIyB2W1 zM*d-JTmIqqFTy5*I)QTMJ@21ONK?G-h_sX0D&!~)!w_ITk+0o3ws6wYzvEr4JvZ<9 z%7Q{ z%)+IhWo*)U8lOjz+q~<0c3L*4VoLAo_}xeHkiSH_Gl%|W$^fccP%k7Vim>m z79TR7Lf7N${>E(9Vh}>vr5B0Uuhe0Jsg?n<;a;cT#I<{K^cBUcV_z5~0m!$QX=vN) zRTJ21b>Y2>ghjlH3_U9k*;enk7A7tT_e|#=5tNe;O z{@+_nkR+BnjU)ShGUNT~g0IR!6Cicb8ixBMV~rKz=p-GH%lN*0=(>I#tuBlmF4eUB9~<$Vq(~9Co7>(dA}f+ z(MjP{OQoxsV6|O;K1{sc&%wtoG8`|h!Dgj5dBxDS$o7MY&4yCfzCc(@CDn%|IR(W* zJ4vO%zK#Xc%Eg?`7R3HY&3sF!!_hvyX%jb$4di-B$bB6~X#^5)!PuHL0se{u10uUS zkOPfclHSt-+Vh-x4wkq3=cmcT#g>iNgi(h0>cHHP3HzBQ8hMS1QM`K1+YDJKM%ZyV zFMf*TYDt((V$dk7nl$l1hw4@LA5(7+*vBJJ*!iwtvGK09;&ky~yX8m|puE|;;5tc^ zZ>C*qBtA5v9f6MQT!VCnRNWRebur2yhjbne?YgG{>T4eBQ|hqRz=Hz21AY9i*O|#r zby^nnGALAKv7ZwV8#x#HO5VYPFX&J-c@U4qSEordmIQgk?{@5`k_$f??+KM8ms9fz zkdHnuGG{unJ?%6-)z8#VymALCc`;bTjA^7X_zmYqO}?Vl63{nC=W2*tehCpADy$I@ z1RDVgRs@2i(BWR=joM$yogRE&>VB)5dLMUkB+5AIP-~XJJv=v&U^HC6dHI19Vj9^{ zCat6rPl42PIt?Y&st7x_MJ|6$7K-$WQm;$J@}lZA7rw&cI?g@%2OTt<>E6rfUK%Vg zmy`mgQ@iypopG7@D+h~)0(}o5f(iy9xvF2u1YNHh9>2Kpx#nrEALD$$%jJl~xfUvP z0$TH8y#WDbc;}Z3ohd8K-4_eYW<|gXAMc{(Q-i06^fmPE103c>r#KHNB8(V)JZxkQ7-4M#bSu?j>3%O4wL*V_VQJNOH3$( zPfyCazi~PoNgV^@NlH{O%}~+YFRYUUWd#6#Jvlf{o%h(r3i(_dtTocy_G;gK9ATr$ zn7daUzBc0oC(B$xIe&HD9!Mu4L`?Hmz|!@fL^62TOhy5kD|?CSd&vTBf*Tb`O5lE| z^+1b{;sDd1pE~4?aX(q#x!o&l7|2@MAZ|W6YFK7#`j`+Bs-=*&?ICqdviSU*zS{f1 z&b#l1BbV{!@PW`3!IQDS>A(+&_P#?B3@uf>AQz1sq4mZ!>m@`Brug3p!9A z?`CqgXT2Zyp!}&Z8==sXNozNqYlj)C6+IP*>Sd~~<4j@Lq&a+aNUx)RxW0JW!-c<$ z@_MH0t&al{yS%e|Ifm_jSI%B_4^Hneu(9+kB+^&_YYKfXzPJ9t=V=Cv`GG78_1fN1 zjeS--Q4N=iqp`PXaB*2vr5J0EnR#XCY6K=2a}J`qM8=1i2fFzOJ-ii~u(Yz%uUVtC zTDS45Eu$9RT){st0^qv$k{;%^DN+XA4aF$0 zc31=-9nDp>8JByI&|0K%Q=y5EqtY>md|%}dwTdW>zrXc3&MRWMkwrd9p)^^4^D1C9 zlvV$ua$*k{0;Dnmp^Kfi66P-K|3FshjLs**;g^kveB`mC@cz!Q>|1LGA zztBnlmuee~W4CJ$nm0VlpD=kxydJ&llPVrljwyH8fK$epaW#~c3B6U)>u=$`fDt}sAS{1~#BZ&Y?Zsh@-2S4d-H zXY(h4be0v0O3PhLKYgixgH+#^?0V=+P0=>;zQT3=KCC-|Sw|DlIwIKJKP)~iUd7~+ zjP2#z`Y5G;(NGgnC`z8rhHg1;!^)j9nS6l&YO;GFP&DRUhkMXBOcs_1rq7AdZz*tG65KDN;s)qWmNcIc298FV^M#|We;0d_)j z<@*fx`_6QRjdN~hCJS>*il^DEr($2(A1c6}PT?kFHSl2P|G|54I;e%gtq5W&IdqN2 zDjK5(pDlh5p~+;WMW1OHKpVWscV8XT2Zb*9BcGanJeW*!2_OL#1Q*2nJZS;<0e_3p zm8hKuX($x32Ai>s0rp67czAAS_Zs$ZN;RxE0_a+Pq44s&1S0L}Jx1*35K67VF~a;B z_}M?r@4%S>w{*CCtnuQn!EUU~1xm1ajC#)Q#idn3?0UA46i+LKeI)hp|s#rd5IjiPdm!sU|>rM!~f%u*zkMq{ze8M-OKGQ^S=7ksR`g;UoJkrrLnf#`nat^lknU}B_11OYcO^1*TchBJ6 z%Ts@v75UR_3QJMW3aRZnc4GlZ>t(yjF-pppT%)IBfv$>ev&MwZ z-p6i`&EvBT7nAvCR0r8OnU73A$~oBEXCfaV|8%@CwOvz*PdVj=<8&tXLPGy+Ib9Z; zLpJE$IL+^DcOZ!NlY<&IhqyBr8A=|k6BF2-LVBBQ_*C!jMsF-(#~6D5 zH}%k=M-j0XM;x6mq8#mb_E% zGkU^)Ajk$lX7C%}%rmO!g1&sI-&9VAK0%J1{C=C7n&CHD%MY!@fea?SZ!i5r=Jbb) z?qG|t4FzZa>Dd^%`3U4BIvY1s*C6Vw+Wf2fuQU^eXW)%B=4typ%${sR#+__HsS z9h=$kB~qhT(e`Iw$Ojy6pU7Yi&;AMiPg}HLlrd@ceVI{je*1Mc%WBV}7mq0qCC*-0 z{r6ev=!ONqxa4gy#Bl&)4<4nP9 z{yK3o0SKI1&Y43Q+^h(sW>7O5Qch2Bbn-d5elu|pem^tKf6=hlS{qjOIx6$((KX1( zve)~LtgwX>liq2XiiNpv-hg{_iQQy#nX;lU%GLz1sWLIo{sFrL@Ha;U#=tU{{qU85 zJf$SMZGIg6JyhTrnrYcDyVcZN=#-l2ac~J{P5ZX}%?Wd47+0`11O@{jf;(J!j|A1sHSzFfT*Z+Nz^ z-HoGWt8)^FZOPmLrHy2uI8lDju?af!{UVI#sk<^VSRYTt!qrnQ!%qu;2#21!G|qLL zJ2^7iA+qb+*X?b-eTgUv3tx=5HC#AWgUo3|t+S^GcgWrVH$N}*5|`rLj;f9&TOON) z7Gj&wTcpK4P+^1ln-Q?rU$NNP8D`elG_2dvohZx((3YRv?iG`UM1(w}-MET~>zmht zZ&G_PJedAv6{@RjjksXNBLm(b)$@q2dFZoCc*ZsHut%XDU|J^YW(s`+K@=$xeudj5 z1g@0DLR3>v;nsTFE-?auzlBVI zow1YH&kN>PQz96lx#Rfi#Tp~A9tE(HM}m8L?&>G1*(P8gdtC`~gsRj9b^OtJ52OTyd^S8jB%okPO1_xIg43?DoGaVV}@g-nd zpERtAjl3T(h@Hq5snmU|>{ND4@%&64C$s(lQ%~Z0 z<1#mK5VS}R+{j`!J0Jr4!138!uY$P>#sE-6QJR>rT51RD9TqiGq717ney&88@BXc# z;A=mio82*4w5-ZD7P?~ipC>@h`OXd- zGv=+NVf{2VJ4uyLYw}6}Vh4g&v=AXNdV9lZpVzRHeQ{0K&ih4QxwVd%V}5cez2(SP zL1F8Bs9prc-R@fhs>(3D8+k_}B_06QYppc|*3ne9JTPWsN$r8lQHBD+oWqVIXEzSQ z%hNElrM(bO%aAs{9rAtkYmvxYi#+gbP+!}kb-pv`yM5@Nl^LvOd&y$;#B` zh8@Ayo4lc~dBSYLNh@zJre^`4R8Ho9-9$fqH9O>0+Ke6a2@E4G`arnap9nCt`PLI; z^;gf8crboJWZ~@WQUy{`5J11vGx^uqJXfstlAdd+CG4NNrQ`JrVP>p$2ezgEO#J6xGw&3)XA_zr|i1~&LGVU^-+&5(g8)1Q!LfZ zxof4G@NbY`?eMBZOo$!_~5gwe~fg{q|9q2{pb^V%OL?;bXaV5N0!nu%lK^38mLv{wJPuNXfM?cM*kpHyk?%kg0luu}#6LqJNBHX=os0htxLs>@9l9MD{`xo zbT!9VE^*cPWsUnz4|yymNwR~S7$6dy-1%hfHsU*|-2aQKuMTK3eAmVn0~7_MRS={_ zL>g=wloW}nbW7)$jS`!PfYeaBWYP>aLItD+M#n%HgAt<#8ynv#GnD|>HFk=X* z|K_A)wJOB|dzB^J{+yO5`=Sr9#`*5c{loV&Re0S@X%pS1z!Sx+bh_sumvWT5lI4wS6g^FGYfUpWVECi;8IAGxqoky639R)+^$|qhkfC-4HXf&Gdeix zCgzL$FTl=Ds+|$Ih|hnd@rb!}9n~@kAAB?Xz5~kcVETiC%u3)67ax4HvIwnHm%Z4D z_GTM6wCpwdXqtb6*H#7@S`Q5KZG=A5Uq8fZD^FYkP#Giu`L9iim0y!+rvl$O$nvGO z!@Am%Syqvpjj=e>ejBf;&t>2t;My6mK*#1DnJ6qM`<4!2ZjY=)c%|befyfsfGWUgJ zvv)d?&tKv^*yCNbv#b^Lr~~)ZA8+4@cLr$nm^gx76N*j7x=gGgZ}RW)gkXuiBwVQ@=u6yVKg zImTk{c8Rg3acmsy9aLl+E4+8T-V2v`WTx-|eJ6=GU+31nfB9^p5cKk6k*SNUtqPd6 z=j88?3ofG2w)I+8R+3X%CDW6Sn-)A&D@iIyC zow685vO9gnpJ}D-_`A1szsLdp1^XK@0)JlUY|D$5rbl-C@9A~+sw5^m*A9^Up%Q^% zL4gl1Ktd-IbLV1JSp&Gj=mp=Q@9$Ki=a=gJ#OLOTYS(6=3%vc`cah(HzvB&L-yFP6 z2Nj1u{+ctvMKh}PZ0-<)r-YsCcwwGQF%}wfv<7aB!M_@NL40Jl*e=)Cu2> z-!_i*UkkQh9+C+Cbq8wT*SHhC83cBVYWA%LU)l@N3J+M^1M+WGL+l?sRTxATz~JU$ zD|D9d6+L-cCl^pi*qm{u;i2+89b@InBC>sJ|1^@WZW8zsqzcNX--z{rm z?|5RBboa`d4F?m%7f#;@s< zVbZNx-AeV5aIV>is+)mbX=9aR5f(o6^;nnE)pJ{Cme2ZVv?|YShVB0lq9LPXW}#~~ zP(eDTEzL0^fenj2ZC`$*Dl1_n_CE~Wk&TNlEOMDtnErKmPmrY z=yZslf=`$3x&HQ4?aT6%YRdvZ+@ZkT%-Tv_wpR|V-Gw= zgQ8>UiCv|(Khthiq94y=&Iee`uH+PSg+N9bRA%0ABjo>altZ_r4ywIy7Gc=}Y+bvrE<#K0+KyezolL9OC1Aguh(RIIkX|K;&C}fA_^4JmO$Q z|F9IlBtr?R4}{1y9?hyLA?I3OOuAZ}-jh@&X{f8?)2Kh z-oAw0IJ4UcJdQ4|9u_ndM9;d0KXgELtv4l1#y;;lY^a{%|ukt{hnq>}0D z@17{lb2v-g7Od6|yr;-s8w?Yd0>-X><3(lO@3Uw#xo|Ry4t$m%#uC| z0YE8UptrFv?DX-5w1bnFfUUUigMbNq^-cI)-cg9f;?y73ikaYn2)hWbg*Fk2aC=TWeTZTr z(@66>UcsP=uLefOvSnGp-xd9VO5U-PqL#8#*VXeXsPF|FSoc1R&HYlR7b*JEZSJYmJi3l{)BqxJ6{U zzkJrxPRHAFf6c5Sk&oN*YF$7Nq4^`pkmIPN8pTmv*OMb8KD#$fuHi~Q8zQ+SA%`qN}wW&vJyI5J>Le$0V z#dnG>^d6G`Ca+WL$6UwK<*i94blbNMzl!$pKAt(ENydD>uux3D;5%AL z@pEY9QB_~*!AsJ|?0%$+CFAKS0CRU9I}!L+v)EzT-jeZe#XG*KO%QfLwkS@l(3 zC2}ZXD8teuI3AW|UWCs@nKAjoOwUG&pcE^jr@n&f~Zu&(s}N)|%!syJZoo4z+|zhdukcSN3@Ol(Ab8CM}lj>>-!-wK3IsK!auS zn?BSEomlzv_B;L4sd9Yw)LosMhT2CS3=bBPAzmHCUfA;WWinu^o_k`#6PO4T5CrNF zo1haKM&m!&eQB7B6{+$Q^EX4DCUXj~^TMnj(=R%EK?_|yrxCdyc-P>XMivud%-lx!_1uZyoAJAGb)2Pij)^!A_eb<-?|g_4?dxQ5-0K6!9T_(e z`laBOK~QA5XpevOlK46-#sr92o(8-Cmw{VVJz(`7*mbOwYZ2%l=q7W7C(z=a? z>sZ?~7L-YT-ulkbYmnQZ4$7&m3jx7&!C(JDzD`u`T5A`}96Gh4Z@hyxSNze%7S4L| zj!!f0CgArc6d8(fsQE2?6c>pW-&c26(P+u%k4eo7-N(I#F9Y`0>(kMPWtV2wdp%5U zMX#xQg@1>@L_fWjYf(v9OdwnS%eImZ?gwQsbM?|x4Tt+Q zS97bY5oM^RkC5V6-tbAi^ZdW<{-~()I*GZ#W?>JZtUVq5N z#$^M``^JC#Y*&qP(HY0Sf?TyU?llDtk@C1NU#%2PRatQ=s*iMAz-kqo6Szij%aU|( zx?SOlrzO>0_txI7z)EZop-E>n+sldRA@7T&zFC>iOMuBqL);E_*UMAn8XkBh`#Ny3 zBQ2;BK$Xu;;z5He3^H+WlWB|}|4-^fg1GuiFU-v({<$G?`|vOBd;H2-=f447V4zea z|JvEDFGO_<{dbac!9A9MIU2kC6+|2X98W)aeu#Y;&Cy&QcV!NhPB%q7jq?~LeU6ZW zH{@BAnpXQoM|0ME>h>Dp5@gxrxK?-RiV#o&OuMnY@vHWWq^w@FN0O=2Ey(>jHk;|h z=wl1}C4HAJjq!-A69$wwU$4@8mrK~smq!u1NI5bxCysBZTQXE9_Wtx{yIKF^u+DdW zNq${p-|9FYa86R6I5Tj%M`>0^ipg0n)gJnz*YIHfm-ifNXE_$#f>s3q%hzef-XZ)}uq6l>ku47V|!1noTnoiyQ+57h+bqb1p zajm$sFHsM(tbTZmlzPJ$5T$f|zR6J(H~BDdw?D#82Vp0A9qV!}(`-C3 z$bXRklmE5lEK*UD*($6-`%jxKA!NUlWES)gQGLb{QiI{s!hA9CcRdGHLo`Bu+8gP; z?@m>_AI}+4*_c3^>$?ACGyw3WC$iGfcuh&@ShDDfX1IeAb6B}rCc zd%O45Hmj@Hb6lK$&^7J_|B?CqZcZ{bLV}+DJ~l{tU)6r0pXm?BZ+-SqofwP{6p$f$ zZmqB~LH3*Jqm1*ux2Njo|J7Y?t^00S+x$x_sl$oRWKhSt^LK!=CkoKm{Ns@#+X2Hi zZv7ySe0o^@((525l!|af^bA(3ZoMoqNP6#JM`MX5}3CBld2;fT6k?4Y1KVAl8^ zhlH1)fLOpR>~!5P7bDpi_VeBzmrHA4iv_IYmE$6Dvy|OH7I)kAqT)Xm|H`Jrtz0zN5MKqin_9kC?8=D`^w~S^Wxo7zJGTBY-}ajld8)lGXDtKr&4@% zf>`5oF0zibmF@(TZiJLOjMyYPp&~J1Q1iVfHKk|MU=a&)kpbdBfJ&_edPtGqL8zuU&w-lx17JV4qn?0*OCZ^2ZyNtEsAH^(nT-*@?2ohvbR*Ot~bW{5AIyy7U}fg0$A{6U+p8bL6kJ3r%IU z6kfHwK4#eL*`hwsv=BVS<+k*7KJ53*X0Y9)f6a%%B_?qUfcmXq=jfGO8j=53msxAw!jh~M8LfF`KF4s+r&@Rw zSOS?{2xzFJti$mHlG_iRqZ`GV;qFpKaBu}=XjaYR=4XS?zxYux%Z(?W)H6Q9V>u+s z@opqR^_4oY6S@4~&bARG)BI;1v{eGliq@J6NLd;M`9??W^( zW9fbezEMpRQb>R4ur%L+G`?=|&;YuV)-A9WaB&lNC2-FH$gwrpR~@!>+fh@sp9_YZ06xpX;K$7m}sax z?$NB}4{Ne#u{pc!w?BgoQGownkRroR8r?E2LJJmOLoKLK3HC9J3`~E$frw5 zmvH?nZ3hYfls;YK_m@j0PFeZ;q@Ow|*!D-2?dg?kr&r4Fj35CqHg#Q`sSBi*xrQ*TPIG9Wiytbat8pRXyZ;Y@+f3at>v@6Oh3*+kO9|Rrp zZe|+&QDE5+oSzBqNfO@p4Vt(I7KqtSeAUXSI~Ifl9VKc=%21w_-P@1T*#lWCbhSoK zrVpHJPt;1bBZmDO|H1PDYT0qQmpi-7P2O_zDLltbadDmT{E9-JnrCENJq{&s_1E}U zczYiYL_=lw8JS2NRO=i~637dgT~ev?z0iLE35b`b=$6i2;W#Ve)2cuIOt~xQTackO zHMSo~g9U^=jtkja8W5tB0|1+Oa=bJ5q?s`7(w2}y@u(TfHKha6TW1l5d}OjK^dEXe zKxh?~Z`-*}wrV!X&D7R2;Xy7lY+A%c37Q?@vx*Lx{4FjaEI*pJ?~5XRle^E<(tB74{QXgGa%VI}G{SF^6I7P{s&?Tj z{=;Asbab)Vg}DdEsuW#r0TqYC^RACVb}p)yUi%hou7C-u65QmkI{#G5BfbE(yw|ii zl*qQvsA?sRJO9+mr}ZyXTUKF?mGTAMhQ2V&p3MEb>BMkFY}Qr1h`9%o@`5$gnnP-Z zWZGL&9^)1QY

X;O}P8`@w(mRIgs`|9g`?Kc~ak?gVqeZ>9-&xZ>H?v6~q$tv6A* z#iaLd;;8!DH8tA2KMz~UJ{^73`9+Lnqw-rV5Sfj`3+~xi>V{sB@@*^m`sA0X&(^ht zM8r*ikhK=L!h#-B=1yO#S?gZn_fxglmz9{)!BJ5%iQmx9Pg78*MeJt@Nq>F$5{B?e zeG%Xe%HW`La^3pmkxw6|^!lK~`rR2nH0~gGZyFuL(q>4LqdU(%pjd4LviNTVWGa!WKXZ%xim1^mmCeh!L9(4as^Mn6OcsAR5SKjA& z3<3(a{iaY(Ax;)9!!7rcPVp2)w zjs*+IpjuvCKa2cNSDd2`-JLuq&zKa!SO7@nNS+*?&^>qP27b~+g{kH`1{5c=4J{K;O0LJCs7-cy<#-BE7)tRJNy0vsoN>@v60`xTRAg=; z@`7HeYAeTFe#Z&7w=x7I^w;VO#H`(Tku(Qpv-d$2lziRBlF1nZm9;;dTZ240`^2K=;5s1Av#(^o9EL267i+wKI}H^kd=6&V(G_o9H$Xkq1Cta$Z5VU)Dc zw?AfnYifT#fqot!o4tXV*{s5_v5(w$#%lb_F2ul>Ue+rYjy)k{oFkb%GHL}H4q>%! zy>(~;?Px5wP%Ecw0ZYB2N@W*KDj2r&>-XpAhvmM+2(vmQ}p9ty3zI6f2 zy<(|hVbRSw=!gRs*u4||Yq3DYn`_HYSzG*Z^s*vuE>>rMTmHmpP9TAHgwdr@?S##L zR~O!S+TA&9@yigHxVUpndT#-ffX(c_!_-|trqlc;FmoL%WSVnmnlGXD_5^iO&&Dzb zzCbLb{biChWXJqVla+^|I>^B5LVx1#R+eG-RNsj1XYEh{waj(gX|vhoHA}{U*!O=4 z3T8E>{PG3A27`A2Q!<)d;^sMjA0hSak1)#>u=K1hE@abC(#}tb^YPb!p8j76U8=Ve zwLy#edkoV`Iopjjinp!P=1kj@hkna0%LdGdMLDr~iJIQvD6@el3|N4X-@oMH;)~m| zHfq^?_Kit{a}U;HpMNPUvj!7@7=3r49k(Jph zsBzN*+dkx_RW+0v8}~E8DRKIOfF{;;yj0gB0Ti9)DjEPdnSakVuzi7ip0?n_G{n#B z{=Z3-n4i2XAS0{d`}*|8r#~r)ATET3ZM)C8p$i*3Qj+ zzF-6zco^4*@1CCy&4D>QXXxjFRzx-m6@FmlD%b1WM0ePN+roCYa#~qO_u+L7gL*5}S7B9P^Qw%cceF0`w5wfg z#izwex`7|{ka0(&!}`x#kXyHq4uev135=~<`@Ncc$%=JifOQV_s7^R33sevC0grH3 zG7mP1jER43F+D5(>|t2r9=C#sSWC{f)$wSQfnz6Gx-b5c+wbZIIoK@(M(zjGzk?Y) zj_XnVbKNV<(jp;MPK*aH6cuLBdI^yS_(b^~`-C?tmPaHeK)&ZRmS01Hc6pZcddN=z zeE_qDyQqA}vucA@PZ3!AvRt>vTlY&wfJLJ)R4=-XHwaAs2396bF|2gxec)0^(ER=0k*thO&yw zb`XQ8k!g;Z;}iJ6z3wSeBupq1u3DPaEoHr;8`83-%Nmgscp6VIUDyL0#Rnv5;-UhX1ge)vQ z3}-{fbT#w#V`jU7ehXh_MlhlUXkUI%*K+htWkp_Px8|S0WRVrKv(@$|`Lj{1W1emR zP%rlkmS3bT+FPZ4t=WQ(nzc9AFT~dF&g0FK-h9=xP-H5n{81gH4c+-K(3S1KCC!7y zIvyllI$%bd0QEzAM#n!P*&N=>0^J3r`b3bII@7kjn!U@S6w)&$H-t!SGXX`|kF<}^ zz0CKfsJwBhZa&4o$A&0)!#blbqxo}|E1QyLTi@-XmFJYcOOiCS2U{`u#Qf;pr_dOk zgothsK(tAbyvFXWXv7%iLuf{3eiKG!AZ3l{(%exT;Sa>Yc!J!+ED-uW%fxWPiRqH_ z2u;?Tv*|u163Lr!4JCqEBO0L=u7&gY`RSCnLBj;FbF*`a!=8#uOpdn}%Xi8ZUqHD_wNH zR%_{)z{WO;%u(nrNEJ3>vn;@Zd^nmgE9_lcpU^33M(Cp!Tt_ zRJ(a-oDoQu?* z4_U{>O6}|caSUIY_VlH%=0DQFHi1YibyWNiAEl&R2w}<3B)qaP9gnl%dr`4`{$>f4 z=-Honp9A9-3`2ufXbp+4B?wR1$vRFqS(lipQl01~jy_MVo`u{(`A4DtWX_lY)e8^N zK!k&F0?F64{?o9Fll5rxMdEH_cKww)4MC2F?qN$0)FX?g;*ad7#47E1Rhor^wi5_c;P_Ar*p2s|%OO9c9y~;#ajVha*EOpG)t!>8u~JXW z>(wl)8D^uo!8>B3n}A;!mKT>TbXBO49>pn2_Zw{dK>t7ia)PFuMxYoYsAO|A$++&i$@Amg+g5OkXE0|Cw~*g~Tz>2}H!R zwAX@{!gv>d57klRry&EheHf1rB-+l+@Z-VTR#?CK}3B+9X~KfI?AL64AQm!Z9J z1q?(juKE274zP^amWtH4RW)<_^q1X2B{e8;E4u5ApbxowAAsy^|s9JQ1Q1${jfDf2(Lc>ppV<7Is!}jLHzN?Gz>aLM;vR5g+OII$Z&0ZSV5nDgM z-cth0b=}z(vSAY&A&#MUYsV5_%Z>(MP#~h!hb$mc7v4bXA2|qwyAR0$2219ns&5AQ zY!%I6$SYb7@dy*1Lod>~`P<2S-9j-H1@s1PZ%r6r4j)rdQSDD&swl`F-}NWdWcc=5 zUBX{yip6*LMr+S(*Pzx6$530HA1Ood>DNk8txv^7UP%4?$dQnB@K)P(hx1R|+F2ZQ zkC!I}e7Vwh>qSE40lNI{_Ol~b`+j_nXR|u+L{IznR*VSzz(k-MzBpk|T~pw0sdP(% z^l0gZ+Rm;91*27p3M0o86saWjhQ@Lam=txLJz}rbYtIL>jZd>Fa^l$6eP*mCrgqwb z(MOE*cks87QgbjU0o?i=Tf)kX-H5b$zRp*pQPfXpfA8k%`=Er(@@!5JKYWI7^j`R7 zY^JOC?#~Rwulr3y?4AHiRExLaBS(FG5sUn*2lKvNq~>t51gXQ{6aG?9wk??yn=6NX z81a^ko@WP&oIbsZNuKHJk=A!t4f3{Z_YQ*q^m(f;eZ#q09u4i1e4`2o*|!sXd@`rH zKBcF;pX$2P;ConU0e3f;Q*Hms*GOUK_}f~{^@#o3HRI$9j1NN3avw(a$9O27U#`9~F z(oKZaB{m21yTSZ@j{aXS))sb@TnlM94HP@i^vC3goIQ`AJ|!|IPd3R0(5jeM5%B9X z|2i$JjtW<vE0aOw*GHKuY1o|N9fqk7BJBowyD6NmxA0G97n zIK^B>FisnyuF?#!p2po6ReLZ)1lgkbK*W4qEy^e=gFw5eL zf}=fW4%~*jGN&Ax9j?6DnQ06r4eU;^0z1{8;`EF?We7w^iGAHXPd6>w*9vy`FE4cf z9Ana%rn6p{i7G`uq#l`tTEKewA&r8+f@8w}1${Cz);?HQ5(0LI1g8EXu~cn%J^aOcAe z!5uR!4O6`7h}y~d{m4`n8EfzaNv(^>SJ@Nic-K1Z!4MNX-NFsri_{e@P9qlQ;4i*T zS%Z0RSd63o#R(yFp}wSa@NYJYwx;YbYh%j?PhN_Ny)7tcdm2g1+h+pwU6Y?_;q57z zsEm?_l!Ui`O9brB=z@VfuGE2glMrz@+1xrFFk#x!-Ay(t8*x!%WBQ_#%CCx)X)~C} z%bWhQ%DX(OdR@cs7LPtKVDij+DIpV|Ikn#}HD-%sMiOtr02y;b@ zr+vM-qg7W!ayV8}Z#E0{*pkT6Q)|FfHIxKet=A)BDu`f4V+F?Llzc8SN!T6E`FjS? zl{}mfeqcA5IXV1wpCa_o)eolEedObx6Hk;n+nS`-g)y|{)c6nN0Hs8O_c}d6@os*` z*N2o1_9i>kT^iV>&y!>~>+{(SjUlPj>35MC%;9j{74!_UpPOnk;bJzmHf->Hi=Lbp zBbuRImKT0AH`+tDLR*fi4yax6#Y+E#r*>`-fGx2+p4EYRkziU-6d~p=3}CibIGc%6 zjz2e;*5NJMZ!;1TIY;(vXFee)sEDyvUA3BQeOImSf6a`R8yar_CFkMTQ6AN5%vzq7 zXPDr!<+P8Fd=mI9-MJ~Z?cJ+qSfWVYhkuQ$^O7qT2viv_Q;nynMp z<@9f=sfAq;92qfV9`(nf+E7nYU>t5Q9Jb6Cr2tmMlqda_9`hWgoII%J^rc;vUr&re zsr+YvFy-dbQRHr@Z}G*gjT66qj@JA$Kw`xaZFCQkuU0lA(5Qdt3I~|?{3{wq64$&r zInke|{yk?PHQ9o|9e`k-L;WL&0f=DLb%cOX6}C)MaP-0q5Un-5m)xvSZKE&c;V3x_ zZZNunnC?cKnh+@=#Xi=ct{dD%kGPH#6}T3@zF=J5+{uw+K8bS8=1kyqo5aF*olEo* zPjGD&n2pI_tG||!87P6xKA-v&sx5Os32R>BM-sEFt=n2Ux%MOFaogg^?1@SYm`->V zFv&dZ*Xqt&oaTE(i#!er^lxP55u8*hLfJbCL31fWw-PHMUdiV@5ETpyL zM(u^ykmgLQo)afjK6Vb#4@oGzoD<|Jpt#9|zjF$uX{q;CAJPeT)4@ZZl}C5iXIqa+ zwFMpv>M~7)T;W=g+6?%$^5-!a_4D~j)%6L%1-HSOe}|!@tnd@qODvzmjqy}xG)y3# zIzsNCA(*H1bI9#i2ktUFaNE{n?&l|!Z%d~Rp5rc3QMNb@wFzAVyn)X$bqafFCEvE9 z!4@p9kbD$+_}}5|)3PGp=&6E_nET%A8SE-3I}LoDU2%P`0xIM8PcS(5i@;LY_zx!q zbM_4WQxovDgu6|sMuDEv zz*LhK1lzGO-9J0IIDa|>cb+J72@SQTRd)ZHlgBtW$!BB~gk-TO-72)G{Ivinzi5~Y z;cn+vm>GY!Rs3S8yiBYvkOJRcW3QUAVVTUAlJa=BuoZTh6mbup=$w}yecTXv#=k#Y z6bNsgPZtJ0zPvm>#)HlN8e3DUTvs!hGh~L%V2Y682~&+PhR{>Xz+<-WQF0!J8|xK2 z9s!HD+_^_M?oGU%66wF5k$ab(+SJ6Wv^pNNnZH^}9NE*z;}7|Ht!Op5Z${~7Mu&izmz`n zEbk=3RdcZIa!Xg@QoVip;-uI4@_RV3!9x<|8$!wOVkJ zNb6bMuohHNbbR|3+bPjN%>iCA9rp^Ij21oih|zB`piU^6oA;)bRiV22-)*E~cZ354 zde;?tP(tx=2cu*@*Np7^nulcCYS`+5#O5(&VJ|-a?+6|i$CO;k?s+7BYu@^92k3*e zp3wDPLX$}oYLL6C#NWg&usqN6TlF+Pjpnvm_Levc_W9%-FRxTn@kt6eG<Q0{VWM8>Etg=0*(r$MuLZ`a(ez27n!;+^)wLfaDLaqL!8>`JDZ<5firhJTF6LpveneG^otBiGy#6x=)#}ODFFgrkH}T8Eo+( zvyS}PHJ_|cCvMvfo4}H(;99Teb}nIEOFLy7L0iCWaaEIgOSpsbtJL2fruiOedGPDkn-kZqlNjf*nciDO;)mu=TD9*4rs(&@h|OFiMv|6BMqCO4{3ufy^9Z8M07eEc300 zOTLx7_o%A(zKSSHJ|I9~H$ol^Zt{M%#(G_6+Fg87mc~X3Askn-2-aowiUvNx$194v zYa%Y}kebtbHzZa9bumPhU2x{*Pw#~Tw1^1EUIu5dfhe;c1TCYwH6c6=!UeyFc)beyg*Xu)P=h)YC8SCU3!Aoq**)h=}pl4y`j5`>$WS{e9z z1)jdtDhaP_rWOF_2e0U?FhZbYs>L4_CeEh4(+c!!d26nD8CcJTDLp7bn85HcC8?T# zUHcV`r{y-xODon(&v;@fyIVE)VK?ZJPB<$87#)U%-`Ie?ZWUru(0AG zSBE$|t_gsYH7S0`8++)D~W?uL0V3`)MuMq|z}owi!Z=rv#Pcv0ESPxHJL zz-wiY$IRp_#C*Xx^zT84a7^Syvbl|VtuP$CP&@grvP4XY055+Br+!*JZR;(D*SEEg zNa&AMCcA_h9k8j&E>xNb-55FtLcroO*PCG;jRqxk0R|KAA3_+EKX%hO-@xk{8nZNf zcJoi=ck54e;R1nU<(IvE`&G}V^7ZOxVG|ye1?Obi-5g)=G1fJkp$K>J0bj0E-jmXL zkqY_)_zAxUQV`sS!qc+5X+qppXRu5E?HA$#r~7l87i_C3Mkn`r@ah~@V`cIhD>=S@ zBiFYW>4vb)c>h&`5F9fg=C;|E5Y+0RH@y+Zmx(SBBUpx;$-A~mY#;F3A{4D8p606HI2J; zvLr9N_%oNPgu0`u6)k61nOD{z2m5sMhZsa?ULn?&4?=C6{p-)lqBVNlYEPnzgq5~9 z9Yw@7qxE?Ig>`2_gRBBUX3%Z+%WgBVDR34G{2kZkrFZEyI=(5R)P& z`F-7%v&Zo@vWz)cc-6x}-1TNmT({(azSJSQEjTLP&8@ynqd&xV(i=)$(A3Om`1^i2 ze?L-uJ7Bylk#pg}|9BA$lq`E_+m_a-8o6nDNUd+3?l!0)-KG3ZnappkBFfOBkR#b) zj2?`9@O(IosNl3r2{IH>hr_4{x2V?a2)^nuN(pAEaeTF|TP?LvE{qgVg%BXT3zuD+llKb-hRLtZQH=7`Jye z6EwOmtuOq2<)tBJE;w1D6X$@ZmW1jj9Gd(b_`y(VJ@*Hg4AkOl18?(@EwH?r(~U`eT2LVPJkt zGKZ#)`~EaUJsh|}{sCyr2&Jy~V8{C+>yV(SE)jzZX_w7Q$xu$Ac9Au)`Smplq@MIa z2qgmT%9%&OcDfWI!Yn}05ps1b>8y#$x-28E3K`h&%*ohdT2GRt#gHmGW|UIgZgv)* zRU2yJRK5j=ma&038EJz)C2_YzsFI~9asND^U#yQiz*t6-3oa7hJ|`BLKr94ggO`=j zk#kF_BOk`}V_&Aw48NpmAKQY?e9QS_Xg@wsjNy%a`9VB2P^tH9|7tI;Lw2lG+(JtR zYAw#9#CS(;)qU}^^{}kTv(0govRf}D<;Ppt`b5;ziPU6_uU}S6uu78i)y2G?)|$)~ zqLIj(z`eg|T3c}f;$zB5&%{~ykM9lawpCZ`RDeM&3q^-2`ZqTZ)M1!D+&zK%GxXm_ zfV^vM%SRJrEmv%!yGv|n7~jZL&=0Y!ciYd`Yq0B_;MH*_%tCru(NRyqf@=@t=)7B7 z1R?jXLb*gW=!E@S1uo;qKKS|c`J;<|cXmv*yT|W*Z9MC#-x8fG+}+o+o;fH)9~bss zPg4~=aXM$x;TVfxL5gja>yKx|pY?N>mz{Q@IS7Za$*c65RztqDqS}E<4W4AR`_HZl z*k~}I_fYAKB7a@PWz9e9p9B-}j2ZfBBxPLCYx|E)Q~ZF7tblqwYU8tj=bvo?fmWZl zyQ3kYE;O&v>n36|Z>NLkp?avposLX?uFaiK-X0A0iZTX3TM9Fm4X^wrc{q2l8z5CI z&!V%!uWY`_*W{0~?0vYl)}a3QcFOUa;Vv&%=BBi#dIqs8IO`al zuT3c$^v4*A343!Qtojlet_>?@+JKCy~NQ zk(c<^*Roau3oF_lg2z)}vr}TXK_PdAxU?f}SGR(V3B`8L#lz>*CC;cDiCZV#il6sJ z!^Rmx79*jMooOR-8LBY7V&*%%T4+x$i)PfVRfE{z)v=&HG_Jn3w69@x#hFf6ZMwUs zaD7lioqWfAL8>V&Wh5$d8%)k;bz`B=)J7aPT$lcryA5hb5(3UFC+=eXb+xO8l7tcC zx|q{o%is!a)dKXrjan)(7cJ36;wZK>;S{le(F1mwaavf<^yvZiS!O8adgquDoLy7! zJ&0wmK1$vaB&Ld9savSWD?V|4hPih0+9A2VYduhUuRNEKpRr3wIyBqmgAr%6K5TiT zM4F8jt2Ru3K5aaB< zG0M61YwD}_;a7}`$DG<6j?F`TBH@g>Rgwusm8yQ|2)l#COpr@2@s3snBz)o}W(2=3 zI|2(K-f2k}(hjlK+@K&9xgVvzH~t-nzp_YKMut`U;B^Wk~JG@}UY%skDgYi#i2j=y)8 zODCFl^^fcbB_$!ax+`>KqCRk~FI`}Q*kFTL-diwK&R>1rQl4I8zb8x=OAer#8h_s? zZgFG~7v)7imr^@NTbg}@3I@7j(>Km}m7WPT`LboS=j~Ap0GL1KSdqHQ$s8s;7%Y}i z1uiD`46p}dZqP3YH}dKsW`}#3GB?v_>MbVrQBWUh6l1JE5#zk7pU}`1g#u~W}djSQv zKK6KdfkqLuZBR4-`H)!fBYtVv^Vd$)bwuLJSK{AW8CxfR<_z}Q!~Y0XKwm=S>w`rm z!}E+AhSm=@yeC!8!i4Zh%GO-rIhx{ql~VErtx912Q@=Xby5{Y3^+o5X;Mh{o)~nBR z+pF@1$T-lq5bSWfK*vK-=(m}S5VEVB^Ys3v$Z$lC5E?8ae0V;%iN-t zl9+Fr%bFL5-8#9kzrnrV9BQmlN*}?PEbr5O<&B^1dRUvOs{1M@7=+sTPWfJXbSu)d zv8JNLX0WhUY5J!?a7J^gCcKp^K0)-9uWyM>>R?DD1tX-$_$XTPFtyfKAr$(zeSuAU zCK&j}ztHqxB@2G--XY=(y^X~7tlNClbm^D}qba( z%NSny2Y-A(c>fUXPHs(Pr#~gZ9V0{pcD&YPSjxtyH@hQcrFJK6wJ7m#nIOKpH+i

~QH#4^SWh`woW(mMT@dnb>FSDNPvs{Q0@qn?Xomi8%6%cAOZV zmVacLlU%EAyRE7zQ(PWSgiKgqVs2A_sgxD;>YN;Y()$5eW0PKVMOvE@Z@w}@AA<#4dg}wa~?g1>3lAy6> z0<{#Eo~;4q3vVoxNJZlY{|#;{Z6f%mKR1!{%;}Y^XRGM;=>om(4zoK(DXjte*!QB| zb)+^zu)^Q5zAd(}oEv!42p5Xqr#07*hfL5z=`#ofK}wp_TSIkfCUVntK*fp>?DVU- zvaTAt>s9?tz^-Kvyy)3RwuaQEUA`=z?50OPOb-f>{)YF?VKUN$eq+y=17}udbQCeW z9|0b}G$N1z2y!k^wT`4BxQA9HXLgdSrV4_wUjnybEk!8@^U%AqdS z^hGmZ+Q5AfhfIVG{_3AmZgF!dfb$h=R6K-~ggo(9Ex@{cQ5vB;4^gVO&q~=`-CMbh zq#b7OYpH`IS1dZe)^jQq@SqtTSN%w2Wl^dg@6Y|EIJ;-QyD+wQPGA~N9qm^?73i_} zPAp(ke*-j42Z-nmQkijmJhd1H11`{#)NP!eKn1w}^E1QSYLD9TvoX9z1`To8v6a#i z9d+nFKvo425Q0*IpwgsC2_XbfS3wZ?Dn$eWO9>saNQY2d z1XfxEgeWD!KoV*~3nh@`cLJ+^9>aaz^N*LB)8@>XnKSd6_Zb^seTh?dL2b^hNY9PB zA`4tcc?S97EY>P3nN_y*pQ!PqYubumnbLo$iGy*~(d0J+lgvPNT=rjB>3h!$@il>a zfJe*BYo%A3?ULoK z=AECfFEBR{4$ZloFxkw%4s?^8Z()wEj~8cssr`xUbH3`56`y*GQ+(|p<1ty2Rcqpf zCmQk+2d&wc**9iOtRj+GrItn9D=53!PAgu{OHJrGJ{uD@Qty_Tq?8#GDZf?!rD4fh z&px+>Hf?TsXYF%Mfhvfob`7Nh8@B9e9GVrFx7EKq-WWVJlp1i&D|7Wk?f_q~?kirP>z1cp6e@)+7r$^+We)$oSFTE$eY(cZ2(@-_UckJxC za=)XF7UR;Y0DmWl22OI6(G`u2NpQf%5XGX1(7(n^G2x0#o813I0b>BtS2 zNitcl9Hq9TQo8pZ2zirLX<;u+fCYt@TZM)OIKBP2F(AOtNo!y}9N(W2sUrdo4(-p* zLegr34I;=-;Z7${2&I2gkg|jCHgkdi>Z~gpe zFpK@zS0-KK@E$3MfTo@*=k}86Bqv{tf);FS+)w5#6XsWY-#a=!$^?QdbeTP%-!AYz zsJ;Awtfteh6srKieSI&CbDA<>tMC0le!TDA51D4u<}D8{JDIGm2OC>-at8Uo_+k8j zdF41PV4J*-8m#v+>vcn$S-HvxO}U?xxoi2cE;AS8jN^Y+9^6WJl@AYJ?w)&~S)tLs z3Ie}Vo;@X*wK(li_W6NP4z)>a0iLBkuH{Qgfw~R|<6FXLX%5n9s~K#f7hWY3CUk!9 z#A33d1Uae~n-FnpqjSlxEntNn9f+IQXWvMso1-h5R$944;7_EQ2PbXiew4?A7nO}^ z#l2z`e}rKSl$iElwd&@+w7z2z=RCty;vNev-npoh(iaPh7{Y){sn4iXTboh+qvLSW zNDXi^9~=4_77s#9QJYcr{2>n8u$J|ljfwQW&#Hb1c0fwIDKV6|_i+krgOh)(6`_{J zVc}Oi&C<*^x3DmqF~&wNd9d^U{&_y*Jt+^rrtvUP?g}1w(Q$DzGRg5B+!k4!2GO70 zweRP1gOjPmOqrI|49B1)GI_I!y#3Rr{+`IT>dJd2VZL;1J53CwA>)oyWW>8Oq@$y1 zgF4ZY5EuKXzd+Pi4dSi5Zd9ZiS~w<)G4Q}`NtP?JiatUy91z5Jmb-$eqz_jl`dG^- zQwFpHf5?>jU=Ksx%m^F!-P=}ydgPI#@CRZO zaVX|G1MThzNmYXk(Jq51LzdsT0 zy!xe&w3D~kB-(Q-eSF8c2v4AY=Q5j4b2tJj&+sjb*X@CQ{d04&4Y&}g!O_7n$SZbQnq?-7Jr_Jz$GJ*L%5fGZ!EfMV~>&3>k zIBq|y3+M~7EIyL{_xQNsk%Wcm_|b@d8Oc#r{QD|UxgF`Mz|<)sT}I(uA)zq_?l)!= z==U4Sr(cDSEss3lPW|~iSS|Ic4sR15KJrB|F(xu`?*$j96dc#LSI93{uD!SU1tHV; zKE}+~kbTojFiA2MM;Ca-zBw5n^!#A=@af>R3~oK(9;4{k0&;KWZSNgLUX zG5<&1AknVp{Y^2?3iliM(r4*$mO_efYjaAVJj_c_ZesAl?zqbJ$xLGSsR%j<@i9mF z7wVC?ZS4fEwg8jUF}mIylR)`ZNM;7XvY;3uLl4Vs>7AS*jIB-3Lsm@rW#Y{v%4_`B zUvS1|@B(|J9DMHvj2Y09mp&&N2-a$~yeTwg@+YK-h#_vXYD#IIu8du0fMTyb_ZpUTDw7Pa>S)MeUFuF_Z(lS-IlJO0Y*>%Y zyRnmQrrvF14sUw`c%fp1g;#tcNZ}`k_#Q7{UTG0wVPEBq)PM?RaoV6A>d*u}@u?37LmvFWS;RIA!Rj~P zx&XwwJXIMa2Y`~3Dqd;iRv$q2Nq$O$cYGw=Xdj@a*$p^IGKZS?f|GA%=%GuiiRXM8 zv5X-Od=i|`1!)LTP>w7C`#;`g;9kM7vH*DYr_!!vyLg4n_C?;-&R{Pd00Y+0=c8ZY z79!dwCjRX|_AM|Etn!`G+0EOVEX#}m?sekl(SP#O>|W-F_7$mUZH=J7rfrC;aBC|A zj@AUNb(WX23xeb%z3_3S5}A(8nTb22Vl&sg`|FXYit^&(=h%qlxQhG!0ha0rpqJiQ zL@bfWiQKJW2b*_~C?&bY`6>i3)5J<=XIH^hhoP-pcd7f`jjoDHiZRE>2A3A%{eagT zj|uz{*)SkDZzL3^RMzO}qi2C?heSYt$wXQ%j1n%v)-zpDbn&a?71_-pm);T!-BoB*AiGdu{_v--yJI7{n$#RZ`>e~5&dMJ8W4B_GAw=aHMyfa|1R%;mD!lg9=K%k9z4=mj2hHctkK#I)DOfXrU;wZzo zWPQW9&By7>bPjbG+P*EkcE2>9+Axa)=!(Bv;+r3S8rT07*>JUg7?KKKuPyLIlzP>j zkij;d2p-l`-WmNxcDB|0=T+y!d?_)kAl0T*MD|mfs8{^+NcqHbYTCjCZUMgisdAYK zS}r92GSBre?S45hS@CAQz(15^;Yw^B#x=H#6vw2Jt_!V5mbm($f`D98Yk9}R(%0kE zNT~H+m0`@JoQTC%lBidilZ3@b$KU2=RiAllx&b@`Kz7NQ)6InR5=FYH?XS4xr-kLq z`e{W+C*I$#-<0>7gd4D!AOWsF(^Kf3kp&Qfh{11(gn%EzT*bIV<5+vTP5)BtnLoP-On-vxG?d65p>9UMO63>6W!}p3iS~>IZ$Z4i1vpXC-cH9ba zI&tCL6W)Z7BS)KtPflvya=kgzZ+GjKWRQ{L zrt*HYM(MT0j=;!C-4A?JX>-q4O1I`>CBawxaO01UU0Auwmwg>_%E@!t_N0_M39#+p-IbN~2k6T`x*>$8D2+SDfmvy}b^U z&cB$y?lD@gucmYn&Le=0ZF*d<0>fk*acynwhhBcVg}isaOs6CaX**whE*0=*!hL#< zD6}vce=mYN>h$Z551y(BCR35l*-l@IljW4!L2YfsOsk=`!@@l1R^ZEcKbX}mdoz}U z+TXv6reGgS&xIeYwn?_McNDZq7NG>02p%X?VAvSem!BF=2HVF6BPx~)A1XVoYGt7D z#JJsf?;dSSjISET?;h*g;D_tFsj5TAp{%vR>j*bzzq-`c*B8@{&%J297lF`E_1QlV zTDZZMQJs_i)%@Bb$3z>5bVtMItPAM9!hbvXDePE;zSpt2>hW3UzpF^3o$3_B8 zk&KUE-1VoZL#Z)Eaue^9HaBSDN3z(n==zw{+Id`Ik=ITNu;*obFjkfx&B`u+G5WU8 zMZ%r!*DMX5Nyw%bO36eQpGw9)ER<5jDs@3elwiqin8L#sECD9X%xDHyDWZAC&QkvY zAGGuO-OY0YHrCdVY(%_${!r)qEvyC86Wg^Y@@kXyBSsU^{p z*hXz)P+P!*_I{vkk{Z4ka$U#P|4jiVn;^WBg0|;@0(VKI%xSJ+!y@?oz#B zxOoK?)En2To%9LqR;AcnxeqrXWb*OQXuC9FobxhiFzqQlhcBWcdno-m-9jx z>E$2>1Ros+0*&S&+IH#M2?cI4XhB@bSDGACzt$yUniwf>O|Mq1S91z!zX`57pO%ad zr-bg{)^^&oK08Wjw&Hl*=z4+)JJJarBQkA|K+GK?f4sXA!(3dv9yl+xbpjZ;U2FtpAg*+Uz3l(<-@psap z$xpy}Ektza$agZh9X7m#mPY-21<5}7wR4bGe)Ygnfs~wwBW!Ue z59Q|MoYLV3T2wAY*+=DKX6_aJh5icbe}TB}lC$m~i1MU4iR5Lc?pIY)F_VBduGG(B z`pP>3BGNxvudWNn;z7pxKk78<^2g{A3X@i@AXMYQ*C67HfIQXJU1C=G#+KLg{*NTs z&3cYIOx0alNM9mv07j->ouSWRbycB)9TppgrZvr3cXS= zpyI?B5u=ADi@W=JhB(K=zsqDOOBXIuUuLO*XExV19fg|h2S3)5MXpyb^{har6mwi@ zLj9z{lHp95e8z#9A zh5o(lm4hLO~PN%DZ4Y1Lp|1_iLD2E$O-HP-S#wEOcsf+K2wlgQwTP&znQ&sMB=mv z(BA)%sT`$3H@H-3`Q~M7Bk%1QWV!OPy_p42Vuxtx`V$7M%vS)s{`W_r1&E9)_NnQ) zuMPKTo3*unXnM$@JDB>PMs|6hK^+V^>+KN!)??`l+%d5v+RE2-Q#HBz`w}Po@}z8w zu*ac-vY`Y`|Mn*Zl$e<-t%)9#S@0<$?)DrWZ(|IDdsQ()jzPbTV|J+vhLIXBOb=&o z`uA2sK^qW@^Pml>ItejC7I>mOHzJM(+VHz58@+e{Rfy13q`Yxj0qGo<2HDc*OBg-duDkx^Ul;F;gcA7h&wvmaLIoYm(*Fb~ z`2UFi7^T#T=y{{-HbzfWUUaWTe)W3G!cYD~cipI-C#GiV!2NZXBA;QxhBo}%cnc7f z&y4x<2KUrMq3I%tU4iZFHN2S)KQ@~tYSK*}{C>>OZ^g^!V7=VRFa3j-MXgs`-h82@ zoec!xpN&=++be97y8nTQB|%&D*0n2x`s@W@#dfLZUR!@N%6m1amKr)`7n}&OxDV<9 zt{ZUbWjowjLfy)bdCsQgQu5Su-W1C*zP8%aBV+U!<4#%%NeYE5UwaovaFk*+e9@^V z8w34vkcQwI$tC|Qfnylm@;a~+m59asGbru z<6j_tzk`pC(PIrcS)^VY_u()p57ca$yO|5FTGLek!LO@%!L@4WfCybNxgY#$5xtRz~%*MZr?FT)+U_W|zqn?@> z+NLL<^nEz*M{q)xhHjP`s=7NEs@?69j|ZzY2A3fR69<5|Uh0R#B$GuDkHxRHCW_DO zi(sNRmU{)LiaGh&C)30-Wo(A3d6&0ca%M?LO((=VS{N4<0OWx~#1LYMQ`@8l?E%5F z9y?j?n80KutVtazm^`Ej@X0l|eRwzgT}lmSAxC2TXdliiFpR+i2JK7bl9`E0_xA0z zxK|~-Xm$a=lqOml-I0R%t}Rjx0D~{l=zR46e}h(-ct3w^;{EgW+{SPj26w8~73u{i zJ}bi}fxOw16^Tg!5+^65&%~k|(jy0^`Ad3jZKo_}2u>!^ zWv|u{K5B~mjxSDo%0t`ilHWXEN+?gQTh7jPK?L!)nsN@nGjVk~47E|PGbP*aNn^ip zx47epCCl>XP3~%_8tBhTi0xpoc6x|(Ex>xg1?f^UGN646t6QvtXLKFT*aP)A7q&FI z-Wjnat3~rPo*cvUYebmvu+qB}-(0RQnbYX)Reovvt*?U!HmrZv;Y>Pcr!>x9q=sYQJRX1YGNb^aO)--&$}) zEx`<#*d?^RY&Yci|M;Z49jFC0jMkbEfHX@i{iDInkqF-Ij>dDl^_O1Y z$6l5QR+}HnL3}B)ym@mcZn4{#pY-9nf^KkG0;hZ&WY3VKz`MA$lVa3gIu3+f{Mff9OB&FZ~kU}$kur0wzxZkNFz-L4%Tb^DY#Fiz%PB5FkaSj zeli6z+@7_~TzBd2iw6h8##%Ojn)O@tPF8rggQ&j@%@@Wh&-{F~2_f$S%;-i_?Y5P} zW=}F=KS=!u$$c39EGf&GvnNX$Zr>z|?;I{=?URa1UdueF*$%a)f~$Vu0`W)_8nV(C z%|r2qGYH`d)V?A-WbxyVdS4X6D2)Q5oi(*V&oR?VC7wAR90ik4-wwC)jbDO-7d{^W z8W|^a23v0sKKGRNt~)EjiTKb6lt%2YC}=7;fCyhe3V@tNP~1wc2PdYmxTyP^Ms2;X zVK*Dg6C=P-qWIDqn64Jjzj6t`Y6SX_pEwvbP0cEeGvsc`@`4Ts`J!kYz)PNL`*sE@ zFIxb_>%;0X8l*(GPWIfh3peYh7Kq#np|r}cqYa;+10zOcNw2jUk3n4vbd)Y?J*v=$}9 z+p~{a%F!K&ZV=rv_->rk-#Zs+HP~yJ_!8(ib@G^cig0Iz;mWr4GQX7gUJLCXvN+_H z_5#j~{26WSB>1H~kIcA$S0*M;gblvVqvuDEyyzdV(P^-+ok9!R*d#9vLt&yVYh7*> z=~Qsp_WKhA_D)^Q^O;YPi@rjoXul?RiMtgO3WZ*3*L>!rx$V@ zxY*BXn^^;O^i3K?T00al^VAUu36*>V2d_Go3F4lbefSG_o$uN^mH!F~t@Ei~p7DH> z33a?>woqDH`Y*&U5NxMq)om}YFzQvqI91a2d7`*Asp_Z%RV8+Iq~p6@loHs-9`7Hl zIT_j*OhcdHMF(&*P?cvQS9voy2WD_2WK|3@830T`Glw0u(wEB8Ih31yw}_XF*(E7g zlfNrbUcl^jL0or`TOfDe`ME&33*vVlOytZeh&h5D8r7ROb4{1~QiWGbeGT6CFMRF5 zFNrTN_YbLX^|^%n6eJF5nf_M9hm+tzyZFajGUF0i>@JH*>L`JVK2yyXkeiM0 z|9Gws|NVg6m}YpyWv(qyMr&~DQ~(!vE(rs+7o^8QFIPb?xe(cr8&cyOHu$6^#I@K< zA~&0oSLo}M@l9Ptw)Kxztb51#U&(;91IS=56XzGh|()>l<;v-$0j-3th+Aq zgWzgvc09eNy4?^p*Sv9YbCy0%i@joE0?tVckF)vBI=ez?);OSJz{U(3e}1dKgrC34R_(eH-dwXq@c z3MqLM`PswWPmR?O3_$RGr{4`6X6r@z+-vx(T%c1 zDQ;M|k;z15i$*HE^9JFZF+0P=l2CP2vBYx)BwPRM>$K5hHt4JIKoI}x`qcQDYE2uH zzg95NOi8>pZ3=ft9z?CR-{wt@0w!m*aQ(*MkwuxBOl3=ghT*IP%@hQ8zpqaS#F-RW z4Qs+sP=&&vd-I|V15)#Whau_@Bjqz%WkT+IZLcT`bP^&K{Q`s5Y2!^p=X#U@P`kKr z`3Wy_$D>H0w#A9_tIX$r>TV%NKy*4y!fSGbmVce5oC z#9H@ilQb9=uNSf7^7#*8+&aiVnIpvRsqD2#eOog>AI;$0IWdnQwDDrxiX~pTHQ6UU z=j?OxZ~NS^)$RJK&m(hP-QAB~(f95rjmm(nJ)`jxje+vY7$I7fW)*%Yig+p%oif3&G3dX&CtvOU$zG(nvg5wWy}$a~JF z^GweTf>!z>?-4>CweH0nMDJ^oHuI8fNG_<#{<)j^ z)?ouwIG=a>CD`e2&zr=bI)oN~TpJi6TAQuo*c?8do8vOxG0uw*TUv_SRL5C5j$Uu> zs@3G9G`!6NS=t?n6hC23m6~TfduX*e%TR&oQyL&oqoS6PQlDnJX`Me=80x4vHsz!a z=wLCwxBR62>t2fqg@yYIijOiqx@f2bpEzVhjm}g4C2U;RY{QEWZssV#J!QopT1dDA z#64W#zj5~Dr)R&l0)d`aSmLqPn`YBs$n1yB+cFkqZ*q6SWCZ+a= zs4J~PsY!3&X4kFvEBiC>UC_-n&T@50HKc|4A@5n1!uCxY>*iw5EC;CVkV%la_l?x; zue|sBcvyh%-T5LzP}>DU2GAe1_V3@ya**vZ?pqS=^LjqyrW$*w3;IidlU;LhvEqvT z!?u$X2c;^|W#biVz;;wHDJ5Z$1{FRtdMrCNrm(a)CZ;QG**nM|^TADbx#<`oSwxf4 zv~2jJqGC*|J4;ify&(rD)smIMdHZ#_8FiQTy=wQ4K_>fJ&wHIju|!`VLFAj=HINRGCWBcjRO$u(TSSrL2`+_V>b zFe0|qtzp=EOa$B<#Gpt*cHG=o(U|xI&{MIA7M=>_$pxpS4hE!P!Jq#!_DUW4A+z-i zf%sW09sc}JeJyV<$2bvP1{cm()ymO$E52-U&A9xc^P~R^HTNR9}ws$C~1w&Y>n8VdCJkGvby?<-_@ij&MIb<;x?m! zeUvJRi~Yd+d$J_$_h&z`2uZpmGQO<(=!_}o6R8@Az85TUY2N&3-mS;Htd$08*s8zH ziy-K=XiQ?<%zi9>BYtPRGQO^a|-|Yn*R-zmVo&2 zAmZ<~K{#_E@5MiMV!Q9N!p+~H>ufw7=4Y)F-C_BYo>+8Gg%9?xM zw;QV2qGh$Ig^tBBYz;rkm@3pmy1%3g9dIDYa@MoS=cnD-jneec8Dq)btMV@Y>1Ul6 z?)0DnXURe0Fn z+07d3b3qbAlnu_$?Om$j5GY?u29Mki`vL+PD}(=WbMDQd=Z*oTWzi3Hm)?g_1a`MA zYpj#WGICSe+_c+$2~P{TDHb!pFNSd^1A(}ePqIXu2j`)y?Dlvve=)cXzu6Ea>Y^zd zkn(8&E^}4nny6?7m*J-Y(G=_R^Bsz!j2YwG*|OWsM#pLO_LGz3BF{l47B_HV{3rGA z2SR*}4mjJ718E_%%){E=e$w`~<=ZpN#o0I9))rysE=uNYf&=;J*=rvj`SRR!(oLL> za{?Lb-uNe-8Cz8zV6pV1)YI3aXIw?@+NnRW3y3Nk6|sA*l{i?P19&udXc1 z#jxRd@szR=!3?S7B>rMYAuT{H($`NP2%F-9Mb_HC7hX^+wMeQq9Q#RE!3^lY_seT^ zW4!P&PyjAu&AO3KB3c`Q=;aox8s}w5QM5;o?KT!02UVZq*jc*`Ga!ixwT?J*S~q*y za)ZzO9s(;<*r47HY8&ChEa~B2Mk9#>O=Q=OMl2YrH;P&FdATw)Fu68dpMCmT>hxyB zyP@MB2hi1gt=-rraRluPLJ$m&ll4N8=d zvzk>pQS+4$=yIJ<((jryFIHes!xf(Iesy}U#nY(lm29qEpSvxRLyhgQYBK~;NliNI z0-Kmu(_MT6OHW;zrM3le^iax9q8mwlqv zF1J!fExlWbCf+hG?G~~6!e!Sn4vW~$?5dvCJsnvY8RDE*emvn;uMr&Gx2>>tsKcM4 zbWpo$8~WVan>L!?Bal!rxgNDr@oML3MDL<`SS;Ye_zEuSI>qON5-pF#KHa2uhn2l^ z-#hu)K%s&s_+^i;K)mw8eC9@X?`&8+xR7Q)W9e-YJXA`VQvwR%+neOq^W(0S1aV`V zTuFCJN$I8R=W#L_G1v8kcFpviQnd>h1V7(C%vIXX^B-S99QYQuR);2U)L;6_u~~24!xt{bi*fH97S_ zwpM0F3#Xy6ut=2p&B>hUYnJC*_b#=+2fvo;`<_xo!9xPUe!uY~Wctg|TPp&(7g*^y z_~O=dsVP;%H@Ji&!&z~MgY;r;4QASY!F!Z^tnYJ{Fh#B$IsP*e>H;CxwR!IGCp9Ai zxvipkhxM}}#9~siCki9n$l9eU@@YPWfVB1Jj~}xInRo2LtluOb@s`_;9H~l(5RTIm zi*VBuOnl)XIY$Atr1AeQ9jNPZKgrrqWu{EF?=y5EsW@P13K8aJ5s-TE1BAk-lJxbk3$GJjh_t>m)4 zPGy?DN?z_}xpip5{Nda-X0E7gyiZB0(kwFHE23F6cpgHy&JjO6T9{PuN?=*c%4zf2 zSa#4Rt3k|5<~je^c9Gk+7t;;TPVgNby+-YMSSe z@WJb|=PJ{@8_X_-P#Cvka@g9XF!?YFIA)q93vJQKETWhVue9|wf#K{K=(p&qvFmFwCa{1v%F zC%BAj!oURksGLg2KO#0q=ip$7=ss3P4+*V$ufY5ksCRBE;57dBqs&aOv!pTWJEkN_ z@V!QL$X!9}ZLDd8bUmByZE5fuVGaQCirG=I*7w z3oIi1tX5aA15X|2U;fNr?5eQ?GQJ2oNry|p^{S;;!(=s+8ug_5IUl`qB8c^6uiW}t z37!f?WSePNE8J;Ab2zKtIum0%iL_;Wt@%c*f2nvO2sw0UF=)Z|PD#p6w8E|8;f7jt z4o%PRr7%D)byAujFdZUSSj)9(Heb8}%&&22P3rEWf)-~D7upv6TdUPzhn7SQhz&Hi z;s7iBbLv-2fqh{BW!Luup2qmsINKN!(^R^Ohof=_BTPbd9Aw4o=I=jxMYKE(t2Yrg zv9T-BJ3IsGl0StUHjt6vCCy`?@|F3Cgp&qayi_)`gp&+DX#iN#XH%B5A`Ud0k@{a5 z)yXvg%dN>XxsW&CTX3KPzAn{L;Hb#i2yeNp?I2&vHpMITtFS{*#y49~sk>gWQ1+D+ zQ&Ltmro)e}BYKN(gpZ8v*S)hYgQX6y#a^}0Zg=?Qskt;3lWTVR(IpdVT6KeYZ=4y3 zwTbglZnz-_U=b5Bm5;W0Bc6J=+FSF3n5TucWjjd}DdZeRAss1h9p+Zs7*oK~EpRju z*|wPPHk_cY>!%B&hu8-FkntC-bAKsI0X^x%B44BD)Q^$k=jjNQXq4b}4kJJ^nE$*QIuz zT4`TfmNGFuWqI(Cie=urVOdmHPLEw6?~esA`#Hr-F#XoeDYo91sI4RoKMMdQScp+U zX9msr%c_Gqton6#6ALpozFTl$GgVEvoHV=rcpNdkgu5Yk4fCeqbhA*$Z4Llxy$%ER zS7?UGF1bQ;5X22Sg==+bXLSVy%JD0By##5ON}N^U9VLi+khkPr&a)5OXcGsBuCj{< zg$j!cZduM~Eor(>q#D>X&CP)ES@E(N()HA|H!;0_kU%R}$Vw0_xL&Pm@RjGc(p8Eu zSg^4v>KXcl)Q@cK3lBGL-X&FGu&dJX_${2BJ(?Km#*%yIVOag^ypLdoR;r*)2W|Xe zIJyIp_OMJWS$=!`3yF>wrupg0JY;q8f$nS%=Y@Tf13o>4HaB^H`)T-%#B;u7C#$$k z10eCsW-4FU*t(;WwswVYKZh&?DeFI;aRCzh+Y0ax$<9H?+t3`A0MFz~3p(}E9aWgJ ziu&1*>q_TIBHTThMs5;rz0Hct3c4n8uvI7g6Z@XsbCF-0pFFSFm2Ts!F#l{NH9O={ z*fagd+Ej1bwV5FCp}dbik2pN1yR|#?Xdu*)16n(zY2n~Psku+ZmEpQ zTG2QF%jbu^(WnH&HNIa&-QqBD^Hds(Gug|(j!}B?aBe@lmYN}%t)T&YPU=m4P~I=T zPp*jvnv)3ytyLP9I_E1HhsYTQ*?_gI3ffv}SMt z^f>W^LsFCRe>2r@-E>Fer!*6mTv{MMd&JTCTUxOGc_cQ-S8JL7EC&P~67!>UD29j^knV+_ROi zRz?{2#dwBF#WR)K^pM~XPsY2mV_ z$&9xs&ol!2dbzFESds2EljTPt3aDjT*i2lfQ^~R{Ab*cYQU9Y-mPR8;AoOA@@cY{X zOVpwGy0%Wg>7n?thjXTwb5z?ZU0VJM)feWcsy7=4*Dr#)g#Q(ImLfu|`YBnfvKYs6 zp~{6}Sfo@-E_g%I{!Nwp3Ss>&5yb`g33JL%KhAnG zHBlg(y|4!H$34(fx5vrA6m!(Ma@oRXgPjP{6t4=wJ_-TP^woBSW-;Cc=|$HG{tG%4VPQg9o!JFjX%z}P7nqIGG)vCvCAYjT37QN;!H}_r zQe(%}+YQc`5DujPwFaKrW*au)TA{CVhxuONJJhXLpB*hSXs!b#4`1?V6uZTHHXHdi zUG-EpO_GqU_hG&ed6IMjuS!?7~I?%nQgtL>eRWPtQDZGtD zzldT#aJhl06lR`P{-qsXD@&*DJh=#H1KQutZEj2Vy2zGj=|HvZQ!?wkPkUz4{NX1b zZ9+LSP)_={icpG|!&hpv$H1VW6QIWJB8e!naqXnmIsaS~p(N`znwXN!(#UMIXFT?E zu0TwbgLbu+gUloFkCwl2X7F(yS}yI?%5`@G(AjfqjS&|)x{d2?_E^gGR)OH_{i>aF zKyk#T@f}Uxw%uem7iP&4Uc2NHE@&BSJnMe3aPPY-C1!DwWWDuX$dXOMG7vR#oM`4f zTlZ@|MkBMZ?{z6lFO8Hrbt6p* z7`4&-5{$Y%4>^;O^9uQ!eO}zP;d>a!lpg{LHg!*H;-!ODFUOMTBw04Kk^s5@OArr%Jwa{!xK|?K)z=PN8aE5WmcOC zEBOIpVDN||1Hu1tF`Qb>V|jA_HO1RXYWNV?Wq+el8a$gt$xAm*Oo{3dWypYX+SU{- zi;blWgjAP?)evLQ^&NOj#s+~t%XykStk=l3C5pn+cG|pG|CTEDB^OG|WK zO@GriGMPjtYrEiwl`O`9&slhF8zp9u_`K9>A7?~0Up!G0)w5%QgWbxnvXy18ePZ`o zj`Q=t8}qrayis#8Z9OHiy1N;6LvyTiMX-mnFst&2>zFL}ZhkKf;;!{Ptdlo9%N=h@ zgV{bZ87B=Wm?cwux!5(W7x8_87a>ST+SHTPv;@Ujcj;<>Zu`3mP;SrL zjh*Wk2)2@A_GZi&E@)Q@RX(r1b?6Q#>7iJ^xOxswa}8f_YL%h_#wP6)VLhd}$*OCa zGmxUm13E_SN<+;~KsKYkFq@;;W}q*^Qa&ETO727c3ty`O%Nb|0?58Vsw=pD!N0p87 z+TD^w!zqVpSxlzB`b5R_|301D%Z(dgWFW=G&MHVSh9STE^QPIzmfe(*YwjzFQ`quP|!}2wgLMnR25WRouwYfHlRjy>oK2|sy z8jr?5TOBGFxY<;t;~q9+M_033D`NLNNuyajYx(PB(%w6WZL6vk!osaQWbh)zz2Uo0 zCl-40vzWZ}_Z2UjB9eu6=0y`oJI-)_Ej2vuk^zjGm9BG<^xZcpN_>s12f@ZK{NIVL zBWs^KGGHU6ujhVtWJiOor8cv2rf9B-As~Tz4x9V0UFXAK+%Fl0o&Ln;bUSrH&l3%6 zW#DN60^_x!zub+;A)+CvdgniAj^7pgGK&5hKdK#g&;rvC?1{^YE7VROR7r$JBdDDq z+eU?vBNojxbv|&PZFd^agE~W|3=MRTlG(PiLJ;WLcq?MlN~g3nR5O6u`t!geCsmIg0@Y-^8S!TtII9aF zhwbkCwu%9#5~kqnhj zK-{oEEdMgb;;pXj%irHQtOCnEQX?}V8@oP7b~}iW-ta%Yigt2~o2%9~^m}~=VY`>s zk}E{lU{dLpwYsRPT<8vX!giH!6=y!QQft95yfKXR2m1pKcODjo{Q(OyHX$D#vZ}pY@7wP|{?|@`Kra?o^sIayTC3Nb z^F70K+S>e9I^h|HoCjEKZub+&4KjY;Zf+lF7himT0*d6#DU)N43+0R4nIlFZZtfFR8$Yc& zZfyWP3!pc09OhEaxB3%FK^MbMKgzE%xdaqw8-MK9Z`Q{-_?)SKcEaBKE=s>=zb&@H z1-kv>1hUq5m5r;gdar%@+9nH~p$GVTmXj|7RQx~bP-FAn^TMwDZ7tDV@jjMxS0mew zq6V(UW;xG?v5vaQ$dVmBI7&6!Vq@+8E@Jo>uN|4PJn^<#_30EXLVOZq?}SmZL^47B zbi(k8Q@2Ie=~+eA=JzGLs}izGF#)PoK>ggaCkrnQI2ZBKGJ|(rnuJX3m%zA?ZFbTs zKA#vmomA^+GoFx9x-7ffP8TjD03->^(9U_!P9@d7-zY?i(eTs4wJOA1M(L6VD+fXz zUYs^(-ioL~ZdvHg{6;_#R~fIj-i-s#;e?euLle?uQ4BQRtBh z2Y3i)4A3Sp5R(H+-}$ikb7Dq9;jz4}4z(sm{G1jd=nN}joE~wX4O)`7^JSK|PoKc` zz56+8I^`k8;L`w?EnOXjiR~0kj=o>rN@1hR;=MYOg6ce1VYf2F!nr+~#VY!{$Nee8 z@jwuF=85_jhM!%SWn6YfZRZBOX7nP=`Bjs=p-4;snnbbu#iL`N2Wn^mjm*|-F5?ae z)MrwPE_X-?EF~6ZIvcb=Z@(%tAX}hau%wLg+$m>G(iDoB5_DO|x_v9%ECARI@XsW; zHIyYkK_CW$60O!VE*MYMck15%laN1ItjI`%7##L6I#Lv`)K)Ub6zCLsOI6rJ_<01J zo8IXa;mKg{X;%W!EVA1cRnRLL>^owK5Tpu$a%+lLf`59KZwYFky|SxTNFo8d{Fm1= zD*#`ib$hYtD<9~q>HmdMd+?>d17oVjE%B^zw@Yp<^U+Pbs{&ru>@cao`Rv-4A}7j)^zj z+SU?OR2~7l;Cm)B?Vr}PH+5jJV|TrBk%p;7**OEV-PWzoO2@q(>d9iqXSsU3**p7= z)F_V(MEbh4c&!0$m>{iL@QgBgg3hyor*3WvojUkHD6{l129`c|!RZ6ZvI%`#O}VRZ zMx=5LKNiYaXd}pCjK&V>xO#gnRtv%HQuc)p=lFDyeDhlko@!Np z^qS^fhDX(~Yhr}fu2evSH&5nPeCw`C0_1aeaH>LKOb#CV*p)OwDxojiS5y63z0}T< z8nN`EIir3FCSYBfdUkpNRaZp!$HNKwg0oR#R5z#9vu<-2eOJ>zhtV2c&|v@*O_~Yi>8bmT-Ch;LS#}&S>zmU{+|V5kp~u)|jbMHI^KjC}=Qj z9I@q9Z5rW=!H7N;zT&!YsY&k#y6FSLo4;kA?$2*5&M+~B#nNrxA%zAmI~I3-7BQZi zVHHUHGsC2dktp{xlib!~efB%|s%`ZTqw<)7b1(i|`{%LJ`A@+BOEO&J17D4l^?$>7 zTf_PAJFKsDiTa6zid6qQ-m`KF5NY-gGmL>7t!}enJdUXCfPk5_G|eo)mbvxMqZupE zx5QI-@^TovC{p?@#UQr9*H!y%FquOI=r$Y7thj=R0Q&wt$|+sj61}mXX#*oKP#Agq zuV6-Z3`Z)t)9p4L(Kb>mXlBL5s_y~6!)@t5k@A!~a7?>MZI8s0T-Y9sA<;SC_4Ga9 zT1VGB5pdT$RJNkP9mdG5<0900HNpjXkzu7NuF2#fyXZVu#B7*K)y{A}LuEz4biDKB z_V?P9EuQR>_k}>lBd5)6LZVSlAUUcEtML-bEFlQ-w+yZ~D4*zy5#rC0J&IJkL38|Bhaw)wzqLFaC%9-yXfJZ{bz|(PSN>RdSFp(S|24c6cZcL75RFJU?Rxc^*X}Si5 z%Ie6K+I(L9TW^bOqh~s%5G|2fUYhD!xD0)c+|O|-CV#j`M&}5z4{IKTf4#%E{6Lf# z68j{_6O}u?2}=qoKt3cZHd)9C?lwvRO2iJ>n_Pf+5qVfGLHF8iB$DJpueTxHYn9PI zZ;j@{IMWoYOZCEFp$=j=^M?jTm&J5VXT-t88PPMYCivPGPyM`8VZeI5s zA4D35l5o7YvIhe=sw>uRilcP1#zUj!Gvbu&`N<^Y4{NRIoO#?vg@2~)p#hfHxd%hl zCXhTu2!Z8jKR&ofm3}avC!zgFH*V{)l$39d?3>~r%>%H$mc&X}WXqn=6fG-Iut~c# zeWw`+_Qf5z&4ewtGwWh33uSc9Ys!52Ozq0mWl*^JbldUIK6ZLXI`T0anW82b0y6W} zA%(8r{u_9(ec?q8aXLReX4(OyFm{^>;uvD3S4-n&59O`S1Q&YG_~Ztp0TC=ZoALFa zVwQKfboD{>w$lU;YS=^*X6Ii45cIN2`>bO9()t0%jr0~2bhS_$#lC^{Q9lYXHdRC6 z3|xmqSx0?5$Ff;hnH%+GkV1At8zm_@t6|2I7qS4_WQju)Be!@TF&%6?s(#59)yvhG zX}XWYPjk}IS>xspgF8O7#C#t$lne1$DS;LBJOG6Xk^eK&W?Y(cv43lSRhp#$a6T=v zc7+SIYztulU~BwA(G~%73&U_$5pvseT=9AIfHbZ!VqTo$Rn153(#|5KD2pU)K8LM( zRmcP;2*C^cwGw7;;*YzCxNlL-hdf~E?Ie}sus`F=`ut>q@PTS|D#mYn?u>y{bcG)> zYT$v;9CKA*SsKOw3-*$-uzh&e$&V51wX)eDy;)(HHfpJ!8q%k)J{Cfe?YtE#1x%L2 zS)CM}sdnd39xjY}_tET$E^*b*m0no>j$W5018N|TiFqPaP8a1~ZpaZ*kH%v%od=^4 z+vvk^U{)q+?mOnN&8m9?+bdaW$l*CrfQ_%o;|YKS<1)ti8cZ`rJP>fW4Eo}9Uyaj~ zZH#D&yyfQA^^2oGp;#|@+NS=3*FygEbD$va2BKLbYs!~6D+52(TF!U6INSd0@U6uX z>NEA=CsKO-ig+ES{abHy;UZ4`!at?49$RadU)2RsOmwKrTXA|*T}cvn0hH>B`}lX`(65kV*4^%+1u&2Tz6TcR2nx)qV^O| z3S$cCP;22gv(W%>#`MQN# zrT^(CDhV#uFS04hST_z1MBJEc0_a>dbA(+#75UJEstdTOjLP78!x62|Htm!%;#)uM z2&rk{K56Jgw!9mbhl$kjEGYUk5SMg)Ng(;%gtRP8S(Yg^v;LsBgjeTk7h9Ns(km{ z9aV-q)70d6+=lTEylz+|GxGv1UmC;_^DHFCZT9-Kdx&5t4wKmSUPQK-H+Ktvw1}1d z{&LQ4wbSp?4JVCj%cBkk040yJ7{~55@3t|`nU)$>0O75_u?$l~aWFL}y};ENpq2P} zARXB&1_HI7&b~gDtFG^MLw+J5m%N`(4|if2xzSJp6g@t_r2QR&qnjD;ZnnDdw?gJT z@Wa&8nV%zGEFR}89_4EnTOGDyo`TU%?l$KE>iH`q$^XNwNX^sL0LfLiUM#=rYtr<9uzJW2Zj~4=&w3$t(*>rcMF&&%2=WTgzC z>32!}8qq*mk3^&SX`rm76j$75lA9K}{Bz_>^Wn)NCRx9AhGTpe(Yi zbvdSGZQJS$^<=h%xnAjBCm~g-ACA!1;6Qi1o4fMuo4!e<0eV?x`EU<-B%gz8Ei94_6^ zAAMDb&T(|;ZB7)~H-@K$#l@~;t=;T+hg&G;+W`2eNOkMBwKk@+#`8z3e1x&9F_Hd3&4^6t@!>#Ywb@(hu^$rBW3O<*%Bbf&%~RLOWs%_TA3!_| z$CdV$mxbrENtjjBMe<_s|2tWNSS0_RdP*k~)Tz=Po|c+o z8o}$-Vg5l2o6DFJhu&B5~>XWGPVGc8sz#ZiH3NHzU%_| z5TvYBt(ou!ulqw<>ievg!Xm75mbn-ll3%4L>vN=+-fdb$Yq9J!jVZOeL`@8gN$f|v zw7;<`+>LFmq!_19scmg#wLv(^+Ig)0@h(?Gcv}h`)bNM=xOw@2&Qm|#f|&}(AfbUr%R5{fceFs*8%1w@Pud`kt*?pYyDGN0W)^)g ztTAJn*===0^_a%?;59>9t2eDwylnFbl(hmG<{bU*1*3w^9>4MRtzPPtWX}tU?4l(} za|aswDJ=-pKBr|tx8YY2fOIwP`j_jz2#gJKi^k)v)0c*|%MIV${R`a;o-nY!MdS>X ze;UcDe9nR7ADxn^tvxQWz_cpCeEtlme&(cL0U29MzE~;k2I`uOrV+kPR4GM#Y88)s^^-seHkL&^_!a=D(LnftrFi-fRZ_wS-HU+5u*{LJ_uV@r-e+aMKN!~jLlnke(mvN}% zvz7YCwsNcAMf`!{FZ0@oQ~UBRwOAhG&KNV2Y=Y)UFtjolD~4gO3uH&)HAQeyiF7^4Y89J1c>&@aDF%-KI<04@uJ|T z(qJt<%sdGGK?ADaIRVrlmM;sD`fAGrr{nK51?I2+4n(QO#S)GRB$t7&{C5)F_aQK? zsh(i%a0UD0EGU%rRFrtL`@s4=i(87o#~-+Q@&jWae!Au+{hw}1C*&|xW(t(`9xo^~ z_+<6mrcy6f>RD+34Vd1FIS0CZIstDiZS`S>Vh;bEGhBmO6Xg5xRC=>Svuf1hjpL6{ z03TUMIel3Aljn|u(ZE`t9i6P-_l{{*z)buU&0o8u{N?m_nXbs5Y<9=#FTbT^s07Dc zr8+hNtN(KT26Wl1mOz9(;h~^I8ql2qamV~`621RxhlxA#+WwZ!qEqb1=kkl4XY}$S zMau~zH5Wk7gia6Aom*WgpycV22g1KK!kFUF~4dTMiqi}Z-UxCTmndit2wF9okE&47EphbKih=&|bg zp0USajgAt4Nis2?cwd*cjMC>H`u;Ohfb-qHbNUGB5D-?~wh4Qsy}M%=1lmwKvEjJ2 zw2VddE1kT<`IiAm3Ul}i-iWnuSZ1V{FgYUUx$vPk4H~;!-n1%P#kHC_uH5dTHDLR$DuR-$tY&>ue z)cSASpoAEE_6mHM^`8N5pW5y-GMNZ9ZB7Ztwcmh*Tqg_lz0BCh7h|KHz)-0JqXzk| zowkvcRZ3sbhWssh^Qq_yO%_d#YhycCjs*!i{pG$aa8<4O`G2$?^k0Ho|5HTD-w&BN zb+FrCb6!<~+gqS#Kyfsu5hnfmnF?^D%fLS>mlr;jQ6(7YNHjWjyXGEm-e=oa+Z?%#7rAmgZGJ7k4lV!sDODwk9J0)5lI6Iu)iNdId<(LYXa_QPkyO&{>| zdSg#);=y|0_laK#hOsiwgouSOGkmX3*wqK9yb}6OCf~Ip`>Ym1;CJKc$Lk7nPCe>)RVVS~|NU%!nqB_$HUGhlfTjIqzQ*smMH$FIW~s#SWD@y1M-{6T!e>Fg z4O^vx#94@1LlJ*1XN0fomJy)~n^HnWEuW)fE*2vLnl_zO1R9%a4Xx%gXX*vC|6DwZ z61(&NZKm_RGn4k&=VO8J^cawtK%mDbsI3d+HvZ?u-oiD?OsDY5`v;p`M?ZVdfkG6!3J9gT<+h!raGs?2Me{)5|T@J5Zbb&p2x~hxI6PC4XJEy6nSG#$CbBzfJ z7dG%ldoOO~!edvEoBexEuU4dc<+yZhf=VZ$^WW~r>OBz?8rc-vae2BM2_Rq=&^PWzjN~G<4G6Z4d@8RJn)s$L5Dew| zQm*zmLfe@EKAY|b<|R<43M>44?cCZ5HQmc{ z!(HV)4LsEoG5&|ezXk^qV?~+si&{tra|*SAA(@Rw$;3eD4uSrFZ}f;DR+g7OXO5hi zmBY*fJqpTRu{-|+LkGi$>W^^CZR=oTuZJU+%SUehABT5Bg+aGTNXI5p)|vf+kF^h| z>l?Vzdru)YgC4%w6JxIycvnN%XJ?BtlMr5wpgRjSPtxLur7+mHgt4Q}nLy%~WX|UW z8}4;b%2$sEHt*9M_2e!!RGYovY_4e)Hr(Gd${d;#>x}q=HMhb{#EBGUBMWXDlPc{m z(r?b!ZLU#!8ipvgI?+4ii&Ztf-%Oo;H@JGIEIdAimf$$V8H+ymfoz0T9#)fx#p-XT9ba!-WhU1&r3YP()ouyby=CwwekwC?aN zG~j)6Fdw{Wy{Xa1;VNSd8t?t48>+%<&6ndn((g^b_8St(e({`VP~S+Ao!(slorAb9 zSk_+t`~s(8{9w?-W$Acg%=e4Q(^5l`xhc@!|w)-9ok?iG?u82Ggs4CVNeT(p2hr-VS)LZI-J0_4QoJy*4wt>^Q$qmJ@# zrYj=^va&_BZsAPxZDJJI3wB5L3gJAgmi;Dq?aK@a#l?Xv7(oe zlegDIWf_q6dl3Gsq!cTT3-K^$g+Ov4&7bLwX4B{7SH?YF+l1BRY*Q`1$sw7IAJ;ib zM2`N5TucR!RBHmT7Dg75P-gMU_OE{*ZmqusdHeZXZv}@Pk1j-g>DDJw$gPmO2K`dZ zV>))Rx@9d1Mu{?4#RRtxg_j=Ye2RXq^BMAqnjJVUH~H@7%Fpx<;8`2wxRt?p^>Rl@ zmKz;XMb~PpZ(mZG>#PM{{|^cfnxV38Yb|YzSaGoQHPTo;d3g6+(sRdGEr?ioJ$$9( zm{p*xlZM`gqSjxqtls&b*vWkXsGM|tL&Lxs8sF#0#jD(H25kgx3yuRi9t{>;dO_Jnm!^CIaw`z9zZ zUw_U-+ZIKxg@i8F!_T}rYOhBudb2D+NjzB8fnO~OO7#st<~_(Y%tm81mwm)t+h@2 zH+iUH*L+dcW$YqA;?OY=-?(eR!N|_vOu1 zU@Lp1bT63c9c@IO@B$90_Xb%0_1A0l_LUZLjIM2lK%iiuEd|-WvC=yHc3sqw6Be;k2yeHl-P@%$6q>^e zbmnUz?Wdsxi+#!HdhoL`uSLJbE$sNHZZTijYud8Mzw@aF=^w3%IUAudbKl zbH~q%{BGesKNj9z`qh?(fL8S6#>m-;SRFXeL>Q`(sY+kxELdd>LD=y(~xSVxELL*X2z~^ zdrC)N(q5MenNw+c?sg;?(b}VW^GAds+n-H{Kp$AJuW{TMhMLkA9 z=O-@!34IK7UC7Bt;~NlcE5u!TLiQ`v)s$G7B%2y1C<`0b@dM6BVCWO?S%a3CyvGeW zg}}Qo61Y6MH$RsK<6M8TBem>|sPRUc*{i05J;Vy)2braOt7&uk z(aA>V12TA$&%p0ucCKVsLFevQuPTkCTpBFno+$L+erj0q?CZ-z*)=;TmIojQvSjV0xT!vYQH#X|SArm?p4x`CCgJMgs+AIR9 zCpJ6>oMLVA@A5w&y63sj1I}9-L9)8%RBL0k|FFPZBv6Zor)(@YwljTE?gu5n_^BV8 zaeZ9XdVKZ3VC*;&KkaX)|HX*+>AaDL++I2P2cN?%q_YaV#eNpUsV`85fQYIMyR8vS zJ@agi=5{%Vft9vdJMr$Jo0X3qC&5=-n$YM&dSQ_x=c#DmD6*YKGQIJ7cE=MK=hL;G zjrydB+5Da~M{S-F3XO?0gcX;Hxb>Em+)Tc-Hg1dlsP4Wp0zk1d{ap|zE!!}UIdgan zolmLTdt`+nWsNc&0ga>4fgQo23m22QRN>(w*kFGV~pH;rb52yaS`ox*9G&D z*~#F?E=gkRZEb@xqQu%#oFcBQ_9&r)K-l(-=w`YrY|{gWJ*hLZnwUu;lv7h!FU|c$ z7o-yk5Ir5~3?UD82#*wh(*fBw$^gVaBz-PwlFQGZ~qVz2Jh;_ep)AQKx6%S`gqY2;lUYct4T%t5r1fV(b^rLK)Oaz^Gf%CpZDBzspD|jsP9HN zSWG6;_vkU*WccXHAZWbb?5%gL{k@pzmSmNC10EK#Mxi07HN2d@*qNpOG389=BaJVa zAHb4-m2xwFh2I0>(nQRK8J}$R({j>Kd`c+qyljbp0i$)VqL01*Y6}Sc7aaLMS;^&Y zM#n1&UP%`+)Fx|gVVX0~Yo=+{r;th*On0p;g>xL&m01N+BKn%1oN&!6?eF>NiwuV& z^?@)j&qs7Ojqtuzpc3dE1z@I5eq;q*IFzj*W6HdZ39Z)k3V4->Qy+&me{|Q-F{#B} z@)vb=b1ChD+f4sY@N9jv(4t;G`Kz=~`hx*tPKIH?BA$(YZor9_SlDPOUY z!gYapr21ItRCMxx+445y+;;2Zy$_fVAV1hh8YRx>bud)5^UY`Uwx=@y?>UJJX`_b| zG5gEEe$Dpr4)WPSZ7iv#biHuX{Gu)#Q&r7QZ|p=IYm>jWsH{$ZPTDS-aSTB}cb?r; zK3sNh_F&T-Csi3;;U)GYQQT()AgaW1_(=V$ZTVm*D9a#PhRJE`0{=XOTcysc;~h}E zCTR62=-Cuojma*q5a|la_07CQwz7(@a)G9^bfSaWF|3jr6kp50Z(49NH>`A5QJu5> zkuHV^{b9B@pIP4-+3ip00zlble`A{iIC$E)Ma+-c618nA9SX@Qw~UDSL6TAj^S+jQ z8zqX>uTBH^)9&YYz5W&?X3A`(a(h5)dG^r0}vYEL#tgdx2=SD?z{~$~q?n?e<6p=FUK#ldwYqG=r0V4d%NP}Nyq(Wf4XjZ9W2ev zCTCMe;DO~%RwymUZxL4q0nlJ1Y=YU?;o768H`_~IiI&t)G~{22A+?A9v1%@(c~oq66b;F**B7@tQRnyr!lOsJAG{%@KUdwXsG`jW9bFcH%Gj^c?W`J zM~Q=Z@I^{VRt{l!weXS+`gg=Eq<%-cLe1xuLo4QlaQaYmnB|qDe2fflyXkf7-H)J3 zJ6L*gn2^+)WdD*bqm;0P`___t&{cCGG$8v>J8x(@Q8Vf%qa zu^uMi2=@zHvuYr(Cj;}=9OI8fa)NlA{>t8uqmTK2?iJ0r+SdtNxe+t@R*XMxu0pX6 z321ag{jX|^2HNjC)I$cY+WZl!Sldn%A$t-!Uh^mdWJbXtSRitQfernb)8y)6it{*e zDfw@kZ1RlxT5rF|1C^}|PNP+}8lBsJV=Z^Qh7IqzpiD$rwC#nD=9U|YOj2u!ZXRY^ zZ4OgM$fq2vw{YMUs}Y8@mI7X5rwjK2^lJ0740?4WXmbGD|C8r!c0xaXCYJ z#AEZLm}qj3@KLMt7MZOqX2jWOZ`xF8C?&#a#OkxgpyF`B$Fjt7tJ-%MU@|m}P&>u! zmI1Y^E4&|9F_oAxP{oxn>L{Ef?9=U+@-)JpI2(W(A6Gcfpf$SjM}6NXTSHf_b)Q_% zSNbkt$!RRM{6olr&$HTGbIsN3lt?0R`jc{D?G{bBZB^FRe%e3RQgF6n_)zzrvcn_x z%^~jhJeqo@mRJ38&9^(e8TZ3b%jj@;H;8I!o0r@Y5YWhW#<*FNt0U_PPdvLDlKgXw zMnrkmYKQw;6zqcAJdEtRt@y|Y^%6E~ZO0OUrPG3fyLbIt=ds^a=V`zk1(B+)lGNzl zXSA((`RAs6IFVj^sGH{ZYw_@x5Jj&ZBOiz6O4WDBYPV*Xj9J*VGWybiAf432iTNQQ z6KJxtxQ7mZWWe$}ZRUgx1y`W}hRMsaJO3M;_=|u3dk0W4x=(DBNrJ@&!VMBW4{os? zI(dTbc)KUDj4I#c#Jwy!o}UP)NvwDMAfIpe@OG8xmK9OQR$mKgyYb+i6Q-II+`FAd z_z1nKbK%_PE2Karl?nvBD{@*wBnPcrMD|2Os1^73xFztf(6=`X$FaDnWW5}_rr!)L zw=s8I!g?u~+n2%ly+|hu)5J-pIvvOR!P@UA3qVLjc2F=j2aVXY;jY|a}{gePl9Y`aaeKC1YZ zm>z9Xb#iTZu^1xR2`clvfV=UQ78`K9!!EnSim#WN1nB=rr1N&s%-Dv!Ym-*+RyC^S z^6Fv<18m+xP$iCX=rOV9{?Ut?YuWyAcHQDfDrfC6X7SO36CVM#%U{L1fA5)}k8`^N z%y77hoOYA4w>(;RCnY};_GzR1jK9p`6ph#izIi(A?@i!dw2ptM_Bm65g1VE4*l+jH zO5;{auqO6~A-C7gpjJPR7Fc+?CB54)kPw-((`+o{_mu@%K$-uud};Jq#o&jS>*a4B zxU_8(ivpLQdP!@G?5l-s2AI)yFP^j14HtP{ix*k9P(Imk=+>kexKBz4)N*)+o@`A8 zz4|J6kL(0U)_IO5X+#&Bjry_(4)QS<4(bqd)TI<(^Mp*5y082VF9=GPRIT)175 z;O48ZfNMT+`Qf3x5b@#=+|uy`P}uc60SY^98^l$ME)T}7+DnhP2jb2bC`wejhcdH5 zQ4aF;$_e$+$EN(vBWyi`G)}=SyE{%l&NFFK*dH3NO+K?|1P!@r7eScFn{BLIXUj!P<{zd#QZYPRiM|zCEXc*|+w^id zA{WC0%H5<#tXtgX&WocM-$v9Y&7aCOXr6FA)sM8pV|hGuxk^v(e{SDzpkj4dp84w1 zdToMV(=-VKd(+&tvNh=VW4~wqRH)YuLR;lNdS%3=Hk7OwnWe*=j~~M6)arFByT|;T z=yk7Ku%%p5EcH^wO)h%K^nyKT_@qEw)v(yl-BU@N_YtW3k`Y9KkaDykNfLJzc0i>c zw1Ak*t*scgiB$$LpP3!ee&yr1%HZs3)4W#c1o z-(21m(_!E4d%d0rRo?H5vZJG$ux=mPa#MBuS4Le2+wyYr7Ax`22}R<^th7DoqiJ*U z#pQ!__Fz_x>i@@^^rX^kAik&YWq~y0aE#4Km5Iv4Bp%A0B2>Y%t);Ofs;QUe8OKjs zn)~HZ_KfM!;6h13(aVPoE*J;QTOY=PuIYdzd~&P%-TOiR!0UEbz5A@*es)~5x}fDh zDHUjda)`9j4#sMw2LBA~`7tgqJZ;maSghz8B17+L57 z83h5p`AL_HnVSh^Z%ww-->EC)&6aggtn+9y>M?t+8Yu2*LQI#)K<-;k_D;4NsX-hg z{jJNlZVSG6cf+`;WShN^8Q=f*k*!ITu9HBAX+x1m4+Q<*N*aYuIBo^Lf|!4A%l+*! zT(}?9enqN8j5)e7dC3N0pjdq*x^O-T z4c$8QmP=_aaATo;^$YzoS5B$2Fy882Z6Y5M30{<|n8xB1IS z5x{2ClXzl(IwMcs%s5EYcCm7CuDfu~%u|G!bCU3ZFz6I{u_|ENmFiY@;$+^*JWHXJ z(zpUq8!3~v@-i(PsA+dJQT{Rp>f^3d5-$GOBSrRo#OzmX%|k7jkNajbh3q)B4)Z2n zCU&w5WobOR!bysiKHUF?Mdx04DCAgEU}foKt;qJ1vi+#XPYq$73b{T>c4)Q$N+D@^ znQM$8PksjM>KRA4RSCFU2njh*B7t`92x}~BI26ZRbmsqwe8+r3=*ByAe8gp*QaDQ!MMkk>vO+W-bLX3FcZggpyX>$M_P>8x3uw6!At<^t6BM{@{w^6h(x z!Z@3&y$VtDsiA`fu30F!E#e>4au*8>jUAW*>RHv5BvQ-ojF6%CODzwYk*Uo0bP z!WFN)UOK&3MVW*-X9uy&_I>6--Ffk}>62`sZdQ-szWM^+Qdlw%E9JF`!Q|g2qPn79IM1wd z-J7x^Y*_J9&@v~SEid08@p3_C->>7ODR)qHC83(x)P!9f%VTHiDXnFKGtwstux@Kt zMlG^7cl`%cRl=5Npm4yuFj*F7O)fPA6E#U**H@DE$}GagYq5_M0i}nqVOi;*5Q?|9 z)}cj!l5~KMkECx*7AxL)>(+EfZ9XZ9AFLaH+!XuUircFzC4b_w}$wi8)}PM}PiCl)SpD z?{#02z0u%0i;MghgwLbnvXk|uSR3u515dcGA(|Fe9BGr3>aE9c_=tic9Pwdi{W2e5 z6IjTG!0GnMQ?irMCk>lx+)Eb=OjBB6ej*p%oo=nPzl%O}_e575v(Al6<GKdVKq^()13m5*GGbh@K6anmrM$2I-j6sXi9Np8My|X?Cxpuk67DSiTaypKXii^( z1G&c$5sGDeez76&)v@%hd#{`PKD`;sW4rm67L=VENDC&)<;`;k=U+YhF=@xk%{aT? znpvdSRXEtdO2hOPp3kC&KO`pEcTFQ}6~C${#R$n7D<8Nnm@2!o77#=ld>_xd4;?vr zH;Vh>lfdt)l@+LosXfS!;gy@0+p^1cO|g{74V<9qFLo-jt1f+3m+)+uZPjvn`+MdT zx-O4om=tkLTOJd(e23igIHfurZ|Ox4jahm^!qpwJo~@PGo^@EaDE}(Z#)=YtrkJ6J z-8fkxD@s)!phh%~)#iTCe`yAhE?V%G+_|9o&R@yZKgr6c8Xo;&$S%qux@=dnGagRr-sG)o97$i|(U%pegzp=?rqWP)Ko zQgp+Jkq<{i$GoT5k>~9^*R%-ddy6~R8#tgy@XldFKM;)OwN4AYlKSRfAo?%hBxG;? zh2eC+7FYrmDAcM#4T)_6ue&@Rk^M=}7o1o`JTS!wuNOO={r;E_|222e5LGs5gE~EO zx!xmzE(rdXxg^ZPH_z#U+r-aAXf{2KoN(eK%SPv4s1kOk0jb%q{vI)(V|QJi%Zam6 z;)lNTvh>elr+3g$m_@`p<>UL*-MLQ7e)s+6e*&u%z4vZK_d0AZ?pHI(4!L^#^NeyL zW-C?8t!{1^6*}TFwG%&0x!+-P<+@5neaQUe1^}>%)13(25Lu^aORwrseI{1YUPs7$ z=NJFxg2~0~y0x9#FHyc*loC~eW(MF=!eyjHsA2SlauVEv{(cfdD&ga0%Ei$VZ;S{6 zcuAj*E7hN}{pQOXPYs!z(8*j^d@l@nR$SKSC}p9J*x?dRVyZ3-j>VpP(lGQ$bFaLn z^b=k-Mk?cOl)SJ-C>z_Nxpem)s371v@PhyHQ(p4#2SRP_!Mf1 zg2+wFx_}jW>W_7&;3mP$+OUC=F~jS-+loejL0LKk8A&9-@7{9_zg|f*4r`}|b7Hg} zEG|nPMb1yc>~DHXr);bvQ~L{J$`Kw>@C#e!6`}Rr0_253Z^`ZD%^{>JvL4L>lIyZJ zfCy+H0k>IpxIkbctbE6Z0h#uan_8tgU`L^Z^nV;QDP3A_E{8gIB0fcsv-86mT(Kf3 zi|29{Nfk2tlbgjNH+~{sM&7PZpeCLdBxLc-Glnc3h@4IR$t0y@S67~gQu|wg!}}Yt z|B;EwE?6JwMX`!?a^KaLE7~v`ejP~yfq9zYRqUAL$lbP$6E$84d zdnJzsV;23;?OdfRqXxi4W5|)G94mk6ceQC-K7V~yhs_pW+E)`PDR@UVj%;l2;1dyl zb9|tQQyw}uxN;u;%jN(k^!Kq4^WFoPi0etBUHj_SY8d*EAFZ35M$D{0+k+&>HuaN` z?UTj(<@sMO-T^qdFwGQ~1ie;PO}(bYts8w+LTmQM|8GIZSQAUbywb zQ48~;3l@Wm(GT1T1!>j-b)O(a#tCrMUzf&I?MHxgXhresMlpDwEFi}@|6O@r#)iJF zxV=dk?JLZGF(nK-6Y7AfFGq2FgL&2{UK46bp=YV1XaMn$N)nB`IS6~)mxozsrEe1f zcWDDtVw5*U7Q)8wQPFlmqW1F$I|%NsaO?Rti>Br~s|urcRGn%L-FuuvxU@gpYy zLUk#-u3}&C-TaEyDex%lkluxF;CbYHSMcDiI=4$Gp41fC$b|OMth)N3-QOmpFK;-j zX-!!ChYmYqjwbATTOouzAWuRbD!5>4_Wa^m8lm#LC3i?1PG^5$Tgb|2AhKeTQJ>~= z(AK;nQuWkCv@nO+SxYNLS^4eN{yQ28PVvZ%KY2Uu^Z1d<^@*$?!nvd!)Y^_Lza|P1 zS&M|bzYRnG`GfEmfTSY%2=uET0mB>u<8E+ob=@2=oM9{Wv+kG=9QDbGBVt(Lr076m z*t|RMwba4Np7xa8v*Ntk{?8LguaqH=U8s8XA9+J z6Lx&B=acHR^3QjZ`T9>@6VxxEzrSQ{ZQqpCyylgVu-Oz54@9b2(C#1VW<{LH1u-)L zehMwsGVthi0k6VPh`w^OuM6VxE3LMxQ0jK)8F^aMuS07zw>Wu+uvoHAYW`0{ozMXW zKwt2)Q7-l08iczm>^DL{>6szrAm?17s78FhC?#T(z?qOq5`C;w*z9gH$!xn}*944~ zrG1qG(TezJ76AY#F%tldP9eUoKdaDJ{4zeW>vQcMZML;T~V)M2m(wx8nsX(@Gv} z?@Q`fK~bDpR8T#%dp9v_!3#pxliHpe54t{J(BqY4~riCmA*wiL}ahxjL~GvDm4~ubC?!s9r2V zh<$IxeQ#!M+9)qeC6eO2BQSF31_dbNhfE{nZz&_jribbM?_iL%?X{rgYq=OkaW(%h zY0&JMPU1ot*YNc!OV3NI9XmSbZ*=gYjDiV`qik9ra{8d3L`X_{!-<#M5LQO04325>$xW>44_;fGdAb*woL8 zm+82#&NKEh1e}lftc2|0-j>yByGDy-S&rQ3{qRWcl^LI5I98@rxJ@i)8yf^T>#e@{ zki`CXA+CKUwy)LF(hK<%ytEnVq_3$rUZ=*Gb-?)~9+1R?-2c)P&m(s2Ljn4VHhl}A zbdKgF<#mwLt>fI!OI*u%0aQ0i$$wQ0&4}~jJ6qqb0}ZT2Kjyx7$p1xYeKi<+LpMq; zjvd%9GE`w0q3(Vm+(dwL=f-?~R$>=~qC0l!`vrqMwI?MTEdnp||I_&J*DU5arVB25 z?1D%ug;^YJ5i`*QRKSa#J*|)YwCS^mI_3iT1<&(K=&~5RRV_AAcA;`Gx};eaekEvp z_hFFWx{T#m+LNBwhg2+ zi~+I~>NYSIlCFQ(f#svIL)xY6G+HM8<+FzFk#GFzK~#N_oM7kB86$vl%cviTKV^WY zYO2C%u=(|CM{9i5R`^s~RFaB|Svaj)25F0Z?Ds=<-+#Nr|4)+qk6@0O4(0D2nTL&m z!WE&>ciYXl9V5e6m`nNZ>@OJ8+AanfNRC1AEs^KNNPw6u4|C%LA{OUaZ^B#xqAkEi z3)HPr>??wmo(mv9m8=x|$cKK8F_hpR4^8gF&fVhPmsh*BdVDO^PG&^8twDZk<)$m% zAk3kon1}T=z7xYW(GqqXxF+U!MtH6?46(aO;U+i%clq^DJrb zPn%dOZZplu+L-CL1yvFPADPvG)f}2_smR+r(cF)2I0T#QHYl_^;A1OjUs2P~gKcZJ zn`bK6pG*okjvUsmgN^{*jf|760@Ybusp*DEsHsgkDnQvcrKZkBvzYNatVckKk?1G zIXUOm1@&7*&Vo%UrTa*AwFrG2A>2Vfx|FB&&f5hd3Q|ruamC)UA{Sc@EP9Aa>1+AD z;6K&B0(BF(pj5}s^cw;K`Da4r_5GlEns|JiudZPB9tmJEE^ktKIXtVwOp6q$J6}h) zk9b0GEA`FU9OHbM5VOleiF#NXsR#DAyo$}KbczBP)#J-MA$(rcpPKxjfL`iLr5|q;C*P|pHxBGb5;!}Eq=@IjEPu#>wc2eCtAh~33$we!W%(w4|%Gtj@PO9(gwg)!+JV$nQ5IiHz zKRL;y1Da?Cg=Iq{Mk$4h&*fygfHAl+l>DF5@3WdGPPh(U%FRWY?ywLNh&Qtn)=#QS ziZ&yhYU}2F3z4!uDz(wPo1@YOIi5jgE7(`6tJ%$>~M*KPQ9Uixsd z%fM@2qr6)CPAGTfq{~1XNa_bLo;TGWEoF9o zwmt1?WoTU4Sjrv5fhR4%V;atCD|+k{rwqB#a`Wx{NxT5gH3ICA0!ZMCu6t~7LReR^D?tH{lhRStNoy5q{W|m7 z!bT5hCcS=OEO6S=h!E*0k9m#!{gh#OLB$O+F zc|gGpL|27c=!-y_`#%~I@*BrUgKLR^1eA-m!$<0H^M$W29wN;GaNhHzgq zGykzS1j%)%ZBH0di*Bd$igWaMan*Q`A?JbX|5(4rN0ex8ZAaRWq|vyhR~x{ovPOta zR4&E38|o)zuNF^~UNMUI2y)pO-b^Y@`f-92X&%a`r}jfmlK<-iMz_SesUQw)V@_UV z4*n^3lP$Y+{#%Vhb0Hml<@-w|@yY)^=3tBkir19A`~YZ~svxqn{>CuAblBhck*W1R z@nhu|gz~q&FZ#TLu+gX`nsM8HyE(OLlF;FqZh@cM2C~@>Y8beY(nTx+ZWW@Xxizs? z7Uk2t$6+FYc03w6Bq*?}V8W0$?SzdCOyXLAzJhV#Qs>_i*&ve2U%xE{UtX<9p5y zhiKj2|6fwXFLudp#(iD&M?Kn3E299O;DyoH4`oj~yF*pj9=Ho+%oSGmHC7&QbGRNU z0TvZ#F;yk#=Dx#TLum_tUczZ&zM5!Xr}u52#Y*liUwO~m8>3OA1O?c5?`X^Kt3BRY zzsIT03GYNMIw5gwr5$!Frr&n6oA9j=3KU?|$ zBBehtNKw2u&f!Qpj$aGk-Q8nsVOruA)PII_Y z+*nD&ZkimeQU+}%sxaX)`+Z9!eau*6Gqp3JtMHl(`y{OGJ~GcVc$v6OiJ8X7_$ zp|->*U)u?G7`}#sF&qMb@gJ^-A~vFl38fc2Bx8XT`iTxe>~iTB zX7{2vv;N>>Y{vxEd9T$sT4{BrO72xcFPA--?p{q2rhg-z6Wp`aV$Hp#Ex#KX>%!Vj zlZiKOcTCb^4f!a~+qoSII*p_-1}d|&kN`W0;_y2tPkm3@=2q%hIUrnlD)5vd8@ zM7!)RhmfUv_+B}V3q;BqBXVGFoK%VRu-oAt%Iqf7;R2m;QbA z{uq1n0l+c}p>j+pyEZse>mK5P!wNZ>9P422t9cwEZlr^X~wnvX2MbUZC@v`j^qfo0^lt-vW=(*BK4Bpf zpPIYJ%d+v9C6x%{R(7eXcQ4%XonJNQt|{QPt0RWD7jSH#E2FZKq89UV{%(T!qv3bjMEWc=Rj%HqmdNmqz#<#=3OjxQOTp11X`80hFaYmr^)l(W#SZ&gl5rWk^I z{rH$>MF#yNJuPxc>^m@6(_qhEIi`SIgzHt}s$mY*fIdmjaIu$7nGR=fl4T>=Z^cM4 zWP3=y!v@gUj*`C^o}Oi|RTM7&7&K^6Z;THVYay#B6mK~8Sq9mP6KNnP6omw2&i=n zr16tw4)C{b2*3U=^8->{EOR(elp1E{F{0LC$c!Uzmrx^`p0Yz@z43mVS`F@1a64m# zg*C-A$-O9_*U%#sgDCq7lF%d%q=u0H9bNS!T*o+b`7{cC$_m{B4$?0d+ZZd<@#XS# zfpM2@El%w#5rNm=vGIXl8qQABmI4Ui!!)CvVTBvQ=c{r+RnKhvW2f`1K`jw(9YNg# zYr3T?uSw5ya>1djHKu)vC)!tfL&OoIE#M#p|7uA3?4Z7TN>bkQc_!Y=J_y-6sweb}`@LT4vKN{k7i&`U!Px5X@BF(Mf?f8({f$GB+F4 za$U|qj#9Dxvos{_&+*20r{GfJ;RfC6QHJ@Qu)Svxvtst`*e+@Ulgp1bxaW&c0lAPC zkQoU8?Ry_VU{A{Cb^36mvONx%6G_0$4Q{<%1#^@4w#ji9vHjT}fO?L{OgFkornN2@ z;K)Q6G=Cope(Mzb-X_KA$XcTsgXgENE~>^CGKrb;ag_*Q;LZXGzJI}9%TiyFn*%Vw3zOCdq(;f)F~Ikw z+t*ze%i(EirfnrG-7NDgShB67zhjh0j%_gMFy}#uTA~WvIdaGO$1UGIMt}YJ24heQ z5Cv{~83=xBq%Dog1pA1!bp;Fdgik>k5#6iL>1Jg6SbD)_q$$!=Inp8 z7S25tH?sxxb7l?>b>&)_SM?I5Css7cT^!pgg{4$ z01>!!){^{v2aQM$-5=fcth&GSF=~TNEVuND$B5up26ku$;M>oplS)=Ji~GxfFyAK^_Xu~NL^29qVE2~c3tXZc&?+c)XwqIBauDY*C4#P}+`JIPhKHr}x5T9W96WuPmMh3z(NCzFvCnDnHxk*nk; zWi{Xf{|35&52f}_r0j4hFUNOjO|~TyXj9JXIs7X8bjliv^C?#q#SQ|(rz0+cVIIv` z@-_Q^PMf2Rj*5S5PX4Gn%hY&$GJLrvAJl&0%!mS=lbEeT}tp zEejPj_n7cE2)awUe+GCep>LH@ojYDV2+!cHuQ@{?&bl`NNG2W)lnz}F6|9eYG5!G* zYB0h4%1;I_bnQa~Ug!bj1wrVJc{|x2VcC}Gy+-`J5?-R9ot z!p_aqGOGv4X+Ya%y}JIS-$_45iV|-8Of{hzg@Fl#Xmv z7!XaEe&HW|lN7gX^s)6krScKqj>Uj4yT{S2fwKRPtlTEx+20q7yI{1ToU!UxQC zjUb-Ap;hIl4bSok4#}Y6?c6YaL$&tX4k6{uJfF0wpGQ+mp&Fc0$D45HN><}U-fi5X zSCCzX-VYY5vfK@-vhYQWH+-E$A`N;&o41>^+)khB1J*b>;%Mq#JC9k70Vnh8e3dcK z-31cR*Z;@~dC;M3W^V80vs<0p*sPiu@e7qVdLlKxKX|tbF)t68%b^c422Re%kbZ<^ zhUTBMSw%+nEp|n}ZMhc;zE9G{WnQpmN-)6d6xnpSY$LP}rZ~C9sST3!HvB}!cS!aT zU)>Y#Hqm-uc2mw=_ofivW0AJRgTSE5=Thklalo$PvEzvsPAyxhovJwZmVc2~dWez( zlb~xiH9X55fA~!5*OQ>y`+-mg(0IhNj}M>aW^j);f2Gdms8sOM%AUfU=cQsfRo-NA zl>dH6#$QlCj*8L5I|9vPWSNg|ZZ*W9|eM-~! zas?0YVYy1jgtTsso8FU`QxmD!oex<^4atY=LpPAZDHC`PN4+9i??>bj4@)co{IdC> zrx8&Lr=!^jd+BXgFMYIRHGjWPCY~9F@!AOrZnO3KUEbGHo|%U!@=%CCO8bDaUp$Hd zX-rf)@@x8T;|DG7?DTZ)mbmZz$HpxH5Z?)V2-N3{wc)_In9>^huyFL)D{O~~myo<# zG4G?+z;s78dil1dFYp>Zoy%2AlK%no#q@@cCfa%ywfuom!WzXJBJ*ek;tkiO*xw*E zOD}ofu^QZp?XFg42IFn69Y z7S*Qf#+sNcK#kmRKxRq4)8TUe$w?x}vZtz04XH=xbpPoUT_H!!?+VHAty_wIa)TSy z06+NvmNlDV)2Rurw__U#k<6{jH1ce7Z@&||ZFDP8uAn#2%~h}LAY_nTIAM`b%U-Jg zH5%Khfr{RuGq2sghNkIWB#AB{bElr=}wmrT5XtV<*8FVwMQ7I#pA6l9HR8OJ# z*_c>K<03$z0REga^f1A;47*ROZ>6jDw)b$vZC@2CxVgcw51#8bE_8sFr6*&Qp%W(K z8udok{5B_N^&`3uf>m{YX z=gb9=HLOLRzg(5bW7#%q*vV z;xa=S3cXs&m6`V{fwwv&+Z*!xI;UDmBAE6nz|g7>SC5s9I~hH->z7e^2_f?bo~P0t zuKC$#d9?FL20U`bja2*~xRqvF%HDcjBfgL83A+H%`;4x51y6}UTGy{jp-giy~H|q@J5~+vK@H1BeU!lQ_j*pM5v1tv6ba z>B?(iPax~^mBDZDAxRp6zmU%fih*+zI}VVE4`k+3@^b0(2&4;ATsUwYldTLJ4b$-Z~72fxJkdb>w^%b)6g8A=!fOB2iJIT*;drm~7 zga!L zX!k1!d%@Axg)E9RL(2hgVJFFp4tXWaqZ*VelKW}cJsjHIvVdD_K4C9=<{%R$8SMC- zeuPWP}z&6xkdyjP{4m1wL)96|gpalV+^iegB4-^8{G`q6GyfXaE1=5R0rs$=5{eo< z2w$709#5VM6ZgQXS`1HZ= z&q6iGe7Yq92JsB-af1$=n6+m0z+T1xnepw9(9m}i-Opy=Z!q2y12R#Yt5``*>{J&%?d1!H zH)f)DJu^Sg%0JzlygKMjg)es&h4lDibaEIu;teCdr}j?rJp?HJKgGksBo?Dmw8-|7 zo_du;oye}lcjN0XXv@-JD)@#J@dg!k?)WkB*B*L5w(zlC9Cl{~e@C7^F)2cxDap@n z2*0bMLgvXO5uX`WU33D1@hkC57VndRh?KQ@V3?y2039#x^2J2#)?G_=^Ds2nd5z6m zp)Q$M(_BD8ac1W#37rnvk1}rgC<|b^jx44GogPMLy~^M+wk{3*D6(^UlIl`Rw@4{@ z@Z$x9|D51vE41>uSuQ2{ zxC=S#_AbZqhx9+HJJmsyk3Rc-@{G>TJqJ!QiHM&H2T?7qv2*?6>JduzCBrL*XHzvB zaIbaqb)#|rCX%1BZGDnLwg(Bis?7wHUrYwmQ(f7S8R}^@uYvRiBh`{}H^)bA>M|>+ zHWo;={ug7U@>~&fRA1^s7vGf3Z(N&B{ME8ghq<2i9&y~3wqRw`xzj^iS?C9>( zw0C6|er6@UIS%oLu}}q>JHp7`g&K8`Ci9O;N_C@VBj;E-wH4;XIdg{P%ro%@)h-{n zch;&*I--|K=G1R4^wq!o>?lJuurgVmluzol4l&cT$_Yza@Hae^e>*4s(LEo;>w471 zz4N|N35@L+duG2+E`mAOM=O_5V2Z!ZB|I!SUgc20nES!7pC?#SrDvfI?s~sGYCJA# z`aTs++;NDRZhrDNV9gEL9)=K8i=KFxv#|3jM9MiJHPfa((`J4c_Tr!F$M}nv+!~9 zLQ|GD#ukBIB7}dznNDDH>qDCg-f? zk;-DHDK6-|n!J+(!)ue?9kS1yQrTAoxV{wLFdJr}kouL2{c@_C4jYjs`opC{L%fHE z1+;@KHRH^@`y^e=-Y%suPn5s-m$pmE8~fnSIZ4KUApap4P&((i2^S94)g8keycOAd zOnLi@V6CA z{4A!&Z=z%+;|pa;HLty;-RSc~g=ga|A@H)cs&s~S7ImUE(U#2{XW~l0h!2cyvw_6% zB3POGMVuk!U~_$;<%ZVCwgA_q{HknB%Hpej46;xSaE~VU6x?oDzN}A^T(ldRFrTi` zuMBHHbJ!qUo1G-1fcb4qYFI3tA!3_nIgg&sxUYa7te4JYVGL+R+8aSBbCoU9E%FC9 zzq?>U1Kp|buof!TtH-#yepE+fUNYyLIN0N1UnJs@ZI>UGycqrMM7VB5 z%szb`*xY%$f4oiM(vr&8r{6L2X5aJ?DHS!@qvgU&G7b<^iXVP9s9wKvFQd>@)_*>@ z?aj$BEJB-aOtikwcx4Y6o#;_W$$R8JaRk+?3Sz?k9CY=xZwbox%iey1QP31AmkH_* z8P0*d`1L2$6c4e3MmqDm+6lP7c5T^z8FeySwkGA;M((J&~{`$gl z<&9x8KC(QE^&bLU3BdS~*3bIARHd`%g=QIC_b_HvU9Y=4=+0*pX=4 zNHC4&f9@yPJy&+}eyWF|&kRqLws+sZ!Ll}N-2cWl_Giqncu?wG0>y_A`%tDw6@F9o%B z))$9TW^UFGA3{n8%EA0glpMzDkvgY8>I<)T*T3$6{#;L?mqKxFGJ8%GHa7oey({Q>w8;f^4avgWM@zPgo~>IkO8^T zu>K~;T=_Yx?n~Izv?e!0LfA)ZV zC+721Q#B;vJB@6X*3P)5)87hvUKR|83=i6pv!6i5kX3<0Rrhd^G5UMgHZ88wx8~ya zh2Pzg-=7?FCD+sMgttv-HtR5X9`s-kZq>y!=NOt;`2yIygNC?Ly8C!H*fPS?X^R3J;z@T<{z4b|gTDwjM)d`C5NugsPOA3cX^s+t_tymah9 zd1ltFhlF0D=&;fGTG>3c&hck5dJawKldsl?RfPZV#SsgK`^6wt_#vZ6{n)s~HXH#g zq{fF2RGKScVOH5cq3^A7&4m&3(`y6BsNVSfalBjGq=ir9OcD2x9ZF3=pgCLU?Q%eW zWU&o=Mwk!$QYl#OW=yx5E3W$b2UADZO|eY{u)#%MT9O-N{F18J)@*0r{qnZ5#*7u*Y}dzEHp)p& zqY4fFVjz&WTi5U0TfV?InRdRHzX%^i9`p$L783Zy$+!G-hzgPZVhp#MC*X$9{Vi6+ zYvS4XL!uh7=HbR30zV%PVY5>sy2C4zO{@kTOa{>e_SPI2U96UqRYlHUFgdWy!zF_t zN%hJvHAW1uV=?#ibzc@FN+tN)9N#Jbr>tgJ7pL=dLL4*+WVEOI)C-(yqXJ_c9ZNsI z$&Ir#1Gg20yVQR9{bAy+0%Y+}y1yJRy8^;_Q!B@NV9_V@;?!PU5|+dSE)YszBJjI$ zYY4CDnCIr}Lz*<$HXT?dp}E|m+T$tiDaWf6V`2=8NSp3+KZKelN;VsY#K8Q;#i1*I zqP7QH!bM$hWgW`o(|HF#95HFD)QA82ynj)L)$@Nufmj+0dSH{>bq& z?8xeh)oaA2`V+n<9_H#w-v128At^~c7e1Pyn@^JdHcE|s{cuXWP}|{rsr}}P$TnT* zF?uH>(J)<3SiDMGs`tf7K2SW&*aAfM-}HI3 z)L6L-_kT+Fv&@pDE-j122iZ1WzER>d9K!e>%yvHqnRLG?Y&PRpLZ)fQH1`%?XWn!TkeR9F7s7oktQ zL+tEH^37WR=r9HUzFqtPJB(R~Q(qoI_Znd;f>LV@nB`pQGXC47V&*Ro%Ed`uR{$Hc zwhI^Vr-V%Fn^Zka!M@7B+S__r zw_+F4TA~syFR?UyMSQ3w7X2tv5#8dS6+)CQ1-6oT-qfmRg z{SZBW6a0xc>gjZgj~S)&i^mnTLwWEErx`Mh!o%gO?^sTD(C9hx<+57wi{w{UH+fTC zoA=v=R^%otd^>gbri`}bdCh}(p%~h5&8Vz#$#F>Ig8+%>DWRWcFCI>V#PyWkm+WB! z2b`Gi%LB_Dg-#5&xJSOGQG1*Fk|g}5OIh*XV_`E3UKm&^5(G_Q@qRCJAqugFTio)H z)Yeng1mu?&*_DUI|K>F3Fy`ZbsPK=};?&*4gEw?0Tz#gSSRYMF^L1=gJ~x;Kl9Jmg7ZVf9sSz7*|PaewG$z#?%Kh*55FO231(# zp^ub!sfw!*jaJ+k0~U1qfT@H1do|~>1){6+&hImAHf4A7{pvh0mp?!vBLR%78s^Qr z0 zHyYVX_H4=osGmwC!AQ*ZNYOJy@pOvPE)(9NqqQzq!kdzJ%PLJEyuIx4zr5EXR`X%%wSHdGeL z9_%}lrhG7ESGYq0%@p(Ns-7mP1W!fV`OSdto*Ck(`8`G4rhE+Jv{f?$QVaW9BT(6H zeW2zifDg@-DW5&TaW6uv6q-s?>18YGroSs4ek;G;XyH8n6|}H3ttbMnO|II6b9QBq z2RmV$9)K?oL3e>F+DuNU)HqvYncwvETGfHf%mWOMxhO{0)pxR?UJ|&7Iy+t>=5uM@ zuNyk!{-k&c&-U-!5W8ib8|nItNF4_9@vc_s0661odm`64O%(|d`TxV%dq*|B1#P2P zkOK&K4oyWs6zQO#^d=}Gp!Cptl`buGP&A@+k={EbNUtFjMd?kX1PE11qy(gwKyr6H z<$c$^_gm}Rf4HKe`IWtAo|)&F8O@mOA=gk=vinR=HhYLm*t1~%Up&eYpUH+#J$%3U zI@@En=tZbGh9=no#cz$=s7tkqWK8Z z!gmioXDTLvR&4F2EKiD#c1Tk*(&8HgT zQXl@|tS|wsb*a51w9q1{mB#v8b$J7a2&G;@PeJDNBsa|s-l=8S;^Gm-Z62mL`u?;w zqZt#PbVlb|i61Y!mFC6CX**|!n++bT*95_~WP;q1H5snO`OKI*D|eXq>QP9m=AR;4 zHs7mDD3|YzilR#^p5D6_<6mEgTc)0K zd*q+R>O$LcA{F3yNv5pgATD3JEL#_Crvlf`X)}hqmd0FOem(RZwixO-GM=l;fy{=P z2ihyUPg0PNTphj57CKBoP-X3#o|)mIXmoM?0P*d6U6(^vqMY-IC*kxYE5^1G%*6h^ zVrfXZBWYMpsAZwxzLeCysLz?}_12x zUwu}@+4oY>*q>&)e!7<3wz;+tk2Ql*;mQ(LZHKR1@pWT^QL~4TePSWc3OfU2{_|+tca%+R_nXXr5S;MJ2#D zUL-kYLUAsX5Hu4Z^61mbKl731+bCVh!n|kUdcqv3b*Gn_iriRGZbw^&$G2D1 zk=%({kw*Ya?tIT}hq)bNd<-LhCo}nm&j5aQZjS#$)@+s6kN1LBos7X2RFrC9h zwvbeL_v6JWe#kQiBQsxBEU4aEbyq<+Rm3<-Dsv`Zob<^ zxw#UQ5;-GH)yQ{PRQD;RZg%hIwGvn*v)AYmsz$jcq)De9dQ!cywyB2!oveSaMP|@U zQd0L%@auh*A%9WgH-AQ$)!|QI4YcCQnsZwrHWe9;mt_faAC#pyBw!CuT$C8)CR&t2 zP&R$y)nTcn^$6D_6Gt^EkTc70uSj@i*jux=3KC$qXf}>8s)dfct3xL1->O2i488>f z5l`Tc*~gJxI0nR@d1Y)IxZ!&AOR--j@9?ZL6t%GPqT5 zuvc%E;5?{+a6;sFCVce%NUYU1O-uPzZ#F8&RzoZs7~e$dV>!H-FJq@B|)5jg=g|8Y>~IB7K07KD-+%K`M|M+>w!y+YS_&PionrVjbR4Xvp`%I)`h zaq@Q`_4^7cj19bk;+NxO&g46qWp;7}+9;RVo2A+Yn=aJJtWOA{Tt<3R(T-XS9op?J zUgE9ZYsBX*Yg4|GlC`fc2AKU?hOGQWM2;eT?RNbN_hz>CGuUL62O%ZhTof}ub*qh9 zdR+XBf1d2*NctWV!i6aa3q7I`w}ACb&-J)~etrQgUC4zajEqK5hGOI8CeJ5m$l%#rSGP1Xia~R4! zK7{fREWUq5W0_(0jclxRAF~%3#{5ElB-r&-2ZclWw|QcV5@TFqkkcT%Nu%<#?KW4^ z5XpFD0+~?b_BBC5w}ng7p%rYfC5EeNb}?MiC60G>Cmi zLem-(v(Z#xL<4!_<7QS{*H%56CyW>*bU6?*%@;t$f$&~lIDq;nT2n>(F<7Ju`@l?l zXhLG|LNvSG=9#zFgj6rxWA@biu}~G$Yxk)(pMfgCchL|E@La70OG2b%%O{_H4?fT7^0z(e+3JM&zCM}A7@dZGK^i760MuNjBn0Xl5!u&qAA&PpQk(i_OJ3G>@&c zMDc!Cq>4Ox6-+Hh9E=$V!nGN4^5+IJyq@v6cL!ukNoJ4 zc)$LXw3vOQ^cfPvH+J;EmJq9|0Mpw&3E1Y_mxijybG%op?qI# zG}2Hc5AtvQ=DW4@Pqw_|ZRLTxo6+>V#cd#|^rU-2Plu&u7&-#gUh|p_V887-#=Wz%>Pseq=3otp z)fPe#CgMG_7k2sHcIV)HJX@HvUKI=++f>O?Sav3;RxR`>f6g|TW#N*@sk;t&h61b{ zv^yEFXOUBE5RCNky4C=ap*E0)x|p{C{T%CitKqKD73L$)0hHN8%t3twBRN^v^uZfb zk%7vKE!&q-x>9O-glEbf_Z(_602lsy-46z(G~iQq_96crzns`&2InnA;t_9!_c+{# znLKqQ{Ei_;QF8w6a)(-vsn1%-ltSMX?sc7yp*nRue=Ky@tm?)pY7$$e04Jd6b6gebWG_+lD-X_tjN zJAJ*T;rUE3ndX>Yh8sl}OGs%GI{L*)5j5WHvFma^LH!$lB;vWZj6=R@xK4ZFj=B>z z5*v7ItN2R|Qf(HT@1xko8F|)Xu!$ig^X!e;epWj~ypHxpaB!{)X zKc^B`GycV83$Y(dh|Sv|{wm<7KPxuL4vWyG{FZko1Ks9{Yn-*l?-(i`{+!_`N~Ion zj?MXaRF32w+~*w=x%>DtSIC|aYhI|E^kzds_2%H$GD)I|W7%xh`0e@Qp=ism`Silo`N!hMn?4tG;Qv&pS}PEUR?BVDD?HhxB%c+b40R~O_*`*KEPK0&2axR+ zO%OR&;bfC}$UeeI4qtBBkM^W9v6$TaaC}VJ5+>sx3^D?BY8`+>i6cn^7Anvewnq!4K}66+anQGBrA*dlQgyIXS$-1C z$*%ifB&FXQ9ZNU)wBj6DSLllAQR|5b7z40)3D~)WD+mfIvy?c}*r^J!|B-A6f z;+rj6{=+4*Cw7mC3w;T^p^rgErh@8?Zz#j~70??>8&D`7_;#TJTG3!vAlR^_aq-__rq!DFFtel zS+f#ZACXSh7JbElAsdFi)WhSzyK5gHlsTNZ7(_{iug%WK`TzkH0Es>4%5$+0_6Vt@ zC1Hw`*J#xMlcUS=^hCczX7*LvXc-CbUuv64=vl*Ob|KrgZJy0*CRpsZeN@8X36Fpz z$G%?yj)K4IXjUz(#x3sNYb;TK=bbLLxcjBJ6gpo{tu@Q1#FTmwj2S$FWnYWE3LcY| z!z&MdIZ?X-OeIk=!>+HsH}c38*?hCm-^CjG?zGtzb=+|eGn>538U?RRXr^bJq4v45 z({&wn$#Xxd!wcCbl+F1^&k{4>F00;Uo45jU+2bvcxAjD3n-Dm7!W8qu_43#Q&{w#f z-d|>l=T|e+RJTkREIbarbCE3Jg<>En9E}`?q@3TT`TMOsjspL(*h>NFlXZ7_D~HpQ1-qa4k!EV?}{5wR{CX z@DeXh{_cZ+UqPE3nK@1SyrX`WSh&+HBTG2BC@r#l{_G7hzALq}5H*V-dv^z8B7oJ` zHGDZFYmI1j1}}8fNN@%_O|{MZnf+<1R{8SXHE$FNcz2QNGQpx6TVig2Ea^`4Q#;2~ zG>=u^9)xyKy&Wm7F1UN)MUU0gFuO!nv$rGUuDFSNJX|pg2sB@WTmA^@5J<6R7Jx03 zU3TiT?v1>{igNqrxrO<~+tJi8nf!9F;WIM(PuZxWV3;ZCdpsh3kHvctT0r%vepi0r zin;uWZMFNtBYTsv<=e-Tq?5G#v-(jA!0OK$O}C$~*GAG`+G_JBX)aRJ^}BbLOJZ&b z0Hm#{#q&*Uo)%@{y)pl0fmUKD`Ks|m0*8^e$16|f=n8%TNMgV|8|npBQLnA5=696C z74Se}AQQ=@vz)eHbP0YUe2E!M%mWy};!ggrf~SHNTTj4=qzw zMfa=4>=qg^&D{;$HC~>yq<>n{3>6_AaTF7eK-xxNB`XK})ZOw3)-!*2cFzoUwrtDi zA7%G^6@}_5G|LSn>W&2dnAw1mM4NoC zH3~5=y$>f+!WI`BA|l~t7$JiQ`w0>Pij@ZaZ#_V@vh4$f6825Wo|8Ny*6P#P+kIdj zl+&gH7ehSW`m+-V8B&Q-_K_l>xY7}wzkGf%vvK6)bU_=%Rl7=I_RNtrL}ziQL}8BUhsT!9ZWQ-CIxuFU{mwIoWcHD9dATM8Fwi2F)e+O^ddd!k z?@rdb6J-=V5S#{jj=JTJ`;JC~LTAYMsQ7>_0Y%SnEiIuC-NSGXaVW4&#!wEsx#5l) zsVO0wXNSm+C+J!y@8-5-*K@eDFKmi|^#`2?uBU+yEI?X+?FNs&KN0h*`Uv_-XgQ?y z)N$1dHLJV%t#{_tlcQH2R8bHYkBYnM;IGQx$r5OGustczC?}Bg6NVhfd>4Y@_qHPX zj^TOhaZc44#+_#MAC5YiHq6fwO++yhEd!;>mQ61Br($Uv<5OjnMX^(KU!=KY^u0_n ziKRs3cnb=X^%sUP1AUrH(qHJw`_xX@q&>1jImzFMH&i{pv`zOr1kq&zAE^~2uZse6 zoYzLN^yc7>-LWT>ql2>El$j-d?l@px$eQhn&65SDj*;=6SsysvwumipZ3m0I|NqakLby>P5BTN0>m@@{g=dBCE~A$A zY1KUQ#p<=pzeww6GUEcB%D84&vbf!5>14W-3tgtYKVvh4@`O!=s;M3N{J$i}nA6EK zW5n+j;)XVm#WsQgl>Z<9V6p;dT?WDg>CXi?H^Pm5cn9{O3V1cO8cm}k5+{82>Cr}M z1h36XrJQ?MlZ%EwBEOt}-~l$H71()d-&I|Kk}Tdcvl*vM*$cn*Q6H|3*TIgU9()O) zG9rjMg&OXhh*ILS1kPhYJ3fr){%KO=@*nfSPqF_t!o>oAyR7?;;1wvt=z9J;{k0mb za_uxi31Qx?mv;^?S(~vq>E{m-&RhG_#xObR{B-JLe3yf=@tU%y6^^^JS!PhG~x{}CwFah%xOV*tckiaP)<%9{~&&S zv~j|pU08>()P3L29#;}T_)v+_QF-8zt5@a-FA4X|y^o>$LI*X!{9Ms}zq8re=4rWmn3_=z?LY`5Isco<&7LdvPs$24JGEM4aPARtb&>K33D^1nwryzE;mi8mW5>otRUL;1*Lu)YYtRrUEub;BzU7JU%+z{pp#i`tZlC%h* zmrifgDnm*}Qf_C35;%}#VW}K6EF-{n} zAV)8MA?i!?1GcwBXF0)g#dN;4Bdkh!5qf%4;(+jE+OI{rDA+%0&i$w8o>VZ^7_V-! z$|qVw;cb_JGi2Enq{kD>(0GhnD9Ui(dnM%6a+8@`!eVN9Jo|*g*5L?vN(VKufsv z@W^N97lrvm!S^Ak9&ta(^q=hDcKoCr-xOp1{Uk*T@eJp_6q;#OPpSd<_lX1k^;fEo zKMRCBR-fl3FB;j0;50_XbnDNl-?P(P-(yJL5$Dq}*l0(shsNk!!6~3F<>B~zi|TTu z)ZI{x4u;^qM;BxebA`Bv^RQ35fw(-gA~fqpo%h;7tg!X+)!~K$yhM!IO~cxIu)mbg zxA{xS*LP+PyJQQOO0~x*SZ_*%dgi|{Kez6dhVeLGv zj$jWn(<#sMT#~$liBI?KNA1TO+msROfMW)H*~sX0BDO zFwLBO)1`&|dk4vfWA}ku?i-{_U#(daaGG2ORRu!(Mw4_}EZUoLQT!sX?j|v$_QG6T zf*qY+nX$ZgBr6QRFpOU3k#)hF6K9^)u~&U{ph)Wh8fRPO%ANH5r~Fhv8cY#$_zhIn z_@D~CYBHGWzskK5yF{ut2kU;OPJ*O)Yg2uOpW~Lw)J-UXMWloDI?#!1Q-l>hT)U9>< z_WFk>>d;#Hk7Vg~nzw$s4yD-V){f4$`kXmvx(jUjwwIo-;x~Ulrd3rvizIi4TUMmh zyst^=Kj5AqS3^(ldORbKv}%gICaeTh)L@EV_I1A;{#sKArcamQyY~H!FbwVU%md&$ z_u1-UMSR1jC!ZYDUkH6vG%T!%0{$Ob2S?bmZPwPXPiBQbWF(w)9)}p?K!RDGsl`Eg zL-KE3x2G{%cIy<17%m_%*Dx^vs$`%UO`aiIcPa%S(|22lYi6y}(ExyQqTRoS+4-#p z7=DKu(`KmK{$0aCwkQva*TwOFq_MjU5!m4yFdhF+)2{@-Cw}YKU9)DhQ`vPzs!4fb z@X8)@&@*PM8UH>`UAWF2wb7p3Z)^Amc2tOF`5~eFp`GYmeED;OJ74!PM$&&A{)9+Z z3|zK&!f2jQt9!M0LG^3rG4IzTzT#xwe$zYapp2J6%D$27gpJ*bg6B3>_uefq^RD}Cb9j|Q~o&m*O=2g_UlJ$YZ~i3VnmvK z-l5rk*);J;;++Tc5Bia_i8z0T44vt6i(EcDuP$?-vqN#v$DbxiN}v8Z`b^!u5+L>r zg%D6CbweaAKaH0{i4h9d6t^mCEfGpdbd{~^GCk9%f;DxuAiDhuwP$+zTpuZTEaRc7jOiu6bXlJr1+ z%A(NhO)NdptzR5eq1dFo8IU`KPiF9)1W9MVuWm*B)SsL)8RgnyXFBmo*)-?NwXl`u z#Bz}4e1i2NG>^}Ls-MPxAemX8|ax!kJX1J(>?(~I54msS1 z{r-~6MS59|Ln{Y(|AW2Unb1(2<(GS|?^|vmxEH8giNf}=wW}K@E15Ymd2AHCgJ$FKqe2Ul&v+7F8 zq$_GVnK!o!wG(FiwnF|gvh!zH)lPP)&cI0YA_SPnzTahqH115sNaZxil`}$OcXXbW zEx$jvt{rT2IyJi7OO42H3KDNX(#!4W50Ws2L&?dhbwp}qc>xbE^DneG^*WC_z5)l? z>{xECG^H;(g(%5~Ja_GnI44p@Rlh>JwS7c94OCs{SL&oT^n)$Ry#CFB0MGl4L6!Of zw$W_94tG)8TM||u8hkuS`w_=7slXdlJ5C!|wvv7%IGlC#h^9Ls5dr7zJ7_cAz;)0^ zt)PdJ7py&Ji<*UfcAsOXW;gEXGfYwUa9&(-7@4B|nAK8s&ISl5lIX!O3f=o4A;6F> zpEL;S55%Th;H-=Xow?#5;U3cHw=iygNvGI*od%E{o1W)vCvG0%^0;wb$*Ib_xAh?X z2lnTFPJPR{-0HUsqE^D5^nTa1teM3&UBa&t+)kMKV|-eQstmsb;kr0${)$?Sfw_T{DkP27Re8Q<7Lw*& zrFNu@FK4R!oHp5gJh}q36D&s&!>hW28lE{lOttGg>1_ds%LZ;=HPqLp0f;hQmyki+ zI{@Ou_icbXEJR$&z2nD$Tw1yoxASw)nD*Acr-15V!gASV7M4S)h~h>=1Bhg+pwsx7 zzl!-V0Nc4Zw;H?Z7iKfnWdvLvCY(o|eH%^Mwz(uPl5O*yZP?rosLzX1KzNk6U1!-y z_`#Osz(3F$5?+6O+N-k}$AkP`m3UO-_~BIsxO@yrs?p{?Lnjf;I@=3xOH_kTZXQd{ zf0d27M>_V`!kE)_L}fy}6;Qgi1Pje(7 zTRM1*uxHd2S#BuX=AA;V<5?XtKsNnt`sYZdpNELQd2Akknt;{ibp~>}qUIypZ6o#K zvbdA}9RIM)!i^)1@moHw(-kJ$l;h4=J+K|wv!1>S5Tl}aJ7S94`R`B++>0h!+jn-Bcecd; zpg>wO{Mh!k7Bxm!pIgJ&LNC2X%)pN`_~vQk#b+kHOF|lFWvNmV>J-g{`uuN-alcgc z5N}?5^J81^QqmLP+dma?Vy!l8q$@%>fJB)?lI*@MDebGk>#$dW3lk6pb!Q!su4&?~ zZdnr&pSF2BS zP@0NrSj@}O`#HR`PU{UNtOf|XB$c<0m8Ia(+YV=m+r2#P9He@GTK!UbzYkLM;iACt zx8#Mj1`e5NvxeRot!O>ohDH39+R2Y^$Oq#n2SUou8~+;U{blkq)j*_E$bdN6PpfG} z)orQ{5M^Ckb1=ZLd4Jff%jb~TlmNYWijmo7j{xR^wcEpXE56VU0+!ZMC(Kf zPbs0F{X=qDAKp2ll&(m{*;5Gj)770@t7M5XJct0%R0_u0T&xk?d}1LnC1gz0k?oXy zo!?~N%!2T$)U8(ylZX4{&+%oJ?tD2V?D}2Gi#K?0b1HWO`272wf8L__9tXMep&uHZ z6iy5x^g`p)>k3qD5A-2P77fJ{&GsU1>4rf6ma8zrbx-v?lmr>BSK~D)f zVXZAuMCy`$sH=-|mp*_TaZ}qeblrY6t%70NhW~)ArH47S^vC1mYLKQfsS%oHTg4dm z+^i)05Akk94z5HMDmNH)$4=?BD%4R8L6%ko67TyP0IN2dSUq8!9rPIu-rM4+RCxV3 z)~MmQUQoFm^?osOGUk!WJ>E;c0S8mBf3)$uhVLwBEqxl&ABWxZ5|kC`5;Bmg=MgQR zcFZ&ZC9?5pd@R=M62zxb$Ag?N+A4;v2nW@i3|2d#&p;8S>vtwNVs(Fdj;Zp!^dPY* z*tI9z3+T^{v{34>iaO-FsQtABM8@fJpv5(?Y$1U#U2W>T*zr|t8Q`-<AMd^CP1RmD<9lk1G*Y?_5bG2MH!OV=5)xk|anEqxjNzg6a zWjNz@-Oa^U0n6T%H_0r8CX69Dhe#c{ViET!R){8*0lfcNMSlU$Pw1}|QoiiXYUu7% z``su%zb9L

zP4<(KTmOX{|4hlw0D$gSDfWh3LcNW&2!w@V!qq~~6A|0$Tz=Z~W)p{S{yh7$?Hqyb z(k|@0PRb;nsB=2t3K|u@x;oqw~svwfIDR4=!W_0Z9}=fEJ*dNKsLAcN_H!8 zIm0Gx;FJm4_-Y12=lC%3`@YKkiEOhm zk7;J!5>=6`fVNM+sfT&+w~)9AUBbC>$9B#?mp0*oH+9FF?{`C4tAs* zKmJ&=F$*qrRC1}<6gdGw`+zKMsFjuoD{TH0R9cyo_u%2w-a4x(s>$o3rpHDK_ z?DE0d9KrW3#juWdwDx>Sd~!J4&8RiuvK-Y*{~NoRiwa2*hwUUa7q>@xmRmlG@>h({SZ3e)`)2#K~!B#{{}e0)0N-) zypBuu(nx#TJ3qSVu7knxh%MC`M*`Hg$SlynH1%f8*oO*?Ju5NFXLs`(D`nr3xCIUd zKXsROSL?$d%RjNT;An?R_k8N$$E&Klm=wl6Oo@8fx=7 z8#aTs=9N9Kmra&1#OEw-8&ubF139V;=B{4e?rtJ6NV4ATI<=z=ydVwpZ~@HJxOCH! z#@D?w^0z8CbxFiug8}ig^d-79Y%$c?aKD^SCiXe`C9o*Zyw0uOjtv{nu_-)q6p6G% z8QQ#M>TPo~wl5;sw28dLkeU#Kp)RM({lKAy?2?f>513&PKkZT%)7KsxM8ol6Dtt__EuNx5XmWBMnY z{OL2hzT_U<8FUcle(U=RW-RKItKVx2km9*p2_`1I4em-zU%;*H4;wxalI<5vXK0Pj zMal2TBv}q~X1P!sb)~KimrI%b-7|bmtY4qcvb=5=(oL{|CJcFC04?R`eOI}oC*f~p z>f5e*dBA&kYuzC;qx<53^4XixCTv_fz|=qNQ)Z(D165 z`sGpwM$5^L)Y`d43-n720PCO&Pf}o|es=pG3`F(&1Qor!3tVAsOOp@WMnE~#xER8V zg!k98yU%r$XmP@2MBidRB4`@~3`OlaWUr_3a~&N#Rd>&4trj4GU|!r&37(ysfS-6u zo4Df!CkH|;%!jc00evH$d9T03a(r-%R$`S@uFTXogcBQbhF;)`EXOj((Z(y}4y+G0s{5C2JPG;|b zySm?UR@#R-@pkDD{?1;x(M*y}=a4q$B^z8hEO zz)^svSSN$2?@Th~Y+~HYWnstCKGt%9rKPl?E}2sr z5GP3+*>weVGsqI=%GSfSkzr3~0^bxTVT~R=j&Glv5Z-%WBlQ2P670P-f7i*8Yx8c=UFRyFyfdgXE3&AH^lVwANZ&C=Ynx!=C?u4Y9njCf*^-`!Q-ED_=ST7C#WNHQ0qEEneZ zDX7r2G7c#PoC)yfo%P?z+ItyLJo9nK9=hJ9l*AYt0?Nh7@vzv#1P(y(Mx{J_6Z7;{ zw$KXP)ONVRK+pTYx%!JO{v9wtl2oL7L!|vDTB{jYRD%0QJQhU1?= zdw_5WNY;`kFr>j;y_|}qodf#(6TPx^8km$gq*&DR z2(iukw9ODhR&mCeaFXCxN21z?+-{wU8t&c-=as&bl0`)D|5qj0`-qQrZovQ8qVrKH z+|M|ZOA+n7ePEdk$QySTJm7o-fTW0>u@m*AA`a=|OyFZ+1ta$R)rEmfMh9P6mY#k^#mu~hfQA`R&io{p%&|xsE`EeBNx6mbXR0@% zFcdcyae_$sH=z)VVrR(yI@wsKPAqhWY>VwB)!^h8ak{!4Yf+)}TV{lG)}y|(44RFh zY=i=HV~m-Z;O=JrZdRcvj^1_?6qQ#%-gDgla%$gNP9Dya*M5)-M+n@GV!q@tno}K; z(ciOFzI(`VQx$0mGB~e}!}89*VFJx=e0AEAcw%WKsEf3f2@v$(zaq~nRQv7qQ12yi z$}m+OoiZbM7-LaxY~o%O7^D;cvoctPE)dhGcQZ4%Fc|-V;%%9j8qPghf`FI6FMW8i zem`v%i|*_EFNv0dLQ5aaFr2td)J5EM>hx82FO4TB#)HE2QVobBoLdx6(0UTt&N`4J zu3dEvFcPk+)%2a|(-8g4j^AKxW9ENrx8D^uv!9pB|bEvn$%CQTj{ z_nbgAyPq4;&Ue z9?GUlBFUN(bKBX`H`}5xt~U>@E1I_->xP!4J_RUVizlYIKAV`TbItmZhc_QT!mFnd zeK=_PTfN4d`B(4C61*09^rv{Sy!ed&C-#8R!0rp`SA%0Ax?z;nOoj~*SZC)wU)FH| z3L~_>c6(DSgP(jN#%V7sTI6J1i5)7RzNnpGA_(?@$Ns=I_&9VV=^W*|0!c z@^zI-Vn#c+wZsb~cOb-WKiPj(F#{sp^<6EhT(k>Li^XiG>K7qOKZ!SzZsg%!!os=Z4Hp&$-XlEyJwo^h<|t5jY+Z158k18$$gF1?`OaonQNuQUqANd zmT>zy1(k83qHu!e|9`C6zrH&?Iz$>5p9ZG2VCCZrRZm~eEuca}o2Hbd9+PEz;gV+R zXi3l3h7`E*KXO_xgRc|dGrg#@fZYLfv=<9Q#9(xDVL#S-N)b*BrPy~uW;-H{wc!fJ zibsq!xVhjt+xYSi)RFvwmBf@n{JD=udtz|x{#XKQB^?t!NPFpA2QX*g!Iy6+k?)LF zi$j@HHwJxy#c?~U*@fR}pm69#c_&4*RJic0tt3$P!R#?se@#`@OcWn^WPYTY*_w;P zQ3#P$A!5Q)29gx!nsF5PWxN{Zwr_8z=n0Bb$%8{?NoE@vv~o!gwk7oc;b2tV^zz{j zT?w3BHP{g)vOohU->M*t^k%`Gs@~90=K@-qJ$D;k#jZB9l@<1~3MY8AE(QRt2!2!~2Orlme=j~;G zvALM83rg~WZ8Nu~#fuVpge|sec~K-$Hwef)Wgo7YqRnRY7Z$4KF5bSL6gm&t5IQ>^Whw~{*JLnu_aXJV zako`Nk@9vN)DL)%%&tyARMiFfk&yij^!(CNNdY(qt|JLoG{D0m{UXl@bf`O4@v%jJ z6^%8g4{D4KO*YiHyM4f4(Z4yQm>a?e78wg(S^_vd5z^79Fi&UB?B5lT@yYz%rZ>K} zCRQ$-a*J4ek$bULxZXPKa+RYxA&<{2vunb5rxC9?;_^b*@*@uMVxt6WOqAJ89j2IP zRI(|kqelEIVxB)hzHtJ1lwqQ^PZ$8Y)Kq^J{{V_8;luK0paE5wCr0lQM=z}hMPF@E z*8L39GvenEULxW)-3TH0>syO!6}9bj`1X1fe~LZGAFh3v*X=osnKPJEoUOtk^3hj8 z68fv<=7li^2b=7>PaO`p(-YU$;*+_`n*ir)aQq}tNn7u@+C4Cl$2lrvryfNsov~iu zhnzB_y_nSUSz@j*GGGEAU3;Ia&dmUN!96omWrhAxt-wFJfd_FqzDxz2CVZXEBY@Eg zcCMrQf&>iq;`B?o#(vMPhp0&2Y(nJKR;^FbF9=-ex;=;Ci%~}E{4KFyK*&n&g&0AU`Ejn260h$Y8 zZ%MN^vy<-6edyAS{j(pj-QWkZN)Oy3&s)(KmXT!ND(VBdtgDbpgST4?=!)7PYr`!( zkzfUJ_jN&;Nn_~Db27=AVN&I)$^KbL2At9gstUq4*E_Rw_R@m9zi>eP)?YR{%dlPL zs&B}I9nUTe=EDB>6;!kcd}SDVfh;|jp&nGLFby8V0q_Wz)H&a|4exW0cee95kb~hD zjHFUYjw4;SuE;E`6LH8%ew&ofR{q;Ap~d)j&Da7ghF_zCSrhUyvzO6}X!s+Y?LxYb&?1 zoD>8!qBR3XTfGuszpo#Emuk@cx;uK`RC&7g2E%IrJ` z_M+qk;O)N3>j_<@gn{5tr(*3IM_v4(RY)VM1sGaV&s^sK7=)yaRCS#aw4$lek-M9m zgDFo|Rd_{E^7wrJ>l!P|u)x$bEP(U`~=IE=m}eh2~c z9G(L{7!1FzjmTHKIj@rCpzhu`d5fh^Q$cIIIe@kSM}dvB!FAO)ZxvP#-I2b6wW594 zz-q03I&kt%=CJ<^0R}$65b@unNXPQl{qM|;L*abA>RF2=bkDWRz!BI~f4Od~!2G}C zY!4lR(X$!Qg9sicRErC^?(aD~KLgwEH)kDhS-Oa(E%i6&l>wiUroN7LWJm!|?Lik_ zNC+6ujB@u9qrCGB!!U3AnUIYQ^)P@JX}>#hS}^^_QIzZ|PkjSmWEOlb%9i52;4wjX z7@&tq{)pwfyI*(#x+b+aX+2^93M|y(8)o}_-vlg5UXViJymfgyTGluJnLkpn&b~@r zUm{fKc>gFAD0&USB;fm3a`d}f{7@~K1<|#fUT3_57aW`%)DH<9CD|Qte%Pn(#X2m0 z2Rbjsj-(@6q)T3v? zohEts`*e$(esi(1qAl))OtlOU0q=vH-^Dpz+sulR#w+8wKN_fDVAW3v#H)nodR123 zdJ|o{NPx1}aH~W*P{7XwcDODDf&ai)mSGop6YS!&X+)5{`XSqAm7%VHv59Z5t2`TQ z;#GBaSs^x6>ug`>p{AApys1=Ge>VO((@NrJ$u94+VS7E6jCUsr&pT_wxB81(TRv(2 zZ&5i;S5ZGC&Y%`dw>O`#{wQvZH2UEE*URgfR1hzl&`=_nuh*_7nK=sQPYR%OrIT)V zsfw381Kj#egIM5hVdHlNRqooZ4zUL(X%R#kco@x(879`iwmjYYr0v}v^FHR+(08$R zxS(Zhav@DWLG#pN z{qD3Iy7VRU)0G?#bF|6XYH?!RSZ(G8NQ5Y)foT{YsXVHkU7+ryB06p93&#%h?Tb(} z`oI`1m6cynTlbEMmcXo&w)=phK(-g04KfIaNA!0$K&?7dEZUg+`ZyQUjcCLi77N8QK+jvrAMiGVQy9vBFLWs3)iy2ke&e%SH}ium7h>P3R6l3=lT^ZQfblz)FhEQ}nXe8f!1{sms$~hsvm0)YNr>Zlb#Rcljd}#+J%nt&dZ% zQWa$-S!I9-iX+{86M0BJ?(b~Ak0YpwD?jh&!U<4Kwb#C?7!rtajvuM447ox`ZGP zo?B=~?jBCWVk^9XBCH?SW~)^D%S}yrLqOO4_vRr{34H}Z{R4chR|!ZQ8KtD}P`Cg{ ze|nE1cfC3CTX|UVbYpHha)f9NhJ>@WI2teHPdS(o`B6wz$?g2V)xg+~rD>x&6B=3A zM3Bos>0k*?qY=B9ob5yTHQr;d%Rl)KN2Ct~@<;FKIW{_PZ$R~afU9Y_#H2{k`8IH^+?uQSerE(z-|c!9HBKSllTRYeV=giIPO+dsy` zN1(W2>(J#^V}YrX`A%H4trb0Bx06L`UUqbfD-8T18_CSJa2AA!iq5ujZUfaZQMIjU1>iOVTtP=rLf*$f0Id zLva_xKjHXdM|nrRnD5(|^TS^UTYv@mT(Zf)yZG@MYxSI=cea=g$*rzCJau#vw8dc^ zHyAgc^w27VOKr=Qw?L4DVtrvdvUTqIMZoe+ROU0t_P%h>1aeioX4RKMX+9uck{}Rc znJkdVy^Uo^|N1Y_%y_PpiwYuC-~iDk@Gil7vL`xq62M12>(yx?OFAe9c<_`bT3_6d zy;=xyAD9_X(%zO~g7MegMGj&eZw>R(@Y1!W{XTYHBmuy5>bo=}cNeS1-r$p^w}7Pd zmcH%&CSN#Ab($?k%0?UUcj@K7w+WQNg&=@ANynG9Za+^4zdHl@1quwjeNt_n)(;<# zF<(FIz6bOhbSITa&{ms45Jpxc5OZXp$PfiQ4n-QJi)^>lYFeI*H%W)_&Rq|&_Od$g zAq`w1(jn}O6w!aoRU_(27q~`{DnGkC6Km$9iYbhugk-D`d`WbRCbGd?8sXJS+Ni03 z(Y7oR((TVhZ{PzEDF?}Hysr*e&A{j}l3oU^CrdUrSoL@3p1qqa>P1zL1GC-Fmw|*) z;6L*=SvhP|Tk$}g;$~eHYrCgPJ`urR!_G=jWDo;bmK(o_sJeem*ST(_rG1oxLC3l0 z&2B4019_&l+cMc=s%esMa{-l?YMvfAKmowqv|(=S4Md^?(FCR0tYx&Y-hvjDpu(b9 z2giXoHv$X|Q&0i^Bc43yvMdRn5&}@QF#kG;L$QH^*gP6Q#j~L#Y=9cm!Kn%fDf!$m zx{YE|pilTy6u1j-D?oxTPpSf~scB|qN=8m6Ey9!8t{muc|6x7O??CK&wGWv!>Np6P z!E!Y~{#!2{!@hhZAB>|XSR&}+wrP^Ll6|RC)u%p4 z`LQb2N)ql%{{F>Yxu~Z5#HK^6pB(RxM?P)}idWVh&gz)EciTt))JMF z@sKNJ#mKIi8^C_BLRc!6U*9Q^U`3>PNE^mFGC}Zi5>8q9OB(0yW{9a02{t8w+Vp;B zmc)fQt$t^yN`tS3hrFRn)|m{bnIOGebZJij&L~e6wLU{E+w@1DmlTSRjtEDo&(=aS z)!`@(N2L@@P-a932b{r2-_^f)@MsV_X+?p$sQ=#Pi^ao7>#iB#!AOJDM856olS><- zM4}xQ&$U|ct^n(DVAF9Llj{o>;3&)Vc)V6!IFJm5p|{f4w--WIMD6$up@RXubrPaz+)Y&%W+j#gyBHGpA2 zM3PD%Gk1dKSkpI`w~U>2(#o3}k{^8AKBTZzEiMWHXDHBsB5h+SX&a$QgYrAo8h=q1 zQN9xz=fi`#&07Z3=P=M%35c2NP5RTZ{7hb8_cg(e65;W;`14TnT^>zTK@EjFgLP9m z+FVywnn0cGxHY85a()Wax=poo+@Hi}>!hF?m}L!9cZYArnh^`4wTtB{ZY#{YZ_5#4 z|KWD--d!}#&f_eG|K2Gf@z8JtfD3yfGAZU6T{{s}zQAU{n6G{O#%XUu=T11;NtBBQe- z|2~^wvwTc9O6KCa1{%pwSPp~QoTH3*H;<}VwK`0*`&NVdV(;OedE1jBrXTk;S2$lm z+*0q=&JU!2rtqI?Ilh|wu?f5wevGYVH9*MZuD#lX-iLCNJ<}zI(rE)oS9xd=G;K2Y z(-=x4cK5Fer!1Q*gy3$cnKgu{Q(tMTV)_IBmujOV+f!ipjS4jJHp@vf=UWI%v?X8X zU947NT5}={m{*Y@IqS0M(zt)~ zR`J8+aO?N(mDI8HyL5&vyBUWi2D`6BF9Vn4o{QJ!%vqCy!yuve&Ux9NB_7<$bMXdk z%N7wnLZHBCTM~VH^`2!I=d{$*N9$Pv|L++=t_bEE%X^v;=A5O@`nOKr^_*flUMs8A zdr83WZ06xZqD!X;1v@Bvjbtr6FXldZ-1HqYF3cZ#=jLGffd@S+4}maOUDf>?s*~{q zU!Ipp%c6S%_}v>x>)xNKkjKqR$QYU{(vB9qKy-Fe++HV%Xs6ftAv&x_iNu3^S22u6 ziT#oKqZm^ElMJ&>cZ*)SWd4`20lIi34G|vfaor6bbnGLoS~^5DQn6S-TyGwPYxSwc zjbFs-{|)%c7GI%<0Uip{3Bn@iI#}x9Oz}1tQ`SN30Xp09Q|x)5U{Qwf{@cc~jf z>xvMhLii0`{V;$xrn9M zqUZOtS^dLdg+UZ4zv21XHNpB-r?1?@1}d1rTm_KRqA!+O?6#8F=cZNnS%!We6K*3%I#7u}Yeo3WO)lN(*`xM*n6vgKHEmkl*&)w8%LKe}E{699R0ikYpL`|HsrG|A-QC?t zOE&@{4N}tG-JwWHcXta&!@u^q_uTK_Lmk%G@xE)#`P5vytMZP$IrwAw1_-7)9fbay z6acs3H`dbfEX;?98xS9_P$h4zNi~sNsQ#lwGI^dzk!jRpbh^B%oF?UD;n3j5H2l|; z=<&&3BwCz3Ot=;B*4I4y&6+cxK*;+ui%%@3GsWB8f?_$5R4ve^q9f&IQT7&U__;lO zK6Adsv1JN@L<&aZL^`kI@|xSDR6OoR#)Kol#%`Wk0Ny&7gln22=Y*tmz$nqgAn-}&n43PQKUA2@yJA$3@?D43+*p8ob(ugD-Q;jZsh$yXdIHFYqNet6ksv+ zR$(~r8%sX#zhq{-`Xyfg(a|7tL${aS@8N-FbF(GHsNX!C-8_@=f&`2z#W*NpJMaBs zZsVj2*HOB(S^V8RMP>^`m9^wsUn9GL-M{XD5t#dWlXPZpvxZ0fd%K!b`J*5>(1d!jIDL z?55n1bn}xrjV72h!01Tu9%04IcX-$LlG+5%YfFd3!zJAX8?eF6T9G{Z=qP#BJ)}R$vA~C`q@jX!?%=xtvKrCgrqzVL_^f z+r3{=GMVt&*9|w>fSB^G_7qGZLBe*b+M15{12;n7b9PRTfA)lVyKuSp&4Lt|p;AER z-jyYA4JQ_-Una{&Z{GhOr~-AmRw9Ilnb@JIw{Q%1YSY!ee2?E1Y%4GxWl1T!S+NrP ztTjw60Wh&2m)*mCD*_Ad)$19(lvJfTrYJC#`+YNs`U7L9q)0{oX4_ODyA1@dMUnW| z>&(x^Dxz&U7vt=hM~oF-?R=13O&y{H2fWkHrBvI&Hyr@{rhD*N=VFDjLEdbU>1$q5 zLy`*TGbEq-!ir0GkyV5cy(^p zr=eZoo;+mqIqdZS!==rY#@jK!8ce`ICNt@vGA^Y+mi(zc*-5 zw}x*dbP|}hj;v)yyFg2c=4$9B+VU^w$rw9+f*B`Ps6IZ&*JMEzr&y>30_}nJ4Ii5x zOF5@kYb5C_BPnVLuFYbj4qfYG5C^P&OK4nZgGS?Nbl;z#880pDP6wV0jQd~k|*yv zi1`|*zC@wI0bsTzCCJz<2Uz-(Gg34kL9em5Y=Jpw?A%>8C}s!YD_| zM7zxc;wSfvmgZ)5Nu-q6?B!MH_Yt8qBFt%Xg9Jcq%Z)Q|n`7oQwuveb8F*;RuP#SQ z?2s~E`CNbi{OfM70r^!>@idv|(p4ny!1PlH@WZ-J4dBjtzOx}h(FE7#xA839YLRaw zXE7I@iXnx1_Ks+i-Q5)WwFmw)*}72)kOatQgbS=Jjw1I4u?vRNEG=VB8uwLpFFNNS zGuh3Y8ZlY3pAFqbfoV`oJ(Ck5#aQD1AN5Bkfk}q$7aOO?9QAHSyGe+EanDK&v@7R{ z5OcfzSp`85X5vm@z#MD;x_J{^Wp!#wT4O_gd|n+cmxiA;{KAlMNoXjBt^ObDJy=&< zqZPpIO}tz-Fb@jiI_n=~4G>;dnM>eSt9;`#RyQC&Tr z0drCg7T4>zuHvFcuCnCtkTAUZ82skn4!7!}7mq7~v3-0EMy~(zDJjLv-EBm%Hn&$0 zCN?d9hX?CL0YaQ9L(HmA`v#TxzuJSr$Z@XnR_;eI+JA3?VzagjKok7qwNXV-!$+$_ zRipVV+wX*6m{`++2<%eOl|j~C1;s8jz#m9obZis-Ke0`EGeIF*1@uOYR0k;Z@9=(d zxtsWa*_qHx?nTEi$YS}0_()LY*bXD8Ct{DY*cAd|B!tsxlgG(FG5((RYPPY!Y@=X5 z$-^t+#2lwQ_liR@8tw#|_~A(+p;UPfVx*l9tq;kD98Q;%6r97@E| ze#^J$asjY$2G4C27@U{GU-SwwNVsx%hfcONpvj6DaB>wT#y7M2sTrd@lk6_&wk;ps z5j>+raE1E|RZh3H$7Ne0o{Fo9<(w2=p$nuZ*X=}a5tdfLY<~j~-PCBvcLD2c^aEKh znC3~b-qL6UR)vfL@$#IaG*ywU>7wh};kP~z3*dGW3pZj(ls*63_a?)e`$Z6RUE{uz zK@6%}AN1p#Kx^co_W9t)hW$e0Ew#qApk>?iPnA^gU3Vb*Xy41hwDbLg4+}psNZ%0p z?op9(=BY!2VIz|gNP3NIC70_6&fZUhh*WKSLn-JwKK{YuC0 zS$fOmCJJQ;3dMIJ6T2q?FxGN5Owb@-4uUn#2cd$BIxrINZKJ9hhcX_m&4K%(J(4r#`;$;Ai(g%2tIXE17a{@iTXB8>$p*pg08!C5bysNz`7f5 z+EnW@t}kJXNjrFN8^PHH45;Z6pbHzVqdTAy?=xxGsJ!<2F6fs+RD7r&PJ-xE-Sw&P zesgi&ca7G0q9ezpQF-kUu1DNqtHXK(W7!V>!O(-FhRc2^LHd=CAm>ZaDxFHL;DKwo zb|j17>G~P(;#MfU8ghU}d$BFFK2T;{4kTQ_%%-uIln-Ss7`rP661_hW=Dg^b1!4D& zrLXGhLIe=Tlvlbq*!Hy{Plz%@m8Jszc9-M3bLs5hGA5vbJs-%P_&<<-Tue1ORe5Ye z@wM9D>&Z2!bOd`ZJ1U6|m2VkMCHE#o!Pkk4bW?*mV#QGIUx0M!3dSmRKiZ-HOpfh3 zjl1lBc%>NRNpfuB5X$QvwRkiO1~n!9*)pnHOCcvAD8wK7Y&_b6BRIB~Fbu#D;@J^l>qj2+&vI9e5$_9b5# z`|2X;|MAPZ$N6@(&+E~mow=ADHBiA0H#aI50atZC`u{1EaWrU_sj-}O_Z9xTQsyyx zCRBj|AUYJg3#Q>uK)M5UCdf%%jl>)?t>p)r8bv_YU#L$WnM$65n? z4cOhED|9IN$74o^A=VVoG~0M1{t@K1=r?60tsq-(vxTp53}{C-j9~n zhriu)w84$-|2mkP%E{8;UR1SXDNtBpZvco3$=y2nU%~!e9+{62x zSk<|;WP}568%tnR)U&&RGS>ZNl5O*v8V*cA5`at$m}zCR@HNIDiN5YqQV_+zyInB6 zPIOACJ3#(<0E+QcfszK2tv4TRR>MP}+{!|HM23u?=*J;YFKhc6U|7x?ST{dZf`Fk* zXW<4oOX5G%D*xaD{!CyBL(Y0}&PVDt^UBa%_$;Hc+uoa`d zc6{u&)wu(ah?Y~Hi8gZQ0}1AAgzVOGxyDRVOW_@VE8Q&#TxkDpk`y5|fl z-45D1ch6Z2XLwfkEl%5K?$={{V;q}&a~Mw<>@yNeJ%fIj5S1t`+b8QPud!coohv&b zF=l-BTQIrOW*^0me?3E%n=ZqvG-Hh7Mo?%gDor#>RLIw4Z>t{NXAKWELu%9e%=kLr z(l%Es>{TMF-ru$0fRmylF=bySYEuTJpxF|&CL?tY5={-V=JzbtNr=Pd+q5K|Cyqq1 z9%3uIF3ihs&Td|Il`NxhY0gp4m8c(xOZF26KeRbin`CEfvQ>$SdOo zffJ2>vNmOkn~xqQ21X`zXh8PXg~_p}xh#r(YBr6TK&C_pUPXF9JOS>~l|7vgMp}i{ zjLq3X%}d?)ETRW(oR##b3$Q7lP683EJP%5odM@~Gq{Wqjf^2w+J&jFpPIUQHElI$W z_^)sw$Y#;?h4rtuvYfl-4-%Z6B`7z!d%3H^xhLpK;}VnTzenuUWP26oqaM*I`4QhU zK|CzZK0WluM`L207i$jbae39eb)Ul1Wfsq`nPN8^U~Yf!s1^s@GZ99l24Oip4#Q1Y zMOB=d)ysq&nwxJvMM=QJbz_Ow@(;G2|NTU*%Oibq`sfHQ%;3DqmoT~}K7lqZt}~JN zV|%6*?(yhDb9yu-#h88nqh9XUlnHjFdwnsLBs~nA*izioN~NlvZdxx6T3*koO;ZVw z!9=g3m3dyFqpt94&=x(Lvcl0A&Sus+b+2A;DEXSg5N6m;>|wV#O;S>(Z0WsS(wK}1 z6D*Pxx?&F}|k+%LS`RvqGt!Vl1%@hlD3dW(l|K~gQo5Lg%oHzpkUd|)Jet!p3OxVH{ zoH&24VW)^`v24>Q5cr;_G-Y~%iNmuvlb*yWX4d^|9nUX5a2@*46Z zBGJNmmPd){v3c+0V(S&bw?S2I3~<2AI}L@iexpMqT>9_F$H0j9A#j4t??1qaTh*Gz zQJ?*tv_RLysY)sJcqliFH+(mzOWmnVg8}nZArCjJcReBt-LYLgMp&8}S(epAvjnDh z^6il9dq29p#cw$Nzrq#56!Lo3Oj$#}r?I>p30yBW-=a$W47Q4UAjZBEYzJdRc=*e3 zvbE>!T?f+s+zC4Tv=SecZvR%7bERmhTElq;@x2D`{1GDL<_L*4mtkzVc=T^xHOU?` zERHl%ql8I;kaf-zqe-vpn+&b!P#mv1UF^NKiTE}>iNUo7XHW2r-{H=Wrt@i0Pdkq- z#y$?q=_WHj56ZC9A_m1_D&E!?xK~wB8Nsjr7`BIS$ zed$7zH3X=bLY2oAgGI+4!=RTGy^yI1u;$v>A|1XBGSrY$uo$1At+K%B*NZAWvJ!yMfD`e#V zJP@;7-zF=~^83Mm*}w8aEgi?my0Nr|5A8khYBLu9}q=_dlzn zVZek*uk(~8a#OIq;v4wZz18L^NBSjTKWKx6iizY_`g_r@vu{I2ESAjNoFtQQSDhS% zTm2M*^OSCa0^p@GNg5VznA8jLGz2;g?ml%yt=w{X%au%hgcdJ&ss8Ine~$OA zEE*J(Rl~;MGatE|!krgrrE9&5-{}RoJ!-sH8A5uAAE38L!r(gnI#qw_!j=>GVN{?vjq2!sjPxF~znf(F~`l#Aj${uqe_6*W25l zT~Y>$3kq}*7@o5A>YT-szZ-C4xUiIU;JYIb7X7)2K+S?Z|2}k#RSSyZ%JYP(ZHEap zbXSBzZ}oS9wz@pVDYI97zX^=VW=gL)q)I6N`1qBfjPNVua075bGO@}KzqWEMdv0!& zSa6Z2g# z?+RaFZ;bDU-F$~a^8NMf2Y!{Ruw^)`O8GGOtrBp!B<0 zNZnUiYI>yBi`z#}cboDp>%h{}BMsbrt^M1#iPBE}Fw#$E}I}+9%d<#>MpYs`%<7+d;X3WlrAfq#f4Nw{1ueZ)%r-zBt=OKhUO$|E{WE#K| zOplOcB#t4K`_VV9$~p@J`a=l5XjkXJ%I5OTKH)9dG^ocu4}z0tOZA(*JaP<7KZ4`z z4=YvN*Al1qAv<;AFgzN%T!rO5KP;Nwdqh!{ksQYDRZ!hXT7B5`o9qL>B-&(?+6>C_ zisB*OE;VTPr(<-EW=4e>Ul6mh@Qsk$jS5M#9iCl?iz+#-65I@<4ZPv)#y?1)MWjk| zyUAw#)F3+=P1)3b`lEm=OYW4 zNCL)~{4c($m-he^8=SDp*mcF~f=>5{S!ay{N^}VSGbdd7NlL`UU|~oLWp4OoE84Kg z?@OxB5*B@i)*$Q#<*UH7!eISXQ`z+V=Aq|BFW6?uilbjtF?@+TNt>RwgXX+-^_!0O zqVe0@E=>2>F#ebrLbaaPi_+RP$Ygum9=*n1~)?QJ&Mo^7`F zfX=!j|HJuSGEJ5m9A_03DwTd3B>FDpdI)vOjVFIZ`oEa9kO{1^*<{7O1)ah-KQJHI zRjiX_&bjkZsE&(lqaNh_TCpoyS@zlR<4K+lZOEmyqUN}lFExYmW%gdhOB~^fI*N9^ zI7c4^%ejYI?&-ivi}~P7xx?kngQuU4DW?@YTe)^fNL~U?oQIc>XJwJNv3U39#eMa6 zr6cWY<8G)cL&LwE%7)^LI!A3zKWEh3=a)aEPliPf=?4eCZYEpXjgePr6S%&$%UPTx z8$LO(@3;A8Cis7l8=K!5OI~DCeAXp6@x!P4T(#2A1T+?QGWrRc0;r;05#)){Zqntx z3J6KBBm$+w(syydxq zW-JhRUm7HXOJx*6wzj%f%w+wtMp)>dnkwG!Yq56X5*DI1WDRh5oSpz7Ri|En%S-gE zt!wCEeL4})-7cF&e;ALiB}avQyYxV+IvJdFbQ1QG;$8kl{5Aa1W32xe2~IY3?BH_a zyIL4}K-s*?&eg5c6%yPy1q+|wNtM{^HVZ~bU!~SN<23P2cG9Z$ygP6z@--xbplz*l zo^9cnI7vB6<@6r+{>DS=+D7OU zTJk{S*sSo7h34=FZ=6X_@J0Xi=wKvwvk0*|w3TBdK_`y|?axzQ=u!&h8f{TQ zz+@+Y7_A=$hbP#Mrsv*x+3bQD1KCbD4}S?#SlN{C9>_;YvqOD5)1m-HLH{h_eQ(|3 zba5D#KPI~>Ul{LkbeEAm3%zw4E9HU#T;^>amY3JVumQ6n!E6Y4%9XJNbd z8=kZfk|MPZeH&wij6Rv7Y8~641TE4P8!qzr<${OT#+%hP&u28(%~ZOVlM?31;W z>iJ85=D8yW{Tz$L59+He!O6sd<8EJKsE+rNn#@_}W=OE_Q4RQbeA2fuF)|s0)MHpB z>1~kDotz-NE%vV~G5XD;>YLjXseSF;1_8W=FCJ3mRM=j`B&rSbI5A0&y6FEx0_Dpg z8FZuyMu!-Ha3_Q=%3g8ba(t8y>^@Sy%s@w>d@s_aV%84SQOlUQwj# zKWXPpMQ@0|GLM<$?tTC8;v$S@9o*#cv$a&ulZEppQ{$W6V91N03m{Ax?afSsv0je# zGG)5oy9zaXXJJT^Ykxz6&i3x;`8vyS%YAdWZ-x}#uQ#y%InTSjeZgPVWMhXggB=Ms z6v6;_SM6Z_#t}<#(W&!Vvt7MreJh#e@)Py;zft3W*9qa7+Xd*>8UhK9Xvz-P+ZY>E&mbP8j{@L)K;GN3w`kY8X$G z`U?8$?8vVHH`dy9$NQ@4I$|3%j<69}9`N!Z6p7Wg?x>)dAY@ATU4*pGd|h+I_ki== zn?&5ABs>?i*n&Ia7%&}JYqlBOM8k{iTID1i1Oh-2^0`M3U`LQPG+bzEya0vtI8!o> zpJ0sYMnE=scouwg{YU7}pd!8FCaCTq%C+PL0EkuKEVXrbDF)?Rlh2NpD1f^bEa1O` zCJTA0lEoyum0Xp{@#C%##p7N)k6&NhZ98q%QR%hqnw~eE=`NHFU)vq@7K~vVFUJ+a zZF!vc#Q)Iba>fg?{|u}$n+WqNLDGs1tCigF#`J4Ty|7HcKDXz*b!StS<(1#~3$PdT^|Nx=$EL4VNC z;`hPtl}sAv(vb2P`O-bnR6lVs`O~Z0mv^gZ#HjH3^=B-7&KAx5LKODn{W)yBMJQ0($O^ValbBOfh6(dAzzt>+iHE9sX!8MN@q)v>} zefi&=Dkes$(IDhlKe!uL!heJkh;mR113j&Xj`G3*vyD^?n~*$vkS16bzDd7yAab6& zX|s$hvce7nCJ->ZKl9B^o4>m8yRX{8vtiKvNnCz8bbPg0lN9n#@gT37Ut7%Y+dChO zlH9n)i|zv7Lwfc**2_n8>7_;hUO_)TTa)Vt>Wb{77(l+ieN82NWY1dCjDZs@hTpRb zPCR-=;dk-4elv0%wrQw`wjwYdtr%BlJa%qhjKs7ludU0$jU{VgYVuS?S-idqb=IAO z%h$}}^DqXdRQs$K>0CTY%Ff=!u-TA#CFjh^* zGPnROA3OQb*WE2L@G4IbW+++K>Ibn(P_8dk zTS4}FbA&TbxL@Y%H5-5&YA@0azGk;M;o}Cu0^I)U(*6Ag^35X*1xWErtOmIvkXl`^pfOBHD2rbR*_7qA2UWJ|d@btud**Zr2-4itlvB}(vBPc)UTh(_W zSp%MMPJb@x1*a!pyl5fuQk3VpVWkJhhMat2&Nd%(z#ib|xU;Zg#$r9@&VP=2wbj(3 zZVPka(hf!RUa{6XUDdtKAN-*ubSbZWugi5>={-IKBZ5&5-cA(aZzpA8uOeB5)MK2? zn-Ms(9LAvkAl5yiR9C{btKJ_s>m{O|M&5c|4ySKJUf3kraZI_2Nd^t`d@^5s&#^u3 z&vq4_>2C_(^q#OD5rLX`LtdLQ%}t8gCf@KjS$COef;is6ABDxkRwBRvCc>5H@ZF6S zUVq;iG&w!D|B;m0vR&(f6IX6qyIz}Thglk-zzQ3|uC}bYKvtYEes=pfr#lnNP)Kh> zVn0>P!a{=z?jn_jgc!DuMT~+vpSz1zYoCnB;3?ce>udZh_q+6OwUi;5P+h;e5hDG2 z?dW4-cV9wTWSSVO{ zdM2V`Ib;h^U7HtS508~-b;Zy8DNlP86vDK@RdaM)(OmN?zpTxl#k@ zXQ$(UdmMEhb%$n;b_E~J1uVycJqG%y(|WM$B@f@+hm{EVf@AQZKJ}#8d%gXvqqNTF!D@;sSTwx1{+F_6dSFbgPEu`mg8zY4G-1F zLa*B$H2u%XKmw)s!X)uT4Mfi+rx`=YPi)RhV?eaacz;I{C+Sr+w|%gun9m(-Gm6k; zCP%mkqsnC0|<*p8w$mR*eY@882?*=omB<+cj5pUI`N1p_kH%v8Z@D%Jw_; z9Q#76YA>=`w-V|%YZ{WqiQEE@SL1b&)=cAvf zm)aY!{o6eAzuc;nMk5Kw|fcP9wKlc9fGrt-weVFIT7qwKYXEQ$8v?%?b zEjVz{CXoT#ilLGqPM{Fa;m8Jg?zl*eUhY?n3Y)uzTJn~)NMXS&Lh@jtWu`K&XjcKI zod|xk8&*8{>hZWsP5$>AC_~Y#K=6x34%0P@AZny9ZO6Iv)|eCuV5C-9VQmGTxH)vd%hMmvL( z5ob3>76yuoUqH2P0eB^NNKm#bQR_o}_ecQ1v?KLF9`O?O#{bfGZN3UZ3g zkritVHA@JB5=O?Y0!i80oNZ9-eIFggUKPWNwn;~c=c!a#y8hI7O7A@m8rc?4UPdXM zL`rUaHe{P93j)vLl|gbK^xZQvfB0meU-4Kpt{3aeA}=w}Eb#d2(TMzcD88Kz0(t>4 zO|qE?UsjIAC73fH+O#VFHWimIBzDV0WpllD_%VOJQK z*P7^Ec#m{tZxGx}(&qW_U~mg|KadU>(=*7}1`oXtsMN4-Q91vvg9SfMeGcFiP~gzj z(kFW6gR)f(RYPHB$9~1X&jz%iwNb9SOwdm9W2yYl3@FF-U^c!^*TA}4h1mpY0?qf* zw-)`+?J9v`0_C4I2bUquTkl!G z!_4D;{P66}%9Q`fLEp!+U!D}9g{drW>z`k%%gCLjD*>s{aWv7}@mmGWUZebf`vml4 zE{!`9yV_UbJasa#v9O~mo>y7Cfc_kxZrKAwme7JU76D$yZ-+5#);Rj@IZ)vG3kc4T zd|t$lw-^3L!0$*K58i|gTt%zX(i@5td_>`R4}A*XGeQ+q@Avi#02wsp-fX^9d%W+| zD{03C7Rr{iDX?GqP1n7BI4aMpY7SggJxhonkgB1zkpSD`Y$KNE2ab656n^{oz>%Js zo-#&Vhe}mW*l!7PF|l=X=d7BsT1y`4mtVrN`UvX7SuFF}OtSLNTKjkYY*?ynaqe;D z)GOXP#V2fP|3`!azed{g#K;sCd)0*mM6Hl&X^~R5&n?6{{^BFgbx0;~5XxAykkXR1 ztcW0Rvwm3biND!T4T9|>cBTsl_FV?+X{5eK@uC}J(^RWpsUUu zYV=afQvxMTmzO_^Y)#npqQn?kn#E*=nR}P{gYhMVNvB+$xw~pEf7r?I0&>f{mSg)e zZ4Q<_GFsq;0Edp*L(^EvK|@Th5IX9)hDb8~PDBs!zl>B_32ZFTA}1c+ed?pmgq?)# z-vqP~z-9@d8Tq|>>j#s5O1axjfUM>U#wytiQK0A-w`Q?qIFf73=g7%wF4dO4-H@`t zqEPSlo7{bSB{v*5819M`T0oC>LTdS!u7N8i8Jf=U0B{)$vl z>w=4a;;IcDQolZc4N!|NhNnYaAh*n)~H{I zH`%wsSqL^0RUV^0eGik`IKMsL^d}j}JY|OB`wa@W?w?-*Wr8!f2Ol~nBMhIQ-6pE% zgTqA*fxxDD*>@6-R_9|Z>edIFilyx74nlob4%pf8C%BK?klOw&3TQXngY;;7$5Z<|pEwh6YDcx}ft94>w7txK*$j;vm z&78k2^Tpb~aB;N@2<%Zcs1J9KAEF;0@lrgW)dAQhVf;Z<23CpZMOY%VGwR10A$U)> z*0zh%bs?)YV(8Ru=O(xl*nX^>Nk|{h_1?)j9E+;HjZO9R{6YI*C__!X(|3O5o|ZNL zfr9O6fV(+?p4%-bL0*&Vz1I0nVJCX)7PE6DGxU&{S@+pZyr?j-C77s7F6dE`M0&Qt z1OA7%HxBH??zZK7U2R6vk-Jhc6Pp>;#h#r&4mG>9Te#D0T08Zwe#EN9z z$MICqO!(9w>}1*kgQp-h_;K?Ci-jd7(SS??fMO)=u5}x4`kF-(ncpu5ChV-i2r#85 z<#DMt107u6>^OlTQsGvbI_KQ1d;$X;Y+W#-4hj_mp$+K2gr$-$aVpMgVq)DCH4{%c zvJ&eZNRm=z)OEkSwv8xqU%ZE6CLehj)AJ}9B~kEgb3(j_Js2rd;&zjc!6)>8J3BW_ znb~$>JEB6ICD%s9Gy@9`DpB8-B+T2eyqYW$cJdEa@a~+-G8I@O5G(cJVnDh_9?2A# zHI|Jn6DzwSVIwhr1vmjBbJe_mUbc73D?c6fKdEXl^0+=t21?oZlN6Yqd2QJt2nNZQ z*rfOF+}~t)>OI}N&F)Hsja+5V7M4G|ef*QXc>i?K63uEo@i@1Ez6#cF?pYVQW60B` z6_vZH;;VA;f3pDY>sQ-Y@rjnmZrnyjAPG|8^8^L(C{)mF!se zQl$D!RL~rq+Ll+IJ9&?bjvc?XEXRH)q4CkBWPhWl`Z<=JQ$ADy>tWU`Y})tt;dtnR z!l1u?A+bA~`-K}YU?`D1=n(+<{uFWT(4VLg-K{oRBci7;)YR_BcWDLVcP&i7C-5W{ z#Wt9B=eVwNuSD$xZB_-^_QO^T1%$MB8nENivD_&oi(#_?kNKmALtjDSd&k8!mwxZ??v~` ztQQ}d)0z%R4eD>LfE@-aL}XLr)atXU^rcp9C4&ELw`NWhEMBytB=AxgTXjJ7(u1g- z*%jP@5Es~P)F7MlHIQRK2Lh+qV&jAI+xWQ248l*Lg%yNhzivJ)3Kccw;LUdG2KS_$ zC?$*hTfJ~*i0%8o2-^1^;9xn;6k)I5M)RS)pCwD@r&{1lzp6O`i_34pIe zg$)}dI>3Bs4rGN+UA|WuazDh%;$>BW%(iC;`^naz93Ow#g3N@p(v19D!pz(zr(j@! z4D)*G9jKc1Gdw@Jct2X6#ALCnfqR$(4&jtIsyvQYMZr)$J5P~9CFq{?VchzRG4y|; z%!D`_1JA;rx8kR9Wpm1fhWO12c`qBuvBYERH2Fgdw1anO%k~ju{FZ}{G~0Z9g_T}* z4QrRpX-`B1x$)DM9QJqLk+^E!u1grObFjizt|*~@fjax6PSo(#1ES!ePG4^r>M<>p zR|Kpw0vvL+semL50DFbsI+XgUUDs;G>#(K1PxZ_W004aL{16Q7rn^QGA;2{i2%;MS z_N_Ei1ya@Dt1xta@>W4S149w*qG1GjK;!<*452vFurS7B&P7v$i|}wXlBcOMhkx)P&>R#i#FN!X08M-NcTtJXi0pj*1O@2r`|}P?{K$c|#ffwvBT?!78uQuG?5HJqX7QEmxq#KY1`=Q&c2tT3EC2)n(GOe3!_V(&U}hGAMs9M;pyPCT2!Y%Q z&txA-3En-LAMp2P)w-yfJpb1gI?8}x=#sS*)Tzgf%Q>b(BI4Zx2uVr`7LD1v1g%Qp z1aTTZv=^}NL}yGR2AHoND6vlX9q@rJjP)f(`O*w1RuJK85{}O1D1*eJ>vnSzBEx`k zGyRV-1Pt_eq8J6y2B9HKoot2@j^@Uzh<1B15?S(G$Iq-?e;Z##Mw{d=iJ6Tk?G1bS z$oz}S#Gd6{-$~SEda%KBsJKck_|p)+tca`G4WV6lN0Le3=I~KeIz7Xj&ch)! zFa^r&{rs}NkM2@r<6llA6DwZA*31{p#F303ShLdZX5IBZ2Ly5i1eSh3x4hjK5^bb- z(!-uz>)w7a$Qlb6;1u$_79iPwxwWWb&>}crOckwB^YD#wWZ; zK1k1<^F-4Ho9Uzo$&KzeNNzfe%`Es2T0I@byFirX z!Eu@l!ukL~fUU?*jRDf~HxelXe}mrr^L0oOG1TKOQ*Z!_jwg9AOwd<5Lc?Qvb9NVH z5L`*tZ;?Ff#2>v&iObX`+(v`w`#Q?ZJTq>Tf(C}ZJwwq z@2cHiC`|k6HB?1r)(H4wmgdJ83j8ed?u`k$4?B}K)1LP`bSaN#?qAq0?%6S27nU^7 ztuY`D$Yyd}_pk1sFNMi}g!R8`G8s{Rf(3B!p9kU_upvmx1){m~a5dzIG1FuVUi!I> zD(Rjt`K`A&<1f&SKp8l{QDZBwk7BVr>k_AMx@c>A(FjYn1h{W07kE1$PJ`eH?+NZ3 z5UN4m?klIzPbqY_ zVR{3cbK4)|;+$viA`27{8cyOtifpyq$sJSxOmb?bLm_lnaqM+;b{03j(~E=e6vN)) zBTZLVy~?XGyVH7Cpe%$hf_kB`iwu@4=|MvNzKa*6)-c&u_Rd72-sD+0ypf&)@mNTF z)=HB2PlB8#4+Rm#KrwBhnks-v8rklz)v*D`Ov_BUNnG!)6k8s-Zvd~-6Zm=$2N^j{ z_7bSkftk9!dLa9ob+^H#zo-`1@d6)8k#bniMz+A!0EH6tf1B@7Apw;ulW&UC_Uapo z2teuy_tQxOM1BL=qUmGzh@^?)vzv#T?%I&K^Wk~?ObiOMQOYP((iIMr+NU}_PiTIa zv5FGLUw)pvATsu8)yJO;aF);(%6)fL_YF?cFF^4Bbo%hG$RZXnb~<>)MB4Wmo7Ehi zBfGWf4RJAx*SbsWz7z5>CE^!uQLOWyC@}b#0Vv9@cYp@GfW%(Tsm*Ng#t0H4fzNc% z`m(WMXMsQ~l5-Cih}k;ggB+5l(u*-AeT=^uZ z{)H#xh{zM;)sB2f0{M0meZTOV6IVE-FT!3AWmIo?D3X5@AcEWc|bElmNY!k?QLCZf{3>TTM=zj$X& zZW+YqK8!*+@~{I|wDj!6E%E5iIC3*H!^rRr6srd(Js8MKHCA%>K%G5* zShgP=DUFQxzlMF-391RO-#`ul2K32u)9cOC#lS#8+wMt&DQ2h)DJ3I$&KYcu(3WV2 zdXO=5#)^p?^!D*@t=zv&VJW7TC%5!Q49R7-6uCRbHTQt|Ks4oJAdz-CQC#ez58)l zfpntFsq(;AqeZGmbP4V&@LE8Su5X9e{5=$3v}UG$*@9lBXB!A>fiy0q`lZ^i#V$R` z{jaZt5lLc#d26s&0v2199|g23*9h$=1{1?+zsT{htClEf2-BoARs0_*qJ1OQ`~6+$ zUJJD)hA!*2PnrE& z{{r}nXUJ#BPXVfC_SYeAJ@v6Zak82YQv3lrfViSn( z0|RISjWn481i~QBAn;Isk$%NK$D{G_6Xf{ny4Fuz@9FK&+S#ZeEDHwBo~xcOoX+>K zbp=`Bc4KA5Gg$ukk$+{=IbYAgeQ+@_>1yT0L{WvTGpfY*-_*i(9iNV&`<=e!36Z9hjlOwjx(`eVp(tWgEd6+xpOiH@94m<=ZGxAbHC-K?p2Q; z2SX&YKqsjKF2_3HI*>4E`tJ66Ld3ol^S+4Q0^OmL=h;Aq#Dm+U)9bQB2tWJp19~Cn zPXEEqh27o&oH(2%OJlYM`lyIYl@nRKF0guS?9;$Eb$t(Q!M5TP5LDem>yC9Dvn}oh z*o^_CFx^qXUdIhi*-I{1QKoa#_T<^?B99^hLa~t z8+cA28B^yT-0XdoO&=Ta^>6KbQ+)n$u_={~u{2PPH@e$|8Bq0#9G1;Uzi z7ogE8uZijRn7ldwSD-J{ny)&C5XAPHoUL&yQW7H05jojkX#?iwKx)}j%6kYB?o3nL zVw6Big5ZShOgBio2Pu(iQ)5_wFJEl~;g7Mcq4WilZKb%fuY;03D<+^yZS|c94#y4< z$@{C^udZewU3gd~Y$P_J7ext4PDAB|1OaF`)kO=Hjds?= zGPvmpEMn!lqq`A|E;?>F^s`A@OIpvAofy=QDZcSG9_C>O{h``$RhB(*2(-4NWih~w=cuRW*MKY)@`Q_u#@*{L6mSDF6CZj|A>d2Y=}C+WI8JLntk-l%}D(#wQ*UUfQ24hhVMy{B!s%K0)N6ZsVP-FS4oPbv9N3;>xtb|;mO zg*n3!10;j~PooDCg(E>b`ZRx6**R@zowH(d@AQvK4tl_wjvPP(g7o^3DM;w*Ih%Dw za{sJkc{Xu?24)QaMS_WI*9LXvTCN}a6OLoFpR(TM4pH4@3OS$O{*Ql?BW3``?2MHZ zVi_4~9+uA5eLp$A{rN+fCA^h+TSk>WIbs=LSRnb!$R-Kk3ncHYcBux2fdmC841Vg4 zIh6L7mqxAQ>c)xWe-K_c{1XB$x|??2bJ{DP+`@DS9^PqzMG2`8AQ#dMkx&ctKXX!d4P_4m$X)c8Vy20j$l+|1^!-_&VEnrfj~w` z$G}lQ#X(CgS~IVvH$PH6eapIMj0qeQ0|_3dS1vN1vihu>v<455+M8ZvsBHhe19}lJ zdf{2Svxr?`1}rLsV2{lX-EqVp0(dy*-KKNrz*jHhCNs!>ibE&Z0S|YTfLj|(0k-{h zWZJpDGArm)qXg-ZAh^S9VM$KCGay`w>eu@wZY(ahg~S%17m%xh@CIK6SbxcM#kdBE z%UzMCy@VU0|H@HP5daoIdc!Z}ACbG`MQWOCJTTAbmK#>c=T~;QmhrX|CKqGo#0y1OKa~ve~tt z#afYr!)*fmO5uLb;)~Sc6ZLh}{QipQ%3B*O%AV^N!v9uzF>J0YJyf7cNSiOyokm2z zDrN~JTU$0>U#4NZjvQg->VI2+3Klu(yP+^;8h7HO<)D$OR_I0pPcVN(mrZx=uN&*V z!jPndfl=jX`X2bK!Mh*N5&>*p#zeq@6xk}~SA4;-Y=76KOh}*FIuM~CD($=|CX2Tv zxx{xJX3G9(V6>|yI43>$eal(=RKmdvq8CQqW;6{NuDNyn^t-Toyh)7ZpI+zx|ow9b3inL1dAk4FUaPuHg99A`tW`-E*zsKvn-}l|$f1ZbD2AzR(-m~Am*IsMw!?RO@ zfzrR|DU7<9Nl%tkRHe_)ji-ARW{?I@;UA22yoNb}yt3;D9x(YepxI50zBMPjQnFft zDfarZ=3?!%x<_VhVuaNP*~feT*hT&q?1-A2cCtbS(&P`Liw(jjVprOp?ift&;Hcm0)73Y%h0!Fx(c&s=K!5l2h9~^+DCJnhz=u{r26J|=f8?~qWOxE z!)t;zDBlu#>CB-^BU*PQ_pGGGN-b1?c-r&*X|763(C*dxUlUHg&ss_%`pCzVR_AG0 zz_0NY{QDY}zO%oj+qn*-$bR#cE?J6K{LDI;x?0`AqKzJHTh10ok!ASAg}oWFO7X-{ z#&gO{tM8dA^FAN_)4~$UJI~3-CFVUWkLfQz=%;wN%`r|VeCOe1{3+s5N16bJI`{)B zO+<$nPrCt{0ZY!MkF!t_&u4C%Mk}y&)*pU&;A_NoX@7ar>+dxX+fJle{ z&^8%za3$ihizSibzGjDICWUF-@j!C6H`>JVp1kMfh2Vc6#X(?T1x4qa+$YxX9VY9a z8YiUHE2zOz0p#@rcI&P?>3mJEi_nAq`C2oXVNgKhzD}h@*3MPxOYS~7CP({NZ_OAtU-Tu#P*Rf6ORmwR@B+SVtx^Q7bz(!h-!$KRa(%}E z0t)2V>Wvyk9V~3G`t0R{oJT#DXN@~;WIZx=No<6!FwH^&m;{k&?mG;3~S!b9c+@`Nd#@Ne9el`}v=>wH2VH zVIs6N+7>QEbR>1l>{Wc_hvkT$Z8lEKxLrLb#oj5+(m-5gK8f=}+;$4xT2^~!+yg)$ zh|2S&)vM#@{lj>~_1a4+rKYg@FjtqTX5jls+PpuEp z(HE!7poA@T8pdV=1OtXQbM7D|FY407i(4v=oImyqF1S-@c!JLnt%}~4uB`mv0zY?- zm`6cWkq0LL<(B)m+voRwP`(T^$gjcd{#kmurTd#%!|C3ultX2^k=G-NwO-C#4SL+K z*#1qan*ScY5<&vzJPmu7Jc03iqRIIotlE0IPn*D7=RH!)Ej+tolwo@Fa_&vZ>i&s3 zu&1Q-aCHbArQ)CCB|0QdLG|pcGF`zLnhSd#K4khM%8VJ5`4tgb9^S8 z(qE6nx$ChFGE^0yU?5dya4uTi_)!H~9BPnFY5r%V$$BhC9J zU|Qj1`+7-h;{@r?wa@S7xnQXCWGi?hqH58<@bBzXm1Q(eZUHcIJRf}5iBN~Is{}dY z;=4qv6uy75!#^)xMzk-(#!)a20Vam)c<|(EVnUp0)!HyakTduccBg~5RAv{PJXZ;% zL7CYF0!sknCqxL+C(!>{XFV9pbGqw#Gj+Q0eul~5f^Pc7C6sni#ZzR&#q*;Gn+K(b zgmnY`pEyYfo|C%uuEXL_q>LD3)!<*@oJ zTOp0cZ7UBwQWw#Oe!yEJJ3{-_y=rk?fy1)oaUEBHDb*iU=g3Gz@mtwH>)6WVqXG>D zqULnOy)%d6dFhnRy+MD2q#6P00Sx}>IOp^*{Js4DJSV=rKn(MlBa-2hpA)bBWbn`K zM7SQjyz$nYd^p)9AAk=R-VM15levir!`E!|@t&+DeJ6u!9Bgy#iNR|J_9G3E{TQ}K zn?_eJ?C-zMhZ%xpr%r_4^~48{jFVTcuX(Th&*_2`{NkHZ%cV1c#FsAQPkriUBE3uI zbLC+8T%G*}#j}Yj$%~g&*QbEp6q)e&IPf4?KS1WL)VTHC5H0SfZX`UQAl}dPKP*LM zbnWMb{09B#Wg2V$0MvbuJ71CMu@?O^ME1`vW%>p9>E$fQmP|BOZrd+xhqGt9gec#` zq^`s0k1NbhH~|sh<#rr8LCETFT3I$EC`!~CC6lX~imlHYu9EY3w7pk@K9VeW6eOr4 zVf^Hzbf6#kJ{8r6((cjl;;CBQj`0Pe4*Kh-=__=w?_bq*-wM2vwDvz|PQaU(Ux1K5 z^-J$-Cp?t+dbhwN;0diw{^?+GE483xxmWkdVN@X+#qmU%)46PTsScRc7G|^#z#N#t z^N>X*%Q3x`GzhKZyFPlIXCJ2N!&qR>HSxi#-2&2oVBJ42E^2r#&`bzQJ}a$QXy)HI zbld+nLQt7*r)l%}owRe~7o95WL&`!IYGc1huO`kFf=#WmJWGFd3n*w9_PUs9v~4|o zXAK(rbLERq+c4`%t!NbyeI9}fVk~}!W;&GqoN{`Zh}eK`Gm>KE{XO<~#%f~!8Gw=; z&q>$!cv2*rR+l^?5ZL?T8*meMr%3y7a+%5FFrS#PYWC)yKi`*UdVz_f_0b_;-phYB zv_WjOe6yV3{g`&0qbc1zyK%Phk_q+stc2U0>DMt8@Q=yv*)W|jbL+Q5QtGd#f41~r zFW#x~MJu_J6zC_pTic{b%oU%YN51@aLFzgzFN`9;oE01y2#6uIX-x1eLrTo|00qvu%< z7ppsenObM1p|$Ip^g6d+c~&aiD$R^==YcQlP>&(w$ekkdDRB>1Tpj4szl8tLjAU0` znJaqd!p1w6t}aqsKO9E0@k2pYvx3b_V!vaOaNK4PxErFgd9&S zXq1f6tp3{zkbJc>+k5H)g2z?(^H$)fIod%kGblo!YaoDanmVYl9j3vQDY)Ra6LIf| z__WrB8c#>Z8)2G2gdEFP|SV^{F3V*VuY-6_nm!@Ys8zT8m=So>)~bD@d;{P$dd zFmZ+vT7>-b*Fzb*y`Y8c*m`|Bg13U?Qum358?5@{PU12<13{wDMTBm$2mGq~%TW8m`DE5-ir&S(0@#g0HSohSqL)KMucSnM9jyD3$~dtSObD)j%P;Dh!t zpGM7xFW;Lm*QR|eukqI&ZcX4du-YsU~whsJgQ5;J)=Z5Hsb9|_KWc-2>SPTm$R9!U z4Ln|%rS#Ad`-QU-m`gTU znxWk`DzOJM&R#ean~T3Gk=(0}V8&mu5$SgFSF9I=uGCtlg(&o<@wYzEwtmmNzQOB? z+1T88e+%=#1xM+n&pkz{b)|g9Hm%)ir`x!96vKxtkn_W9A41gjCxO`d-w(sg%0eay z%qR_tMcbR>UU+iw^taQ?_$dXSCn)LE#>?6Vs~;J{!)oQd(B;^NpO-^hn~YT=;x0Sf zJJ@*E6cZGDa&=ySBPS=UetOk{t=iJgCpv+uFtl0WZL8^{tFJG!<&NGxCGg~sp_@&# z&_cCcuJf1g5r>%y#kpWmpm@wlgw{A??)u)U{P&|4pgykha_JmIbR z72XH>-(`c;?wuus%pL{(&;MR21VVK>O`1yEU~J?@MYq7_1}-4?{e05z$ATX7w5Gxhl-{Wo4atKeRJAlRY-pLgoCQqq$tV zUtHYWfxjTlfQk5=!H}|ABmPmi`GKsB0#dKVl`r=FT$b2icXBg%MFK_VL>+!Ol;NoJ z>O7E7IhE7qd$#(%w`Y%5H+_0>l5KCEXVh)xq-qPwuOwY7{u0&jr#ejqy(%$O@JZsX zf$V+1J$XOn{t2&B?w-1(x2Eb9I4eiJ`qG$GzzGc2!NT7Ov3KY0j>TC$t)e)auVAgHa+qZ73MthiY`1%%S^HQGb$mkOG}v* zarAUh+L3_H#>p>DBIJLLVnuK4rpPD7fZ>ie;vYow4I%{MMHti>gB7`WrlvVEr#IXc z*cw!@NUSnkxPh$zYZ->Yg90pyxe{{IZ-&I zv&s0!=uxA=w&S8(cQP`#NgJ!b*-Bt$f8kIVv&1jYa1Rh-N;E;S8pcSe%T|F7+a<3}Qx;y7<@>m0O(nwjp1`0Y2Jj_;pD`sAlIb>O)h(~uEgDKDI8 zv@mx}ZpUo)xnyKE479#Pz)q`XgnOB#ez{wU`%Z+}EXnMjUiH{}g*8{8mGe0H=Wx7{ ziUB$te#$oH-(J)?;9HsN736-=uD-kGIn#Amg8PFlY6g|f!`xZoWviYt;pi$`zWr4f zVyXI6;F~if`SUy6$1P^{oScW7>d7dtY&ERb9>l&we&Q`@>lydsxg*<|klMy>GuJnL zrnq?uw=8{RJhJZ9I-}Y9h_46VNP~L)hfU`*A66SQnxu@n==t}>izXcCV$>}2j_&Tt z?wPI6Je)N8$iqeaV`Cvxj-o7nY1o$J3~}-N37PF;qq{a063aHc8zRA| z5^uMp1SFHv1=yct6{sbHNEH;fV^K(Hzb}+zL$0Z;E*EqwNb(OU*nP>mp`N!QTMaonTU(x%< zw|16`a)n8qDYgCjUN|?%Y=m0Hz4;hj;Lm9J<)=V+*OrX^TLu33_gT1-R-&!tYX}6M z^8cj3$Bfc*ge`1ZDx&XGIs9R*wP;7X*YKxw7#wg(8?`B6u_>5$7F|51H!hpM_a7(g zccWnWAma6?JS?fcdSh9U^`5GpCBPo;vn~IFou>{bum}gKlsx zW%8ELMHA)jh|qmA6-GM$R60 zYBhK`u|5Rf>51LISRE`i#|(kreH`B%&#&~<3K$XeemqLHGVO}W9Hc5zYg-rA#|Nd zia&o!n?hh$V!XV%y!+3KS|3HP=_%>*^sRi*?AOdHOc;J48IYUWni~)m8OvuUr&t-Z zBp}_ctNrQDsdK5VdrEb8_^8FNKU6YM`ILD=sROowvafcbLCCSK`||F2>@iU(N_Mdc z#3ij=QmWj<22@QOXl&J^*0Ux_|=&!?K03h_~t0$a6_UE&e7uyS)7RX(%cgk!Fg1s&f?Gm z+l3h%Ee)@h4C#Fy=5zn-1(V=WJjQH?xIG3SGrf3R>Q^SreW~`3Z*w8ClMSCwSH+Q( z_?F}iB&!9?c21jQn)5AdKkYC?=87`Nm~7IbHc|1Jkf53Pu7BUaJ^#1 zy_MoecqIB;o47!09WBzAt_SrA$$6ch4^B=T&5GOk7gc=9M&^84^|VJiq3VoV9rxH1rZqr4bAw|f1e&e`$(EzUi*Oys}w9xzAF;m?*U*)*KrYE(X zCZCS#hWRtdWM;H%KC{>|K(! zLUH1Qo3q~+zMdTQ(608~Lya;p2;YKUL!~=_VXJb?G<@H4RZC%~-m;81s^Z9Br&D{| zwg1bbIDTf;!Q;6UVadj8Vc6|fnfXFS{`C9?Tb1&9r@aqXL>)S{>W}>lbMF6A#lrvj z)s8(@U=%+n?uxF$q`ep7=NU-l{+2fXX4L`!?~qDwu8Tl|AMP6z5TuJxr-kVgM=g9^w%eZ$ zYjLNre!3H?`&`bKT4uySNk3oD$68$_dDhkANj{Am%# zvl%rP_|*=x%kukhXf9vswQ#X`Et?S{kIF%H(za8iB+osFH4uJF{$oP}1H+#y z{p4v%{Zg0G_<)hzgfp~9dC3vn)elEB6jACBriz=C4RoX<} zY9aiF`T2HMX9$9tAEYGt7LZ|6e|_CC5i^X024$K~%JRY8QpfNl9tLh{OkCVk!Uk;q%KexfCrDsHVUn(p`BwsYrC-oWA`!=1aPFw+~@y2v&1 zKxkm>6lrqZihFR#F3roDea>6_iMweJ>o4HGpyk55u)$?XsyuXq;v8V2t0A!&rn zk`+B3J#T9I!S7@Kj6L?z!ne)-zW(nMYwsgYA`Z8hHMFv1E^#_Lxtr%H9F$syF^K0` z*4l+Q;})!WT?BCd;I-IDuenNotur=HvXwe6(TiE+ zPwT*QOH?~$liJMXjhG8YxPo{ucVjP6s7hVS$~{S5RxX63Tc=;X&x*>@d8filZAoH& zHX(m7d7Z&zu5(=)sj-A{_Hx0o4j-Oe$0NswQUteUDUlR_scX&Po;a3TauE}P?~LvQ zojesq*C2V6RqVRtDdmKqP$FgT$LV2761+^;zSsvAiAV5n&S7h8d!P-@O7e!5IH|^0 zBUf0lm0N@rh>~^#F-6Vx=DuZeGEBW5u`jb;o6_sP$b#b-85v?ewO6C#fFSpbyASQ{ zZYB87ya+ftZ_uyUS#@6y8(@-x=H1r*bn5w(bKNf@y<2SepP#>eakYSy#LFL&OgL*Z zuEJy6e_itBF{^!(W962v#l9u>sHjEjh(=OIQ+>;b+z*jCwA7+n6fzwirw~sD|J`?O z{hGPpgj*>~QixGk8%+px-ASv=PAJf{v(D}$4W+a;Z##7(9M>V32r(URf*!L*2&D^cR{U56qr-_T3=8N~GJD1N>T6gc6h4ipFIgveH&$(PC z?&YffvYr0t=X2Kx9T<6bPFG}sx0jfUN2O5RHU-3y;c(Us%wWqmidZhDYj+9Jr0C=Le4*`W ziNjq$Ngpe`Kd^s{O%eAkZReo>8HVjKo5oLXI+86+NmF;#wF>D&fo}D7&k4c=?}^Z+ z+lm;a@4GLVFJ>+#|D8zRUL-&NSZ>1F?>v=lB@HH4v&2Hh^@D#}?E1k{m&HRNKvy5P zEAJ|051_jIZB=LFRG@80BTGgTS{$2ul@?C)^U-#TJyD1<^7O{}KB;yxOI!{&8LjLw zN_-lX()S{vXDMO>ou67RS*xpR{*;@X)%ACKDYp01t8(Lh1vwG| zi`NzJn#&*+fSwzXY^91$^*EMsP$U>of4gpLDt@WIm61gCjqL1n;k8xmwQdU*i@E*K z^?be2s_M9CfHbk;@$idOcpxL3&VNL#hdhQrkW5l@{>evwJ^jpkaeNs2-6Kh%Y+!%f z*262h(szNh+D|r+Jtj5<+8GHaTQM$8J(6hO67!!I-$L_J?&(^*Z{K#0UeaHi`ULra zx>Yt0r=XDhtYUMAI3Eos^E*T6v~gp)!9J3P(`;?)8%A2W z>?g~|_i+qqpwJo>N>&rdo#?2!4}lc^wqHCaC%N$1rLvK1PqzmM%#On4D`w{3YKnU- zy%Yju0})p__iXfvd|kTirzvg<3Ia|Wt2Pa4i>qnsP-uNRuESf`Hp6B(|FMi z-TB%olaQz+oKzlt!8QeRJ1@ldSr{aF&~t0F0NTHBDY&!p8BbQypJlm>&@PV?a@%Lf z+3S^;dKsfyNI`Qx+28}Gnz*=cx)`f%R~E(!3zTBy_DaPNfKAh141|6XzyIb=b5JNJ z{gfYmr`%GsEO7)|CcPlgk-;55mTn@B%zgF1xZmm6`GA(Bo#=?UYHk@V>SHTsN*c3v zqTpM4`n9d~XG#}%T{qC3(>u=nmENkeGig$o5-6_lMQD|j^rDM3imYazD!K^hqVp)x@>+?%ra#B6m;v$l(x?K9?e zn6H{^dfkZre5TP{(cHA)Y5@4;}vAo zS9P4^w__7Vv^ukmWrmS_ewOo^Z2ed^J zkYJQy7cI_qqmiKBE{P9ID>-d7y>WD`RWG5AZ`5_o zes7~kSC{|E}#2y@^VKJPqUzRMvV>TxaG!K zyZ2cf%YZ(;seEp`_0Z;!eJP=g&uu3;ul8h%i7v&R*+frf0LjehYSsVq>q#HSZlbuY zXb!cmj+)oC^%BpVF(XFhdp#3DM7(LQ{$|$bGSbT>G;8t|Q2XwQ8BR9E&yi*{{MR3b zsr3!yD3C2eW>Jxqh^7>dLobPH6;hC&PyP$;n%m!fvDTf)drMSWW}0DZmtr?zKzA?~ zqd&Yy?q6p4va&Of=k1B^0X^>AF#eiQxOhD=~;ddj3l3$xXt6w&f2Junb zd>ZlF{iL-w`62<|y>{zDIE9F5^9 z3fzR^f$i24l-qLHBMCwdKD-r;djIK6{P4|Ce$M87kO4ZVG!<{{3T@~s#}%s;AtO#B z4i7^%LKjS$QX}IZyZ2E{b^q>T7R>lE%6o0^mRCoTQ>8*b*iG!@zg46=jqE8B#{SG# z5w-8TR}Xi)l0v^WXzzO2ehED_sz5j?qic8YoyyN~NL7C;;64cy%I^o!1C&jAXI=zT zO%(TRsw6XigZQz6Y9`edN43*l8w_Me`|&8BOW1QW-YntoM`uQtWE3@K z06do{7&){SBeG%#EkvkazJXh14gaTjrRw0(`A!_lrawPkiK?Uj{)WKlo^Qcu!!QOX z^)L$(nih4#@)h>bTrZo7sBwX~_49})HzW^y`p^71u)m&GDk9!?6=oH8_r#1RLv9*pyUAxWX3||iSRyM)?LrIgy_~D88g{yZvQlm|Nw3pP ziRY+J*t73}PCc|~R`Whp%Occw0$f4pba*aP*@ye{_3aKV0R|?Sqw; z64$0hu326W;8AQ!ZK7sE6uC_F4eo`W=_hnt)jJ{mIZgo&RS^4je*2~Jz&@n@kP9N| zJps8}XO=|O9#N@58${ruyyQbR#+)U^;nU_)9l1D87Eo; zRAyA|`1kdkFWS@xvo4l%3q?ZBMpn?Q3~82NcFoT84xtVw$N%jGnBp->9i8VgAu;qP z;P~mM>gC&udV9r)-SMbp+aAb1*&!4BKz^gQ#Qlt1i0Ui#=Ksn#zrl&F)wJ0BaG#gMV~^a6GV7W~287xRq| ziwo}fZ72W0mW|Iq7gp$9vOHaKU^N75Rc2fa7=YjKbswSe<-MjyyZ5M^zGI@#%mm z+q`=@I@Zm}%hbCxYR|g-W0m!X$r}>#NULHCiAe&j{9t=I6mZduw)Xy>ookwm_|~vS zx7?t_Giw4FQ;3dA;uX5_Eh1*06Ts(YoZwwD(hr}^*x5SX(lyuop~tXs6_>~`z8CzI zXkG!YW!{#Aksp4Q&yme))yox{y{H*K&VDnq|Gk%3e?b
qCe)FX^du62K4s82#! zXpW|`%fWW_F8d}sduJClu|^|jWXn|V=<6U}%tR67?tGyT=AcYrY$NIYoRCg4-cu zjQWs7d_|X@@&))}ORjsg&I<`Yra@_nyIW)x?`~WMt(b!}GWmOlp{V1SxgHm{jvL!Z zmY+?=;yMb0AzUqxKj!@f1)CKD^Myzb>&i-$R5Mxe>i&$oOqQu+`yl~2He!NT2pMM( zW!EKe?D1EGzjirJ?mse8j~#k)POV;&Lwasm*WRzpplG$!}APg5Yg!QtHAvITARnm&XgZ$o^~&%m^fjB4=S- zqmwlAz>9X8BeF(P$TnZoa2B2HgVB|VA=Unr4AR^_XpK5JlzyncW#gnpLhmrTw!vOi zQPjq<&U`2!64t9Xsig(GF{ABqc;foKaF0rTy%pUAvE6Ow)+?rMW+@shf9Xf&dJnUD zmF3+w6CWuw1@rF7WBBx`d>=u6_Un>Rd|w6}^?CRL2^a2r-c@>;0A^kW`FRH;xzID3wvG`5 z4YYk-Z^%0}Xdc3SUW+6)JJ2S_Q1j240pz_8H4*S?B?Xa} z$t;IP3I{m%wx4m8n=Ekx2G<2)AHBZm13N~@M4q5RXK;T@VHFZt;eS;I3A>t~Ww3{; zy#DSp0_~*dfHh>((n;B7Wi2eq94*`q_+lDvN~F*Me7#HEFL`3QIV7?9pP>2qVAsMU zrdZQ$4iIAuzQU2U>hou5&FadWc9iC=aOm=LmKXYVq;L@bT(O)2ZRmRjfZ4INCsOe1 zjV8Wq=;C!jKK%PeOs|&?2AdYzQkePpXY_`v;7IJ|FKHj|DQAVYz!ISlB}nuQypiRr zt#N2)q93zF(X)nJ8<{#GeWiCkYc#G_Ea{gh9$=)|Y8?DiiRa^IQ|JgMVX*6zCbYm# zXl%~D1?)|?Xf@ZjHX1CJ!o$h;Tli(_$-CPcq@7t74Vd8l| zX}2}g`sGOZ@{e-_h0A1Yp;9uZeA?XRrd>BHCJQ&#Cj`wI7Y{eHkQ(C~`M!}(X2Jz> z47;w-q&HlGIY~$0s~5GjN=6_pv`Cmtdect zb4zZrGxxO^sI@HdY)a2U+fi<%Ukx;Z1-cC15s-p^Ogc;d_qPIUN3uMpgfa!B^>l#OeC&Xqw&uc`0MF-A$x!hA#uf%@#|1a{bugv zUK4j0HU8Q%@%4WEiXg}I(}drE&bK#(O}nN>{U!7;+19FXJw7Z+)U2~Z+S<10YzBJm zJJy^UvNuqiWK?x2PdEdH36*mL9m&cNE93^qO@aD6sz#Sn+GUZ%CTFQ*rkT$MwWOx1 zi4wZPUbI=-GhyE{waOwSqSa|s2b7;W2({8Cl2(sB-w>XhrQbYLV9yXyi3INNId!m5 zPHhc85eOHLYDXT6oQ>df#(?xez%i+jmZXYrItrqLyCr7dbO9MjSZN>SK9=alk`rQV zeDc5;%{OwNu-aImiy2iV$XuhV`}$4+hi{9+=y6r9ciBCTJ;P`7?ImFsfmRc|z)h$- zP!kAHVaO+kCEHxp$fRNed=8Bsb4Yr~+7|AX5z@N{n^MqkyDYq-Gx_=wNn0HXa*xZ} z6b1(nnwg&A2S?+3K05tw|F0OO+0efIRD#(o`%5z)nMR=%U?uHx(yCIr@20AXDqo|Q zl^emD0BQndIK@=-!r!@z16u4@d_ZqGn3T%*A|_6gp2`>MG8)txOU*JEOl4DF)R5td zgVcn9^VXO+6eoI30%Qa&Cz&+tpvw&;%Mccgr>x2=S6OuJzlJJk+VoZ|(X?mvhl*15Sjs_Dcm22(izz)voJGTvqPrbuzaGphc9jY>_UY|riuuS z37Ome|HLC=H#c`Qf$%xv>8CDJ-<8G&5}+3X@vj@zc#8B?7Z9T^U%vn1IQTJz%PbyE zXg00T_WA$@h#t&ZW>$a7*YpPsF9Mim4x+D_(MuA&dL(?b8nmFf=7)oj4c6QajA;pg zDY?`>jz_40W8K01qn`Ri|9N|0kU?76u@UnwAmq-6x`{yO@w?bQQcL%BTsXV;Yv3B8 z0(i(4oMt5l6QrLG|Gb55Lj$P`eKa?^g_KXb7FBKLcqOX$U2DI^Jco zTzzaLX~;ET$V(UP;?*-Yr2@imV*N9+OB9J)-ycW?9J2zZ{rcS<&2xX_Q}1vPNeKWJ zi6of=j@QCfKe6{+wQ6*IP6hd5uW|eW?Ml3#(5QaZL-*TuAnGFfbn?a#R8%J>a%@aDtAc!~H}?j172{ay(#DM>lzCCleRC;) z{APh#R+)&t-T~ek`Nj|%FBzyL5=xk}c9g+Pqx1`N z{X4NUWY|S3Oo_#kBRV^c-%;^!ZT}XK91Z>fbGG69uLLfF+zbs9+~4hZCT>T^WrLdv zx8$O_r+;+62B0!DJ<>_skMP*iKWA~4$+g$jvMs(34b)}%RF8-PZLFb7GHTAT6!)X~ zwCGx=SZ}d#c1ZVZruG6sAtZdAK69$;O~R?z4;RvQ3(cp~q*#Ie3j}55^~vq#Z;8;n zP`gG8QQJoHKCw5d5z`_=$mg6+yVe z0w<8sG64yRAMN7dyuppc&aTT~%o<6Hgh&j_z(!j>6S?TQ9dt@VX7vng@8Pl098m5F z<|MR0lp}~BMlLB!v9s}C+5t4~-n#S+64c($l$@|%CD&JOcMVPTFe_z4Ll^+~{i@+; zL8%rjORV3Zz{}&LD-|h6Mj9)SJnIv@+RpWApl|}A{^tsXFzKTT^V0PJXt}JtR|8g) z6X+&uk4|%^XjQmZO-FoGbVfpWaA?Z&e(#){7JbcOGpM~CpeLkW9&5pfZpAnl1O~5E z^})G&Uw}g|rb)9Lrp`1k&Pq&?0Wlbg3So!)1dl=x>QEOL48z5OjPOadF%|u8UD`@M zm6vL^52&kMv>ft(Uj@t*Ui>T-n~=KR?yar zhpNI)C1hWM76d=%p=*_~kIZuPtO=BRdI|*M^2vWQ!S4wPo3=(bnSPimJH+wc2o1`2 zzdeq{3f&3JjLO?yx1~emUM4<80I25CgM(0;)S*FRH^@`3uoQNg{_zx7w2j{GjU1b8<;Fd+&`M zSSi_t2R|h=y(4T`_BgS7#yfczi$ON}lIU4gUM)?#VEq8q(rwmAa}p@EE9AT4_d|)- zJr5$AG#Kp6Xo_LL}TFWdNPU)jbgD%Z-=is1dQddlc zZM5@~i7*wfoo=S@c9kwQ|MkJ;M(eqS-mt|J{GYT+bH-+8cc2+ai07rOz_&A8plTj= zZaSkAaqd!XOR5=oCgx*#MU<~G7#v}wuKbo+n4lxoORcTbm&lvK26$|_yMG#fJ^=&A z@$o6th;V5#zQG=N41)O^fGyliEN+ZrZLiX~RK&ln1s}5S1O&y3-v7Cp-vA{y@T&i= z?Hz*$?3Me_?-10mGvl-5P`rlwz%7Y0(wF`*?@Fuw(sy{E{K$wHk1nH)4n`?alVxYQh=<0gcgwPs+ ziLXBOFD4$LnmsU_48%^#Ux4p1c=3WOmYqbMES|Q-yf<>WQhN(v-6avt^ak;mRIqF7 zP&b+pEQ%B3L4{zq=v6-4w;M^88ui3&vmCcpZrMFkR|BTD+%2znK$c@*`?G$1f&6l~ zZpepCXnF81wYd|hUI=_#+zBDxMba#n%}Vb*bh1(E2q)3Fv(QNSLIay8{F%#-<&WVm z#RJ)=|764L!l~P7;7{rS<(ys?Y)L#UH?+an!+VonrCv2LGV*Nh`<1g&FOD-qD*?zK z5Q~W$knwIA-4hyV^(ing6v^kDQTSOWg?JRy*j#W{PomCBPp3%lRJsCa4wOZ_Pk;^K zr=^i8ev?%luu=$3RCU&$#4Nxzkn6y?s(E7Q z3S=u~V6j|#oXxFV0z8j=QuF)-_1gF0*nWIiqD16bicA2O#|D!DJOS54IJ_xrI`H&S zwrTQnM$6m>W4bd5r1#0F&Lt)}Uf}UD{{lHvM5=8B7=~I7G(SNO3?b}HDRzle}D6_8?&sv`AEn7c>d!BTBp5xLR zWq_o;@9 z+Uryi2n6ZW9eu6N_yyR8&v?~69TXyamG@haFHaQaCqE>xM_^~m3F&5p#OG;j9Q@Hh z&w|i`{(fvp10hDJKq}9BmCs&o;L8;Ev{=H#^ZV11bat#?NKHe zz}nE2`4qm!_#Q%>bp984h9E)04%c~k0-H8%GV}n7!IheAK-O#^OAmwXCZ2|050LkzJjd^b>q+YITq=;@P&(@U_q;`0}~J8KE`SLMJat~CIqKp z_Go{i!=_Jemf7qa_z@s?+q%$o102Tztq9jj4!Z0nOp#D$f0m8g9Du?3ugc7xKNsG` z^3jc<@1?H0S80DPd3Xk>&&Advv_pAL$k9K`S8Ei*DbSbZ0tmYq=_RlD+n;pu;{REe zKmKHwz!4pLGKl2)eH?uFY0-qse!amqSVXV@%H5tH|EZL=GUamM7_R zWaoBuQR5uTj}%Um9IBtfp;P(YEEcOZT5GazgXc>_2CofGyJ%^)TD!OYwSX35mk++v zFJXy*1Fmnk1GW)zW0q`&;Y;W`*gbs<^dB1J)adJe0-Ish4If67rYCq&2xdb|jKf0! zO2@CjSVo!{YyWtk`uwFv(%u|K;xhyBCrBG1tl6|wQ~2SJQH+lH>5CHtltxlsG{{8d z%WuvREcGsQ^(?Vo*sdX#s={1t5PLKl|F*~0GFp5#0@iB7VlgB(<}y&lmc^|swF*@?BHn|IHM!1I{#azDe{t8rR zg}OcS`pii@f$CNy_y83wvP5{0f1(P3FEd^b2gji%4kj0V5dRfbO#hB5AmKG3JqBSa z)OE*GApIBRW~(dcU6eW?ctDo)bhF1f*g8Q?FLyL825C-NO)IarvpNwhO$2#iW743E~gQ+i-3NattB6H>yP;CyUiy+(baQ*(rs~r#iHFy+I3wdKuolK)qz&g&g) z?1Or?gi4dqlHnhsPk2?Gq$#S{oIn~4dli5t+s#Z(N%OZMtxA2B&(z{H-lhT$iF)i< zUIot3)OLtY2#dZ2t9QdwMRYB0+lFS(Gqt_EwJS1{2Y>PS)PHxn=TTsHfZCmha9|tM zN1aK1j0S@lOng);h3J5{5TFaL#6{h|*>8MEH>=2mO)Q5x{pCxT)P zdQd6k70I;tB1^V+t8@pg`2`im=a*c5iv&=+3HC(xxQ{6XjE|WZD((1d2cQ;f_V>@> zf_XD7=W7nc=`Ef=b;`)*TG7AIA-<5g$b((~z7e~>il24%BJzpj&Dq=8PC?l)*>(G` z*$`xaSRuOomQBfUr^$0-d zXM*o{JKPAnNMYHUst$!)TYV^dx+0bUZ=peo`t^5Q*N#8>@*Kc+tddonElMM5%a!=I z{{6`>Z@#?YsfQcs-|u`PKJZL>eqMD`iyERId!wJtHvFO)+{EVg!7b1k;m~;K8TG>p zroc+02q7acN-zN~4Jm?at*01GlEZG(>AzNdBlRcAQ!{+WQJ|_MF3C6byiLB>Jp;p} zIjmNllZ(XKg*o~aC(IA=cZ`E?5L5U}4LZVX*nB*EtlzNt{m?Fe3}$X3TR?7?)gN-i z`{2lJzjuH;ngku7X-72;o;X0plbfKeUJg&GKU57RU=@IoIc!#)v0WNqZH;w(^Ykj1 z_NICmgH;gjf{L$PZQ&Q}nCWOca$-EmmdUOc-9-*)3h7CN@L^&yFaIdy^1PP| zfv82e>~+0c^K{iAECYhG8zvNbwz~8(Hh81B5d{Ht%zDB^VG0ur8+l0?&0e zZ32#j>r;2fzyLpolMB|XvRqi`1wwTZ6o-%HiZ+?%{Xj4aj())0{zQmkkn$ltvdV%v zsu$)QC?g$KynKPP1#czu4R+nn=f=GU%VBMuN>ry6L01gDpyW04~1NAID$lqX*iSqW@3xwGEw#Ela%MMDs{neTN zPcNP?D+kcYu!!=>gAo?op3Gv`)$ZImVK7b)_&BP2Q5hIInlu?4bqEJ-C{$m_($(IT ze_tJeF3A_i=f7R>$5;BU7UP%qWeETC#P{E<3IcySv^%E?r#GZCZUS!H<$a&r0~@{G zXg|{eSwH~5j%h%WqJ!TV*1f2%6Z$&Q;8VQSysPEvh9}$DKF*K!0!{X-4#Nhi7vC3G zGe?*3YtY}>KejKg$~1?@$0;HZ&&xd8obt6%q_eBeOU_To!(+ zp@D(F|Mw}=cl3YW_Wya+VL%5qvN)?Wrt3YMEG5x3>3m$jhgz;a`1hFUzdjvs6>P`L zzkb61etX2gQvSWKdynDXN_ri@NZjfY1A(?(w$6pY zGaHvmyZ_hTk+3y&Y%f)7tySu?6?rVF1)(iVED?bK0c(|pAXFewmVjjyfr2Cf!WwHI zeoqnX1%d(zSVT(LD#*U71!PYHfhSAAvIN4WvPlx)-Q*_F=i?{zeBVtbGiT16nRDjM zoS8cledt)3_{huw+`sis<`%Z(Xkv5>KK~dP-7E`Rco@Hvw1jYk@3pk!m8Ecx^>rC-^@E# z>-o34g+mpHu7tYm1IbYH2OFMvYn+x8^AXC^(tVPSHeR%*)72@YLGDoSCJlNfMcunx zZpQl{%>12?(4#$$(AW7LXa$%Bhi<#j4+L!NFJ{WH0pt(0OjG>>u0c)bwvL}$=d zFSS;Ex}Sx6`a-t$#4E+O&g)7_(75k_pNJoGr=b#Jow(3{2WwzMXH`0*ZDzZol|sEc z?vieNeYb`d9HoE_V;Qxd-EnUr^unWWwFFK}{;LEFj7+*Fs zJ77TDa7ek^Bj{l=Yoj7odHsC>L-dCAL}ATF6+|f6SN59sU#Z?XDR9R7bRPW%?7)Or z{y{5@T;bK`tSoiXu7W)J5^N~AJbP5?DS% z%7ubqS`sG2t_w|Z=rZwhm}KY~YpUwkk^1Cn7XQdCc|F+@(iAvT8b+!miMNfe%k9+O z=8gq}dKqMwxW$}>VjB=TdwZ@crt^Z)%y@Q4^A!}a?MoCYFbiM#+V82bWszPs__|Pd zikBA2=&06tnv(?4HSE~2>NmoJ7lT!YOfrxK5hhsn2=jHCk;VAZn9t;LOJ~P4^!O)Y z^olW;BP?1T50dF*mz7D2#JLVa;zGwNg8TD==_4KCxj_}76;y_X*-pGS{&b?RsMKd{ zzTkPKv3niyX(=N;dOTSfG6e~l`Z`c!n6`AM(Tq^Jlh5*^?_yY~e!B`gG6pg?>c1%U z`M_kcUgc?aUXn>!n0EHqT);q;nYa(e(bXtX!uo=dhe-cZ^Ib*Jo`elQNNRUxcQzs1 z$zfqBWpzXJ@*!QKhNIL+ma@GCi1)ujqnGDS!W5(Yb4M}%odP%C->vhvhWy^*`gS55Y8>ykEXgPBmi#jBpXG-I z!r^U1YJz`G+gOeo98>KTS#+l+SDIrR3rKR;YPG>h92Ec{ouyk?YW^iv5@abkW9M~L zAR`I^>*K;90vZlWA|xMFF3XZIazR!tt$}4eduugEhPD*v@Zc7g=2bv~Zz3^oDJx-; z;Fgf#K;L!uQo8HCEkGCCbvTyvpJr_(!Rcw){Uuwt5offpw*4cY4M|z^>sQAUq&#dP z0aWhGrT4$$#k)}UeL407>-0w_h9j<3ELQOC@W0lu{&y7w0WNCvcDXTBbhIMz0&!npDlZ> zb}Q2ot*>;U%w-MM(l1AZ28>Ux3=#6O;Tiy zA^N%}&-c}zq0=9}O+KQ3eLS$pz?kaGs0Vsmt* zb4-^0SRmA+s9lPSvGALlS-HJP6Ntl1ijX^tFzx;jo@NIh4gaKY!>p~1qGSo_SyC65 zEmi7ay924Z(4^(z)tHf|Fh3C%DK8WdayB4Rdnn~<2QDSQ`ZnC(f?qNPk&1K1C>#&t z08KjYB(Ee(-}0GCYlEhrtkY^`3*WasDn54}`((lZ3TuPuB-U)5Bc3xJiN@$|3x zDbqpgS1@KlF3`OBVhNL>O^`P6aq@s?(JcU=FRoP$CdDUr!SPez`Msy0n&t5ejtX4) zD+qN;mM0cY+w0@W-smYfT6+Tb?z-N401KPA#TVG=RCTcuG6g5@;>lnO&JoTc?)(Qm zc8h!+v@7*@ag;z&^grCk;k4>NZ9L6)V58rA?Z@Jj1UVq$bY$Q(tT|NOD}>#^R9xm( z0SOUvj}xhyt>ELIwGqx4p(Cx>Xe?OQ83(tpNlUoxdSo;4GVOp)o9{?THt9ovrN%7K zm6|!$$K+^>>D@q4 z^;SVIC)F+y+1a)yktSyHTl_Gz<_0oJ@b;*=McEf>qky@BeT7)UVwk!SAzGP?HClcW z#Q52Mzg<}umOp~kt9#WAr)!ixw68+V@gMYZ^o>@^@lLgs1oZpB)D;Cnq$Aj$DicLk zXmfKyr}ut?l!J1BM%7}F;ineyf#>zgWJR~wQw-bVVzL`vU31i~)M_PQH;yg1ncm*G zrI|~hgG|gZ@=OYLy{#9&I5s9JyYa>4NM?Zbz)TNQ_1Vk#y&-ExLQ4xdzyz1#Z>J>n zS2W5v?>5R&iz+?l8Lp(cup|*y;&nl8Qi30^THP;ZwO>EJy9m)EhJisv%+t>)!cfurWvn=Du{DHK3#mvn$Q%Jf}*y}No ze$I}wX}^`((RYGn3XO+URnl{cyymh3PHN0f&U!jUbj@due7WV<1!pC=MLU7UTPR*Z zY{5ln1jic#c=B@+ARmPSana?jS^$H$OMV#C&{sc{)3swv4r{QHg>KVJ?w8EzdBtZ_i z?R^cG?zOKARI<>t0PhBs&B}y;kNGtX^1qymd_C6G3zivcsAD?$VH#_ryfHE4^ME z&g1XFuF$MuGKPknzDIns_O?AwyH^XgDW!T$vzqM-@2L-3=ECeKXQA=B&q^N8h{t!6 zmXftF4I{JG?__Gb>k(NVHC<2JSD+}2GzZcJ|;m+s*22Ik7>h~6jj1*T4?mYT#I zAup}5VjnO!^;*MaloasZHq3|^8nSY|$sIc7C4t6!Rc~B!eWFAHboL*hpJEoa^xKfCD+ z&jifn(!mwiU86wb_ukJ%LF#iv(8O81909?o6V%ptVTHUGV6v@jtoR%vqP@?wA#)ss z<+GucTrptl>7gS^rBRR1OPCsXy{95KXuQI9B3&jDus5&7L=6>#Y@aMPW*Ok=+Ona1 z3adZ}^Wm@Du;=7Sv8k%|z7}AU(PYALi4EHejNaC%o(#;($AKN6OEq=r{&id53l1L) zhyNC|t&OaGK|+4Avi=w$k14Nd^ne6+W!B-9oHq87BcdCcE97`W9?tScaowlF2Qi=c zH6Zg6w8iTm5G?(qX~#j}V*Qn4OZ6{B zAuseB(wWQU_7oyt6fym&B+KY;<)(SXkZkFnb1F)_g6~5kkGW%Aq;1eG2Z89?is1eg`__ and `pytrees `__. +Scenario Execution for Robotics is a backend- and middleware-agnostic library, that enables the robotics community to perform reproducible experiments at scale and allows a seamless transition from simulation to real-world experiments. +Scenario Execution is written in Python and builds upon the generic scenario description language `OpenScenario2 `__ and `pytrees `__. -SER reads a scenario definition from a file, translates it to a py-trees behavior tree and then executes it. This separation of the scenario definition from the implementation massively reduces the manual efforts of (robotics) scenario creation. -Although SER can be used as a pure Python library, it is mainly targeted to be used with the Robot Operating System (ROS2). The backend-agnostic implementation allows SER to be used with both, robotics simulators such as Gazebo and physical robots, with minimal adaptations necessary in the scenario description file.  +Scenario Execution reads a scenario definition from a file, translates it to a py-trees behavior tree and then executes it. This separation of the scenario definition from the implementation massively reduces the manual efforts of (robotics) scenario creation. +Although Scenario Execution can be used as a pure Python library, it is mainly targeted to be used with the `Robot Operating System (ROS2) `__. The backend-agnostic implementation allows Scenario Execution to be used with both, robotics simulators such as `Gazebo `__ and physical robots, with minimal adaptations necessary in the scenario description file.  To give an impression of the functionality of scenario execution, the following animation shows an example scenario with a turtlebot-like robot in simulation using Nav2 to navigate towards a specified navigation goal in a simulated warehouse environment. Once the robot -reaches a reference position and a box is spawned in front of the robot +reaches a reference position a box is spawned in front of the robot as an unmapped static obstacle that needs to be avoided. Upon arrival of -the goal position, the scenario is ends with success and the simulation +the goal position, the scenario ends and the simulation gets cleaned up. .. figure:: images/scenario.gif @@ -29,7 +29,7 @@ gets cleaned up. setup how_to_run tutorials - actions architecture - openscenario2_support + libraries development + openscenario2 \ No newline at end of file diff --git a/docs/libraries.rst b/docs/libraries.rst new file mode 100644 index 00000000..f188655a --- /dev/null +++ b/docs/libraries.rst @@ -0,0 +1,212 @@ +Libraries +========= + +Beside ``osc.standard`` provided by OpenSCENARIO 2, multiple libraries are provided with scenario execution. + +- ``osc.helpers`` Helpers Library +- ``osc.robotics``: Robotics Library +- ``osc.ros``: ROS Library +- ``osc.gazebo``: Gazebo Library + +Additional features can be implemented by defining your own library. + +``osc.helpers`` +--------------- + +Actions +^^^^^^^ + +``log()`` +""""""""" + +For debugging purposes, log a string using the available log mechanism. + +- ``msg: string``: String to log + +``run_external_process()`` +"""""""""""""""""""""""""" + +Run an external process. Reports `running` while the process has not finished. + +- ``command: string``: Command to execute + + +``osc.robotics`` +---------------- + +Actors +^^^^^^ + +``differential_drive_robot`` +"""""""""""""""""""""""""""" +A differential drive robot actor. + +``osc.ros`` +----------- + +Actions +^^^^^^^ + +``wait_for_data()`` +""""""""""""""""""" + +Wait for a specific data on a ROS topic. + +- ``topic_name: string``: Name of the topic to connect to +- ``topic_type: string``: Class of the message type (e.g. ``std_msgs.msg.String``) +- ``qos_profile: qos_preset_profiles``: QoS Preset Profile for the subscriber (default: ``qos_preset_profiles!system_default``) +- ``clearing_policy: clearing_policy``: When to clear the data (default: ``clearing_policy!on_initialise``) + + +``wait_for_topics()`` +""""""""""""""""""""" + +Wait for topics to get available (i.e. publisher gets available). + +- ``topics: string``: Whitespace-separated list of topics + + +``check_data()`` +"""""""""""""""" +Wait for a topic message, compare a message field against a specific value + +- ``topic_name: string``: Name of the topic to connect to +- ``topic_type: string``: Class of the message type (e.g. ``std_msgs.msg.String``) +- ``qos_profile: qos_preset_profiles``: QoS Preset Profile for the subscriber (default: ``qos_preset_profiles!system_default``) +- ``variable_name: string``: Name of the variable to check +- ``expected_value: string``: Expected value of the variable +- ``comparison_operator: comparison_operator``: The comparison operator to apply (default: ``comparison_operator!eq``) +- ``fail_if_no_data: bool``: py_trees.common.Status.FAILURE instead of py_trees.common.Status.RUNNING if there is no data yet (default: ``false``) +- ``fail_if_bad_comparison: bool``: py_trees.common.Status.FAILURE instead of py_trees.common.Status.RUNNING if comparison failed (default: ``true``) +- ``clearing_policy: clearing_policy``: When to clear the data (default: ``clearing_policy!on_initialise``) + +``service_call()`` +"""""""""""""""""" + +Call a ROS service and wait for the reply. + +- ``service_name: string``: Name of the service to connect to +- ``service_type: string``: Class of the message type (e.g. ``std_srvs.msg.Empty``) +- ``data: string``: Service call content + +``topic_publish()`` +""""""""""""""""""" + +Publish a message on a topic. + +- ``topic_name: string``: Name of the topic to publish to +- ``topic_type: string``: Class of the message type (e.g. ``std_msgs.msg.String``) +- ``qos_profile: qos_preset_profiles``: QoS Preset Profile for the subscriber (default: ``qos_preset_profiles!system_default``) +- ``value: string``: Value to publish + +``set_node_parameter()`` +"""""""""""""""""""""""" + +Set a parameter of a node. + +- ``node_name: string``: Name of the node +- ``parameter_name: string``: Name of the parameter +- ``parameter_value: string``: Value of the parameter + +``record_bag()`` +"""""""""""""""" + +Record a ROS bag. + +- ``destination_dir: string``: The destination for the ROS bag (if empty, the current directory is used) +- ``topics: string``: Whitespace-separated list of topics to capture +- ``timestamp_suffix: bool``: Add a timestamp suffix to output directory name (default: ``true``) +- ``hidden_topics: bool``: Whether to record hidden topics (default: ``false``) +- ``storage: string``: Storage type to use (empty string: use ROS bag record default) + +``log_check()`` +""""""""""""""" +Wait for specific output in ROS log (i.e. `/rosout` topic). + +- ``values: string``: string or list of strings (in python syntax, e.g. "[\'foo\', \'bar\']") + +``differential_drive_robot.init_nav2()`` +"""""""""""""""""""""""""""""""""""""""" + +Initialize nav2. + +- ``initial_pose: pose_3d``: The initial pose to set during initialization +- ``base_frame_id: string``: Base Frame ID (default: ``base_link``) +- ``use_initial_pose: bool``: If false, no initial_pose is needed (useful when using slam instead of amcl for localization) (default: ``true``) +- ``namespace_override: string``: If set, it's used as namespace (instead of the associated actor's namespace) +- ``wait_for_initial_pose: bool``: If true the initial pose needs to be set externally (e.g. manually through rviz)(default: ``false``) + +``differential_drive_robot.nav_to_pose()`` +"""""""""""""""""""""""""""""""""""""""""" +Use nav2 to navigate to goal pose. + +- ``goal_pose: pose_3d``: Goal pose to navigate to +- ``namespace_override: string``: If set, it's used as namespace (instead of the associated actor's namespace) +- ``action_topic: string``: Action name (default: ``navigate_to_pose``) +- ``monitor_progress: bool``: If yes, the action returns after the goal is reached or on failure. If no, the action returns after request. (default: ``true``) + +``differential_drive_robot.nav_through_poses()`` +"""""""""""""""""""""""""""""""""""""""""""""""" + +Use nav2 to navigate through poses. + +- ``goal_pose: string``: Goal poses to navigate to (format: ``x1,y1,yaw1;x2,y2,yaw2;...``) +- ``namespace_override: string``: If set, it's used as namespace (instead of the associated actor's namespace) +- ``monitor_progress: bool``: If yes, the action returns after the goal is reached or on failure. If no, the action returns after request. (default: ``true``) + +``differential_drive_robot.tf_close_to()`` +"""""""""""""""""""""""""""""""""""""""""" + +Wait until a TF frame is close to a defined reference point. + +- ``namespace_override: string``: if set, it's used as namespace (instead of the associated actor's namespace) +- ``reference_point: position_3d``: Reference point to measure to distance to (z is not considered) +- ``threshold: length``: Distance at which the action succeeds. +- ``sim: bool``: In simulation, we need to look up the transform map --> base_link at a different time as the scenario execution node is not allowed to use the sim time (default: ``false``) +- ``robot_frame_id: string``: Defines the TF frame id of the robot (default: ``base_link``) + +``differential_drive_robot.odometry_distance_traveled()`` +""""""""""""""""""""""""""""""""""""""""""""""""""""""""" + +Wait until a defined distance was traveled, based on odometry. + +- ``namespace: string``: Namespace of the odometry topic +- ``distance: length``: Traveled distance at which the action succeeds. + + +``osc.gazebo`` +-------------- + +Actions +^^^^^^^ + + +``wait_for_sim()`` +"""""""""""""""""" +Wait for simulation to become active (checks for simulation clock). + +- ``world_name: string``: Gazebo world name (default: ``default``) + +``actor_exists()`` +"""""""""""""""""" + +Waits for an actor to exist within simulation. + +- ``entity_name``: Entity name within simulation +- ``world_name: string``: Gazebo world name (default: ``default``) + +``osc_object.spawn()`` +"""""""""""""""""""""" + +Spawn an actor within simulation by using the ``model`` and ``namespace`` of the associated actor. + +- ``spawn_pose: pose_3d``: Pose of the spawned actor. +- ``world_name: string``: Gazebo world name (default: ``default``) +- ``xacro_arguments: string``: Comma-separated list of argument key:=value pairs + +``osc_object.delete()`` +""""""""""""""""""""""" + +Delete an object from the simulation. + +- ``world_name: string``: Gazebo world name (default: ``default``) diff --git a/docs/openscenario2.rst b/docs/openscenario2.rst new file mode 100644 index 00000000..83c3ce89 --- /dev/null +++ b/docs/openscenario2.rst @@ -0,0 +1,99 @@ +OpenSCENARIO 2 +============== + +General +------- + +This tool supports a subset of the `OpenSCENARIO +2 `__ standard. + +The official documentation is available +`here `__. + +The `standard library of +OSC2 `__ +was adapted to be usable by the current parsing support of scenario execution. + +In the following the supported features are described. + +.. role:: raw-html(raw) + :format: html + +Supported features +------------------ + +In the following the OpenSCENARIO 2 keywords are listed with their current support status. + + +======================= ==================== ============================= +Element Tag Support Notes +======================= ==================== ============================= +``action`` :raw-html:`✅` partially, see details below +``actor`` :raw-html:`✅` partially, see details below +``as`` :raw-html:`❌` +``bool`` :raw-html:`✅` +``call`` :raw-html:`❌` +``cover`` :raw-html:`❌` +``def`` :raw-html:`❌` +``default`` :raw-html:`❌` +``do`` :raw-html:`✅` +``elapsed`` :raw-html:`✅` +``emit`` :raw-html:`✅` +``enum`` :raw-html:`✅` +``event`` :raw-html:`✅` +``every`` :raw-html:`❌` +``expression`` :raw-html:`❌` +``extend`` :raw-html:`❌` +``external`` :raw-html:`❌` +``fall`` :raw-html:`❌` +``float`` :raw-html:`✅` +``global`` :raw-html:`✅` +``hard`` :raw-html:`❌` +``if`` :raw-html:`❌` +``import`` :raw-html:`✅` +``inherits`` :raw-html:`✅` +``int`` :raw-html:`✅` +``is`` :raw-html:`❌` +``it`` :raw-html:`✅` +``keep`` :raw-html:`✅` +``list`` :raw-html:`✅` +``of`` :raw-html:`✅` +``on`` :raw-html:`❌` +``one_of`` :raw-html:`✅` +``only`` :raw-html:`❌` +``parallel`` :raw-html:`✅` +``range`` :raw-html:`❌` +``record`` :raw-html:`❌` +``remove_default`` :raw-html:`❌` +``rise`` :raw-html:`❌` +``scenario`` :raw-html:`✅` +``serial`` :raw-html:`✅` +``SI`` :raw-html:`✅` +``string`` :raw-html:`✅` +``struct`` :raw-html:`✅` +``type`` :raw-html:`✅` +``uint`` :raw-html:`✅` +``undefined`` :raw-html:`❌` +``unit`` :raw-html:`✅` +``until`` :raw-html:`❌` +``var`` :raw-html:`✅` +``wait`` :raw-html:`✅` +``with`` :raw-html:`✅` +======================= ==================== ============================= + + +Composition Types +^^^^^^^^^^^^^^^^^ + +Composition types are ``struct``, ``actor``, ``action``, ``scenario``. + +============== ==================== ========= +Element Type Support Notes +============== ==================== ========= +Event :raw-html:`✅` +Field :raw-html:`✅` +Constraint :raw-html:`✅` partially +Method :raw-html:`❌` +Coverage :raw-html:`❌` +Modifier :raw-html:`❌` +============== ==================== ========= diff --git a/docs/openscenario2_support.rst b/docs/openscenario2_support.rst deleted file mode 100644 index 15aeb7e1..00000000 --- a/docs/openscenario2_support.rst +++ /dev/null @@ -1,309 +0,0 @@ -OpenSCENARIO2 Support ---------------------- - -This tool supports a subset of the `OpenSCENARIO -2 `__ PRC -standard. In the following the supported features are described. - -In addition, it is recommended to take a look into the official -documentation available -`here `__. - -The `standard library of -OSC2 `__ -was slightly adapted as py-osc2 is not yet support multiline enum -definitions. - -Level of support -~~~~~~~~~~~~~~~~ - -In the following the OpenSCENARIO2 standard library elements are listed -with their current support status. - -Scalar types and units -^^^^^^^^^^^^^^^^^^^^^^ - -.. raw:: html - - - -.. raw:: html - - - -========================================= ======= ===== -Element Tag Support Notes -========================================= ======= ===== -``library-physical-length`` ✅ -``library-physical-time`` ✅ -``library-physical-acceleration`` ✅ -``library-physical-jerk`` ✅ -``library-physical-angle`` ✅ -``library-physical-speed`` ✅ -``library-physical-angular_rate`` ✅ -``library-physical-angular_acceleration`` ✅ -``library-physical-mass`` ✅ -``library-physical-temperature`` ✅ -``library-physical-pressure`` ✅ -``library-physical-luminous_intensity`` ✅ -``library-physical-luminous_flux`` ✅ -``library-physical-illuminance`` ✅ -``library-physical-electrical_current`` ✅ -``library-physical-amount_of_substance`` ✅ -========================================= ======= ===== - -Structs -^^^^^^^ - -========================================= ======= ======== -Element Tag Support Notes -========================================= ======= ======== -``library-position_3d`` ✅ -``library-celestial_position_2d`` ✅ -``library-geodetic_position_2d`` ✅ -``library-orientation_3d`` ✅ -``library-pose_3d`` ✅ -``library-translational_velocity_3d`` ✅ -``library-orientation_rate_3d`` ✅ -``library-velocity_6d`` ✅ -``library-translational_acceleration_3d`` ✅ -``library-orientation_acceleration_3d`` ✅ -``library-acceleration_6d`` ✅ -``axle`` ✅ -``bounding_box`` ✅ -``crossing_type`` ✅ -``route_point`` ✅ -``xyz_point`` ✅ -``odr_point`` ✅ -``library-path`` ✅ modified -``relative_path`` ✅ -``relative_path_pose_3d`` ✅ -``relative_path_st`` ✅ -``relative_path_odr`` ✅ -``trajectory`` ✅ -``relative_trajectory`` ✅ -``relative_trajectory_pose_3d`` ✅ -``relative_trajectory_st`` ✅ -``relative_trajectory_odr`` ✅ -``any_shape`` ✅ -``any_acceleration_shape`` ✅ -``any_speed_shape`` ✅ -``any_position_shape`` ✅ -``any_lateral_shape`` ✅ -``common_acceleration_shape`` ✅ -``common_speed_shape`` ✅ -``common_position_shape`` ✅ -``common_lateral_shape`` ✅ -``behavioral_model`` ✅ -``bm_engine`` ✅ -========================================= ======= ======== - -Enums -^^^^^ - -=========================== ======= ======== -Element Tag Support Notes -=========================== ======= ======== -``color`` ✅ -``intended_infrastructure`` ✅ -``vehicle_category`` ✅ -``driving_rule`` ✅ -``directionality`` ✅ -``lane_type`` ✅ -``lane_use`` ✅ -``side_left_right`` ✅ -``crossing_marking`` ✅ modified -``crossing_use`` ✅ -``crossing_elevation`` ✅ -``junction_direction`` ✅ -``route_overlap_kind`` ✅ -``lateral_overlap_kind`` ✅ -``dynamic_profile`` ✅ -``lane_change_side`` ✅ -``gap_direction`` ✅ -``headway_direction`` ✅ -``lat_measure_by`` ✅ -``yaw_measure_by`` ✅ -``orientation_measured_by`` ✅ -``movement_options`` ✅ -``connect_route_points`` ✅ modified -``path_interpolation`` ✅ -``at`` ✅ -``movement_mode`` ✅ -``track`` ✅ -``distance_direction`` ✅ -``distance_mode`` ✅ -``relative_transform`` ✅ -``on_route_type`` ✅ -``route_distance_enum`` ✅ -=========================== ======= ======== - -Actor -^^^^^ - -======================= ======= ======== -Element Tag Support Notes -======================= ======= ======== -``osc_actor`` ✅ -``physical_object`` ✅ modified -``stationary_object`` ✅ -``movable_object`` ✅ modified -``traffic_participant`` ✅ -``vehicle`` ✅ -``person`` ✅ -``animal`` ✅ -======================= ======= ======== - -Environment (An Actor) -^^^^^^^^^^^^^^^^^^^^^^ - -========================== ======= ======== -Element Tag Support Notes -========================== ======= ======== -``environment`` ✅ modified -``weather`` ✅ -``air`` ✅ -``precipitation`` ✅ -``wind`` ✅ -``fog`` ✅ -``clouds`` ✅ -``celestial_light_source`` ✅ -========================== ======= ======== - -Map (An Actor) -^^^^^^^^^^^^^^ - -================== ======= ===== -Element Tag Support Notes -================== ======= ===== -``map`` ✅ -``route`` ✅ -``route_element`` ✅ -``road`` ✅ -``lane_section`` ✅ -``lane`` ✅ -``crossing`` ✅ -``junction`` ✅ -``compound_route`` ✅ -``compound_lane`` ✅ -================== ======= ===== - -Action - movable object -^^^^^^^^^^^^^^^^^^^^^^^ - -============================================ ======= ===== -Element Tag Support Notes -============================================ ======= ===== -``osc_actor.osc_action`` ✅ -``movable_object.action_for_movable_object`` ✅ -``movable_object.move`` ✅ -``movable_object.remain_stationary`` ✅ -``movable_object.assign_position`` ✅ -``movable_object.assign_orientation`` ✅ -``movable_object.assign_speed`` ✅ -``movable_object.assign_acceleration`` ✅ -``movable_object.replay_path`` ✅ -``movable_object.replay_trajectory`` ✅ -``movable_object.change_position`` ✅ -``movable_object.change_speed`` ✅ -``movable_object.keep_speed`` ✅ -``movable_object.change_acceleration`` ✅ -``movable_object.keep_acceleration`` ✅ -``movable_object.follow_path`` ✅ -``movable_object.follow_trajectory`` ✅ -============================================ ======= ===== - -Action - vehicle -^^^^^^^^^^^^^^^^ - -=============================== ======= ===== -Element Tag Support Notes -=============================== ======= ===== -``vehicle.action_for_vehicle`` ✅ -``vehicle.drive`` ✅ -``vehicle.follow_lane`` ✅ -``vehicle.change_lane`` ✅ -``vehicle.change_space_gap`` ✅ -``vehicle.keep_space_gap`` ✅ -``vehicle.change_time_headway`` ✅ -``vehicle.keep_time_headway`` ✅ -=============================== ======= ===== - -Action - person -^^^^^^^^^^^^^^^ - -============================ ======= ===== -Element Tag Support Notes -============================ ======= ===== -``person.action_for_person`` ✅ -``person.walk`` ✅ -============================ ======= ===== - -Action - environment -^^^^^^^^^^^^^^^^^^^^ - -========================================= ======= ===== -Element Tag Support Notes -========================================= ======= ===== -``environment.action_for_environment`` ✅ -``environment.air`` ✅ -``environment.rain`` ✅ -``environment.snow`` ✅ -``environment.wind`` ✅ -``environment.fog`` ✅ -``environment.cloud`` ✅ -``environment.assign_celestial_position`` ✅ -========================================= ======= ===== - -Modifier - location based modifiers -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -============================== ======= ===== -Element Tag Support Notes -============================== ======= ===== -``position`` ❌ -``distance`` ❌ -``lane`` ❌ -``keep_lane`` ❌ -``lateral`` ❌ -``yaw`` ❌ -``orientation`` ❌ -``along`` ❌ -``keep_position`` ❌ -``along_trajectory`` ❌ -``stationary_object.location`` ❌ -============================== ======= ===== - -Modifier - rate of change based modifiers -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -===================== ======= ===== -Element Tag Support Notes -===================== ======= ===== -``speed`` ❌ -``acceleration`` ❌ -``keep_speed`` ❌ -``change_speed`` ❌ -``physical_movement`` ❌ -``avoid_collisions`` ❌ -``change_lane`` ❌ -===================== ======= ===== - -Modifier - map based modifiers -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -================================ ======= ===== -Element Tag Support Notes -================================ ======= ===== -``map.number_of_lanes`` ❌ -``map.routes_are_in_sequence`` ❌ -``map.roads_follow_in_junction`` ❌ -``map.routes_overlap`` ❌ -``map.lane_side`` ❌ -``map.compound_lane_side`` ❌ -``map.end_lane`` ❌ -``map.start_lane`` ❌ -``map.crossing_connects`` ❌ -``map.routes_are_opposite`` ❌ -``map.set_map_file`` ❌ -================================ ======= ===== diff --git a/docs/tutorials.rst b/docs/tutorials.rst index 61fe09f3..e6e6567b 100644 --- a/docs/tutorials.rst +++ b/docs/tutorials.rst @@ -1,349 +1,220 @@ Tutorials ========= -Table of contents ------------------ - -- `Create a scenario in - OpenScenario2 <#create-scenario-in-openscenario-v200>`__ -- `Create a custom action plugin <#create-action-plugin>`__ -- `Create a scenario with a simulated Turtlebot4 and - Nav2 <#create-a-scenario-with-a-simulated-turtlebot4-and-nav2>`__ -- `Create a scenario with a simulated Turtlebot4 and Nav2 and spawning - a static unmapped - obstacle <#create-a-scenario-with-a-simulated-turtlebot4-and-nav2-and-spawning-a-static-unmapped-obstacle>`__ - -Create Scenario in OpenSCENARIO V2.0.0 --------------------------------------- - -To create a scenario in OpenSCENARIO V2.0.0 syntax, first create a file +Code for all tutorials is available in :repo_link:`examples`. + +Define and Execute Scenario +--------------------------- + +To create a scenario in OpenSCENARIO 2 syntax, first create a file with the extension ``.osc``. Input the following code in the file. -:: +.. code-block:: # import the libraries with import expression - import osc.builtin - - # Comments start with "#" - # This is a comment. + import osc.standard + import osc.helpers # declare the scenario by the syntax: "scenario scenario_name:" - scenario create_scenario_tutorial: + scenario example_ros_topic: # define the content of the scenario with "do_directive" - do serial: - # log a message on the screen with "log" action from the built-in library - log() with: - # constrain the logged msg to "Hello World!" - keep(it.msg == "Hello World") - # emit the "end" event to signalize the end of the scenario - emit end - -The first line ``import osc.builtin`` will import the integrated library -``builtin.osc`` from the package “scenario_execution_base”. All the -OpenSCENARIO 2 types defined in the file will be imported into the -parser. - -The comments in OpenSCENARIO 2 always start with hashtag “#”. - -Then, declare a scenario without an associated actor. The term -“scenario” declares that this is a scenario and -“create_scenario_tutorial” is the name of the scenario followed by a -colon. The content of the scenario is defined in the “do_directive”. The -term ``do`` declares that this is a “do_directive”. The term ``serial`` -states that the following layer will be executed in sequence. Use the -``log`` action defined in the built-in library to log a message on the -screen. The term ``with`` declares that there are behavior invocation -members that modify the behavior. In the behavior invocation members, a -“keep constraint” is given to constrain the action ``log``. In side the -“keep constraint”, the ``it`` term references to the current namespace. -In this case, it’s the ``log`` action. With ``.`` symbol, you can access -the members of the ``log`` action. The ``it.msg`` references to the -parameter ``msg`` of the action ``log``. The relational operator ``==`` -signalizes that the message should be equal to the string -``"Hello World!"``. After the ``log`` action is invoked, the scenario -should emit an ``end`` event to tell the scenario execution to shut down -and return success on scenario “create_scenario_tutorial”. On the other -hand, if you want to define a condition where the scenario fails, use -``emit fail`` to shut down the scenario execution and return failure. + do serial: # execute children one after the other + log("Hello World!") # log a message on the screen with "log" action from the built-in library + wait elapsed(3s) # wait three seconds + log("Good Bye!") # log another message + +The first two lines ``import osc.standard`` and ``import osc.helpers`` will import the named libraries that provide required definitions. In this example ``helpers`` library provides the ``log`` action and ``standard`` provides the definition of the `s` unit to specify seconds. + +.. note:: + Comments in OpenSCENARIO 2 always start with ``#``. + +Then, a scenario with the name ``hello_world`` get declared. The following colon states that all following and indented lines +are part of it. The single top-level action of the scenario is defined in the ``do`` directive. +The term ``serial`` states that the included actions will be executed in sequence. + +.. note:: + OpenSCENARIO 2 supports the following compositions: + + * ``parallel``: execute actions in parallel, continue afterwards + * ``serial``: execute actions, one after the other + * ``one_of``: execute actions in parallel, continue after one finished + +Use the ``log`` action, defined within the imported library, to log a message ``Hello World!`` on the +screen. After the ``log`` action is invoked, the ``wait`` directive makes the scenario execution to wait for 3 seconds. Afterwards another ``log`` action is triggered and the scenario ends afterwards. + +.. note:: + Scenario execution uses the predefined events ``end`` and ``fail`` to detect success or failure of a scenario. If no ``emit end`` or ``emit fail`` is defined, a success is assumed. + +.. note:: + It is good practice to define a timeout action in parallel to the expected actions within a scenario. + + .. code-block:: + + scenario example: + do parallel: + serial: + ... + serial: + wait elapsed(60s) + emit fail Use this code to see a launch of this tutorial: .. code-block:: bash - colcon build --packages-up-to scenario_execution_tutorials && source install/setup.bash \ - && ros2 launch scenario_execution_tutorials scenario_execution_create_scenario_tutorial_launch.py + colcon build --packages-up-to scenario_execution && source install/setup.bash \ + && ros2 launch scenario_execution scenario_launch.py scenario:=examples/example_scenario/hello_world.osc -Create Action Plugin --------------------- +.. _scenario_library: -To show how to create a action plugin for the scenario execution, we -will use the ``log`` action as an example. +Create Scenario Library +----------------------- -First, we need to define the ``tutorial_log`` action in OpenSCENARIO 2. +To add new features to scenario execution, extensions libraries can be created. An extension library typically provides one or more +OpenSCENARIO 2 definition files and might additionally provide action implementations. -:: +To show how to create such a library for scenario execution, we will add a ``custom_action`` action as an example. - action tutorial_log: - plugin: string = "TutorialLog" - msg: string +First, we need to define the ``custom_action`` in a OpenSCENARIO 2 file. -The ``plugin`` parameter shows what is the name of the entry point of -the plugin. The ``msg`` parameter is the message we want to log to the -screen. +.. code-block:: -Then, we can write our code for action plugin in Python. + action custom_action: + data: string -:: +The ``data`` parameter is used to pass the data of type string to the action plugin implementation. + +Then, we can write the implementation of action plugin in Python. + +.. code-block:: import py_trees - from scenario_execution_base.osc2_utils.osc2_type import ActionPlugin - # Step 1: define the py_trees behavior - class LogAction(py_trees.behaviour.Behaviour): + # define the py_trees behavior + class CustomAction(py_trees.behaviour.Behaviour): # Override the __init__ function to accept parsed arguments. - def __init__(self, msg: str): - super().__init__("Log") - self.msg = msg + def __init__(self, name, data: str): + super().__init__(name) + self.data = data # Override the update function to define how the behavior is ticking. def update(self): - print(self.msg) + print(f"Custom Action Triggered. Data: {self.data}") return py_trees.common.Status.SUCCESS - # Step 2: create the action plugin by inherit from the class "ActionPlugin" - class Log(ActionPlugin): - # Override the init function to give the action plugin a name - def __init__(self, action_handle) -> None: - super().__init__('Log', action_handle) - - # override the create_behavior function to return the behavior we just declared. - def create_behavior(self) -> py_trees.behaviour.Behaviour: - return LogAction - - # override the parse function to parse the parameter from the osc2 action - def parse(self): - """ - Parse the parameters from the action - """ - self.kwargs['msg'] = self.action_handle.parameters['msg'].value - -In the example, we created an action plugin to print a message on the -screen. The first step is to create a py_trees behavior for the action + +In the example, we created a custom action plugin to print a message on the +screen. The first step is to create a ``py_trees`` behavior for the action plugin. First, override the ``__init__()`` function to accept the parsed -parameter from the action plugin. The action plugin ``Log`` only parses -one parameter ``msg``, so the behavior only has to accept ``msg`` as an +parameter from the action plugin. Beside the fixed parameter ``name`` all parameters defined within the OpenSCENARIO 2 file +are handed over to `__init__`. +The action plugin ``custom_action`` only defines one parameter ``data``, so the behavior only has to accept ``data`` as an argument. Then, override the ``update()`` function to define how the -behavior works. In this case, the behavior print the message on the screen -and then return success. - -The second step is to create the action plugin. All action plugins need -to inherit from the class ``ActionPlugin`` from -“scenario_execution_base” package. Then, override the -``create_behavior()`` function to return the py_trees behavior we want -to use in our behavior tree. In this case, we return the ``LogAction`` -behavior we just created. Remember to only return the class of the -py_trees behavior, not the instance of the class, because the class -needs to instantiated later when all arguments are parsed. Then, we -override the ``parse()`` function. We define the arguments in the -``self.kwargs`` dictionary, which will be passed to the py_trees -behavior in the ``create_behavior()`` function. In the action plugin, we -have a handle on the ``Action`` object from the parser. We can access -the message parameter through -``self.action_handle.parameters['msg'].value``. - -After we wrote the action plugin, we need to add it to the -“scenario_execution.action_plugins” entry points, so that the parser can +behavior works. In this case, the behavior prints the message on the screen +and then returns success. Please refer to the ``py_trees`` `documentation `_ for details. + +After we wrote the library, we need to add it to the +``scenario_execution.actions`` and ``scenario_execution.osc_libraries`` entry points, so that the parser can find it. -Open up the setup file for your Python package and add this line to the -entry points. +Open up the setup file for your Python package ``setup.py`` and add these lines to the +entry_points section. -:: +.. code-block:: - 'scenario_execution.action_plugins': [ - 'TutorialLog = scenario_execution_tutorial.tutorial_log:Log', + entry_points={ + 'scenario_execution.actions': [ + 'custom_action = example_library.custom_action:CustomAction', ], + 'scenario_execution.osc_libraries': [ + 'example = example_library.get_osc_library:get_example_library', + ] + } -The setup file should look like this afterwards: +To ship the osc library, a ``MANIFEST.in`` must be created and ``include_package_data=True`` must be enabled within ``setup.py``. -:: +Now, you can use the library and the action ``custom_action`` within your scenarios: - from setuptools import setup - - package_name = 'scenario_execution_tutorials' - - setup( - name=package_name, - version='0.0.0', - packages=[package_name], - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='todo', - maintainer_email='todo@todo.com', - description='TODO: Package description', - license='TODO: License declaration', - tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - ], - 'scenario_execution.action_plugins': [ - 'TutorialLog = scenario_execution_tutorials.tutorial_log:Log', - ], - }, - ) - -Now, you can use your action plugin ``tutorial_log`` in your scenarios: - -:: +.. code-block:: - action tutorial_log: - plugin: string = "TutorialLog" - msg: string + import osc.example - scenario create_action_plugin_tutorial: - do serial: - tutorial_log() with: - keep(it.msg == 'Action Plugin Tutorial') - emit end + scenario example_library: + do serial: + custom_action(data: 'foo') + emit end Use this code to see a launch of this tutorial: .. code-block:: bash - colcon build --packages-up-to scenario_execution_tutorials && source install/setup.bash \ - && ros2 launch scenario_execution_tutorials scenario_execution_create_action_plugin_tutorial_launch.py + colcon build --packages-up-to example_library && source install/setup.bash \ + && ros2 launch scenario_execution scenario_launch.py scenario:=examples/example_library/scenarios/example_library.osc -Create a scenario with a simulated Turtlebot4 and Nav2 ------------------------------------------------------- +Create Navigation Scenario +-------------------------- A simple example scenario for spawning a simulated Turtlebot4 in Gazebo -and control it with Nav2, can be found in :repo_link:`sscenario_execution_tutorials/scenarios/nav2_simulation_nav_to_pose_tutorial.osc`. +and control it with Nav2, can be found in :repo_link:`examples/example_nav2/example_nav2.osc`. This scenario files looks as follows: :: - import osc.ros # imports - import osc.gazebo - - scenario nav2_simulation_nav_to_pose: # scenario name - turtlebot4: differential_drive_robot with: # define turtlebot4 robot - keep(it.namespace == '') - keep(it.model == 'topic:///robot_description') - do parallel: - test_drive: serial: - wait_for_sim() with: # wait for the simulation to start - keep(it.world_name == 'maze') - turtlebot4.spawn() with: # spawn the robot - keep(it.spawn_pose.position.x == 0.0m) - keep(it.spawn_pose.position.y == 0.0m) - keep(it.spawn_pose.position.z == 0.1m) - keep(it.spawn_pose.orientation.yaw == 0.0rad) - keep(it.world_name == 'maze') - turtlebot4.init_nav2() with: # initialize Nav2 - keep(it.initial_pose.position.x == 0.0m) - keep(it.initial_pose.position.y == 0.0m) - keep(it.initial_pose.orientation.yaw == 0.0rad) - turtlebot4.nav_to_pose() with: # navigate to the first goal pose - keep(it.goal_pose.position.x == 3.0m) - keep(it.goal_pose.position.y == -3.0m) - turtlebot4.nav_to_pose() with: # navigate back to spawning position - keep(it.goal_pose.position.x == 0.0m) - keep(it.goal_pose.position.y == 0.0m) - emit end # end the scenario with success - time_out: serial: # timeout to stop scenario after 4 minutes and mark it as failed in case something goes wrong - wait elapsed(240s) - emit fail + import osc.ros + + scenario nav2_simulation_nav_to_pose: + turtlebot4: differential_drive_robot + do parallel: + test_drive: serial: + turtlebot4.init_nav2(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 3.0m, y: -3.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + emit end + time_out: serial: + wait elapsed(120s) + emit fail Let’s break down the individual components of the scenario. The -following snippet defines the turtlebot4 amr-object and where the -object’s description comes from (in this case, the robot_description -ROS2 topic). +following snippet defines the turtlebot4 amr-object. -:: +.. code-block:: - turtlebot4: differential_drive_robot with: # define turtlebot4 robot - keep(it.namespace == '') - keep(it.model == 'topic:///robot_description') + turtlebot4: differential_drive_robot: # define turtlebot4 robot The ``do parallel`` runs the actual test drive and a time-out in parallel. In case something goes wrong, the time-out prevents the -scenario from running indefinitely by canceling it after 4 minutes and +scenario from running indefinitely by canceling it after 2 minutes and marking it as failed. -The following snippet make the scenario execution module wait until the -simulation is up and running. Note, that we need to give the name of the -simulation (here, Ignition) as well as the name of the simulation world -(here, maze) to this action. - -:: - - wait_for_sim() with: # wait for the simulation to start - keep(it.world_name == 'maze') - -The following snippet spawns the robot at the origin of the world/map - -:: - - turtlebot4.spawn() with: # spawn the robot - keep(it.spawn_pose.position.x == 0.0m) - keep(it.spawn_pose.position.y == 0.0m) - keep(it.spawn_pose.position.z == 0.1m) - keep(it.spawn_pose.orientation.yaw == 0.0rad) - keep(it.world_name == 'maze') Before being able to navigate, nav2 needs to be initialized. This includes setting the initial pose of the Nav2 localization module `AMCL `__. -:: - - turtlebot4.init_nav2() with: # initialize Nav2 - keep(it.initial_pose.position.x == 0.0m) - keep(it.initial_pose.position.y == 0.0m) - keep(it.initial_pose.orientation.yaw == 0.0rad) +.. code-block:: -In case you want to localize your robot with -`SLAM `__ instead of -AMCL, there is no initial pose needed, i.e., you need to change the -``init_nav2`` action to - -:: - - turtlebot4.init_nav2() with: # initialize Nav2 - keep(it.initial_pose.position.x == 0.0m) - keep(it.initial_pose.position.y == 0.0m) - keep(it.initial_pose.orientation.yaw == 0.0rad) - keep(it.use_initial_pose == false) # the initial pose is not needed if we are using slam + turtlebot4.init_nav2(pose_3d(position_3d(x: 0.0m, y: 0.0m))) # initialize Nav2 Finally, the following snippet calls the Nav2 `NavigateToPose action `__ to make the robot navigate to a specified goal pose and back to the starting position -:: +.. code-block:: - turtlebot4.nav_to_pose() with: # navigate to the first goal pose - keep(it.goal_pose.position.x == 3.0m) - keep(it.goal_pose.position.y == -3.0m) - turtlebot4.nav_to_pose() with: # navigate back to spawning position - keep(it.goal_pose.position.x == 0.0m) - keep(it.goal_pose.position.y == 0.0m) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 3.0m, y: -3.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m))) Once the robot reached the final goal pose ``emit end`` finishes the scenario and marks it as successful. To try this example, run -:: +.. code-block:: bash - ros2 launch scenario_execution_tutorials turtlebot4_simulation_nav2_to_pose_tutorial_launch.py headless:=False + ros2 launch tb4_sim_scenario sim_nav_scenario_launch.py scenario:=examples/example_nav2/example_nav2.osc headless:=False and you should see something like this @@ -355,9 +226,9 @@ and you should see something like this In case you want to run the navigation with SLAM instead of AMCL, update the scenario file as described above and then run -:: +.. code-block:: bash - ros2 launch scenario_execution_tutorials turtlebot4_simulation_nav2_to_pose_tutorial_launch.py headless:=False slam:=True + ros2 launch tb4_sim_scenario sim_nav_scenario_launch.py scenario:=examples/example_nav2/example_nav2.osc headless:=False slam:=True and you should see something like this @@ -366,13 +237,13 @@ and you should see something like this Turtlebot4 NAV2 scenario SLAM -Create a scenario with a simulated Turtlebot4 and Nav2 and spawning a static unmapped obstacle ----------------------------------------------------------------------------------------------- +Create Navigation Scenario with Obstacle +---------------------------------------- -In this section, we’ll extend the previous example and use the :repo_link:`scenario_execution/action_plugins/tf_close_to.py`. +In this section, we’ll extend the previous example and use the :repo_link:`scenario_execution/actions/tf_close_to.py`. to spawn a static obstacle in front of the robot once it reaches a user-specified reference point. The corresponding scenario can be found -in :repo_link:`scenario_execution_tutorials/scenarios/nav2_simulation_nav_to_pose_object_spawn_tutorial.osc + + + 0 0 0.5 0 0 0 + true + + + 0.5 + + + 0.083 + 0.0 + 0.0 + 0.083 + 0.0 + 0.083 + + + + + + 0.25 0.25 0.25 + + + + + + + 0.25 0.25 0.25 + + + + + + \ No newline at end of file diff --git a/examples/example_simulation/package.xml b/examples/example_simulation/package.xml new file mode 100644 index 00000000..3e032f01 --- /dev/null +++ b/examples/example_simulation/package.xml @@ -0,0 +1,25 @@ + + + + example_simulation + 1.0.0 + Scenario Execution Example for Simulation + Intel Labs + Intel Labs + Apache-2.0 + + scenario_execution + scenario_execution_gazebo + tb4_sim_scenario + + rclpy + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/examples/example_simulation/resource/example_simulation b/examples/example_simulation/resource/example_simulation new file mode 100644 index 00000000..e69de29b diff --git a/examples/example_simulation/scenarios/example_simulation.osc b/examples/example_simulation/scenarios/example_simulation.osc new file mode 100644 index 00000000..0560f7e6 --- /dev/null +++ b/examples/example_simulation/scenarios/example_simulation.osc @@ -0,0 +1,28 @@ +import osc.ros +import osc.gazebo + +scenario nav2_simulation_nav_to_pose: + turtlebot4: differential_drive_robot + box: osc_object + do parallel: + test_drive: serial: + turtlebot4.init_nav2(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + parallel: + serial: + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 3.0m, y: -3.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + serial: + turtlebot4.tf_close_to( + reference_point: position_3d(x: 1.5m, y: -1.5m), + threshold: 0.4m, + robot_frame_id: 'turtlebot4_base_link_gt') + box.spawn( + spawn_pose: pose_3d( + position: position_3d(x: 2.0m, y: -2.0m, z: 0.1m), + orientation: orientation_3d(yaw: 0.0rad)), + model: 'example_simulation://models/box.sdf', + world_name: 'maze') + emit end + time_out: serial: + wait elapsed(120s) + emit fail diff --git a/examples/example_simulation/setup.py b/examples/example_simulation/setup.py new file mode 100644 index 00000000..246fa421 --- /dev/null +++ b/examples/example_simulation/setup.py @@ -0,0 +1,43 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from glob import glob +import os +from setuptools import setup + +PACKAGE_NAME = 'example_simulation' + +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=[PACKAGE_NAME], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'scenarios'), glob('scenarios/*.osc')), + (os.path.join('share', PACKAGE_NAME, 'models'), glob('models/*.sdf')), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Scenario Execution Example for Simulation', + license='Apache License 2.0', + tests_require=['pytest'], + entry_points={ + }, +) diff --git a/requirements.txt b/requirements.txt index 8d98e164..b8ad65fa 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,4 @@ antlr4-python3-runtime==4.7.2 transforms3d==0.3.1 pexpect==4.9.0 -kubernetes==29.0.0 defusedxml==0.7.1 diff --git a/scenario_coverage/README.md b/scenario_coverage/README.md new file mode 100644 index 00000000..1bb44f5e --- /dev/null +++ b/scenario_coverage/README.md @@ -0,0 +1,6 @@ +# Scenario Coverage + +The `scenario_coverage` packages provides two tools: + +- `scenario_variation`: Create concrete scenarios out of scenario with variation definition +- `scenario_batch_execution`: Execute multiple scenarios, one after the other. \ No newline at end of file diff --git a/scenario_coverage/package.xml b/scenario_coverage/package.xml new file mode 100644 index 00000000..07454065 --- /dev/null +++ b/scenario_coverage/package.xml @@ -0,0 +1,21 @@ + + + + scenario_coverage + 1.0.0 + Robotics Scenario Execution Coverage Tools + Intel Labs + Intel Labs + Apache-2.0 + + scenario_execution_base + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/scenario_coverage/resource/scenario_coverage b/scenario_coverage/resource/scenario_coverage new file mode 100644 index 00000000..e69de29b diff --git a/scenario_coverage/scenario_coverage/__init__.py b/scenario_coverage/scenario_coverage/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_coverage/scenario_coverage/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_coverage/scenario_coverage/scenario_batch_execution.py b/scenario_coverage/scenario_coverage/scenario_batch_execution.py new file mode 100644 index 00000000..d687be80 --- /dev/null +++ b/scenario_coverage/scenario_coverage/scenario_batch_execution.py @@ -0,0 +1,148 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import sys +import argparse +import subprocess # nosec B404 +from threading import Thread +from collections import deque +from copy import deepcopy +import signal + + +class ScenarioBatchExecution(object): + + def __init__(self, args) -> None: + if not os.path.isdir(args.output_dir): + os.mkdir(args.output_dir) + self.output_dir = args.output_dir + + dir_content = os.listdir(args.scenario_dir) + self.scenarios = [] + for entry in dir_content: + if entry.endswith(".sce") or entry.endswith(".osc"): + self.scenarios.append(os.path.join(args.scenario_dir, entry)) + if not self.scenarios: + raise ValueError(f"Directory {args.scenario_dir} does not contain any scenarios.") + print(f"Detected {len(self.scenarios)} scenarios.") + self.launch_command = args.launch_command + if self.get_launch_command("", "") is None: + raise ValueError("Launch command does not contain {SCENARIO} and {JUNITXML}: " + " ".join(args.launch_command)) + print(f"Launch command: {self.launch_command}") + + def get_launch_command(self, scenario_name, junitxml): + launch_command = deepcopy(self.launch_command) + scenario_replaced = False + junitxml_replaced = False + for i in range(0, len(launch_command)): # pylint: disable=consider-using-enumerate + if "{SCENARIO}" in launch_command[i]: + launch_command[i] = launch_command[i].replace('{SCENARIO}', scenario_name) + scenario_replaced = True + if "{JUNITXML}" in launch_command[i]: + launch_command[i] = launch_command[i].replace('{JUNITXML}', junitxml) + junitxml_replaced = True + if scenario_replaced and junitxml_replaced: + return launch_command + else: + return None + + def run(self) -> bool: + + def log_output(out, buffer): + try: + for line in iter(out.readline, b''): + msg = line.decode().strip() + print(msg) + buffer.append(msg) + out.close() + except ValueError: + pass + + for scenario in self.scenarios: + output_file_path = os.path.join(self.output_dir, os.path.splitext(os.path.basename(scenario))[0]) + + launch_command = self.get_launch_command(scenario, output_file_path + '_result.xml') + output = deque() + log_cmd = " ".join(launch_command) + print(f"### For scenario {scenario}, executing process: '{log_cmd}'") + process = subprocess.Popen(launch_command, stdout=subprocess.PIPE, stderr=subprocess.PIPE, stdin=subprocess.PIPE) + + log_stdout_thread = Thread(target=log_output, args=(process.stdout, output, )) + log_stdout_thread.daemon = True # die with the program + log_stdout_thread.start() + + log_stderr_thread = Thread(target=log_output, args=(process.stderr, output, )) + log_stderr_thread.daemon = True # die with the program + log_stderr_thread.start() + + print(f"### Waiting for process to finish...") + try: + process.wait() + except KeyboardInterrupt: + print("### Interrupted by user. Sending SIGINT...") + process.send_signal(signal.SIGINT) + try: + process.wait(timeout=20) + return False + except subprocess.TimeoutExpired: + print("### Process not stopped after 20s. Sending SIGKILL...") + process.send_signal(signal.SIGKILL) + try: + process.wait(timeout=10) + return False + except subprocess.TimeoutExpired: + print("### Process not stopped after 10s.") + return False + ret = process.returncode + + print(f"### Storing results in {self.output_dir}...") + + with open(output_file_path + '.log', 'w') as out: + for line in output: + out.write(line + '\n') + if ret: + print("### Process failed.") + else: + print("### Process finished successfully.") + + return True + + +def main(): + """ + main function + """ + parser = argparse.ArgumentParser() + parser.add_argument('-i', '--scenario-dir', type=str, help='Directory containing the scenarios') + parser.add_argument('-o', '--output-dir', type=str, help='Directory containing the output', default='out') + parser.add_argument('launch_command', nargs='+') + args = parser.parse_args(sys.argv[1:]) + + try: + scenario_batch_execution = ScenarioBatchExecution(args) + except Exception as e: # pylint: disable=broad-except + print(f"Error while initializing batch execution: {e}") + sys.exit(1) + if scenario_batch_execution.run(): + sys.exit(0) + else: + print("Error during batch executing!") + sys.exit(1) + + +if __name__ == '__main__': + main() diff --git a/scenario_coverage/scenario_coverage/scenario_variation.py b/scenario_coverage/scenario_coverage/scenario_variation.py new file mode 100644 index 00000000..2bd56702 --- /dev/null +++ b/scenario_coverage/scenario_coverage/scenario_variation.py @@ -0,0 +1,153 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import sys +import argparse +from copy import deepcopy + +import yaml + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_resolver import resolve_internal_model +from scenario_execution_base.model.types import RelationExpression, ListExpression, print_tree, serialize +from scenario_execution_base.utils.logging import Logger + + +class ScenarioVariation(object): + + def __init__(self, target_dir, scenario, log_model, debug) -> None: + self.logger = Logger('scenario_variation') + self.target_dir = target_dir + self.scenario = scenario + self.log_model = log_model + self.debug = debug + + def get_variations(self, variant_element: RelationExpression): + base_element = deepcopy(variant_element) + base_element.operator = '==' + base_element.delete_child(base_element.get_child_with_expected_type(1, ListExpression)) + variations = [] + list_expression = variant_element.get_child_with_expected_type(1, ListExpression) + for child in list_expression.get_children(): + variation = deepcopy(base_element) + variation.set_children(child) + variations.append(variation) + return variations + + def run(self) -> bool: + model = self.load_model() + if model is None: + return False + + models = self.generate_concrete_models(model) + if not models: + return False + + return self.save_resulting_scenarios(models) + + def load_model(self): + parser = OpenScenario2Parser(self.logger) + parsed_tree, errors = parser.parse_file(self.scenario, self.log_model) + if errors: + return None + + return parser.load_internal_model(parsed_tree, self.scenario, self.log_model, self.debug) + + def get_next_variation_element(self, elem): + if isinstance(elem, RelationExpression): + if elem.operator == 'in': + return elem + else: + return None + else: + for child in elem.get_children(): + elem = self.get_next_variation_element(child) + if elem: + return elem + return None + + def generate_concrete_models(self, model): + models = [model] + while True: + # The following loop always looks at the first element in models. + # If it contains a variation_element the element is removed and the + # resulting models are appended at the back. + variation_element = self.get_next_variation_element(models[0]) + if variation_element is None: + print("No further variation") + return models + print(f"Creating models for variation model {variation_element}") + # remove model with variation from list + model = models[0] + models.remove(model) + + # remove original variation element + parent = variation_element.get_parent() + parent.delete_child(variation_element) + + # set resolved variations in copies of original model + variations = self.get_variations(variation_element) + for variation in variations: + parent.set_children(variation) + variation_model = deepcopy(model) + models.append(variation_model) + parent.delete_child(variation) + + def save_resulting_scenarios(self, models): + idx = 0 + file_path = os.path.join(self.target_dir, os.path.splitext(os.path.basename(self.scenario))[0]) + for model in models: + print("-----------------") + test_resolve = deepcopy(model) + serialize_data = serialize(model)['CompilationUnit']['_children'] + success = resolve_internal_model(test_resolve, self.logger, False) + if not success: + print(f"Error: model is not resolvable.") + return False + print_tree(model, self.logger) + filename = file_path + str(idx) + '.sce' + print(f"Storing model in {filename}") + with open(filename, 'w') as output: + yaml.safe_dump(serialize_data, output, sort_keys=False) + idx += 1 + return True + + +def main(): + """ + main function + """ + parser = argparse.ArgumentParser() + parser.add_argument('-d', '--debug', action='store_true', help='debugging output') + parser.add_argument('-o', '--log-model', action='store_true', help='Produce tree output of parsed model content') + parser.add_argument('-t', '--target-dir', type=str, help='Target directory for concrete scenarios', default='out') + parser.add_argument('scenario', type=str, help='abstract scenario file') + args = parser.parse_args(sys.argv[1:]) + + if not os.path.isdir(args.target_dir): + os.mkdir(args.target_dir) + + scenario_variation = ScenarioVariation(args.target_dir, args.scenario, args.log_model, args.debug) + if scenario_variation.run(): + sys.exit(0) + else: + print("Error!") + sys.exit(1) + + +if __name__ == '__main__': + main() diff --git a/scenario_coverage/scenarios/test_fault_injection.osc b/scenario_coverage/scenarios/test_fault_injection.osc new file mode 100644 index 00000000..8eaa74c0 --- /dev/null +++ b/scenario_coverage/scenarios/test_fault_injection.osc @@ -0,0 +1,26 @@ +import osc.ros + +scenario nav2_simulation_fault_injection: + turtlebot4: differential_drive_robot with: + keep(it.model == 'topic:///robot_description') + do parallel: + test_drive: serial: + turtlebot4.init_nav2() with: + keep(it.initial_pose.position == position_3d(x: 0.0m, y: 0.0m)) + record_bag() with: + keep(it.destination_dir == '/transfer') + keep(it.topics == '/scenario_status /robot_pose_loc /robot_pose_gt /cmd_vel /amcl_pose /odom /tf /tf_static') # whitespace-separated list of topics + set_node_parameter() with: + keep(it.node_name == 'laserscan_modification') + keep(it.parameter_name == 'gaussian_noise_std_deviation') + keep(it.parameter_value in ['0.0', '0.1', '0.2', '0.5']) + set_node_parameter() with: + keep(it.node_name == 'laserscan_modification') + keep(it.parameter_name == 'random_drop_percentage') + keep(it.parameter_value in ['0.0', '0.1','0.5', '0.9']) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 3.0m, y: -3.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + emit end + time_out: serial: + wait elapsed(240s) + emit fail diff --git a/scenario_coverage/scenarios/test_fault_injection_drop.osc b/scenario_coverage/scenarios/test_fault_injection_drop.osc new file mode 100644 index 00000000..f9e95530 --- /dev/null +++ b/scenario_coverage/scenarios/test_fault_injection_drop.osc @@ -0,0 +1,20 @@ +import osc.ros + +scenario nav2_simulation_fault_injection: + turtlebot4: differential_drive_robot with: + keep(it.model == 'topic:///robot_description') + do parallel: + test_drive: serial: + turtlebot4.init_nav2() with: + keep(it.initial_pose.position == position_3d(x: 0.0m, y: 0.0m)) + #keep(it.use_initial_pose == false) + set_node_parameter() with: + keep(it.node_name == 'laserscan_modification') + keep(it.parameter_name == 'random_drop_percentage') + keep(it.parameter_value in ['0.1','0.5', '0.9']) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 3.0m, y: -3.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + emit end + time_out: serial: + wait elapsed(240s) + emit fail diff --git a/scenario_coverage/scenarios/test_fault_injection_noise.osc b/scenario_coverage/scenarios/test_fault_injection_noise.osc new file mode 100644 index 00000000..0a932cb0 --- /dev/null +++ b/scenario_coverage/scenarios/test_fault_injection_noise.osc @@ -0,0 +1,20 @@ +import osc.ros + +scenario nav2_simulation_fault_injection: + turtlebot4: differential_drive_robot with: + keep(it.model == 'topic:///robot_description') + do parallel: + test_drive: serial: + turtlebot4.init_nav2() with: + keep(it.initial_pose.position == position_3d(x: 0.0m, y: 0.0m)) + #keep(it.use_initial_pose == false) + set_node_parameter() with: + keep(it.node_name == 'laserscan_modification') + keep(it.parameter_name == 'gaussian_noise_std_deviation') + keep(it.parameter_value in ['0.1','0.2', '0.5']) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 3.0m, y: -3.0m))) + turtlebot4.nav_to_pose(pose_3d(position_3d(x: 0.0m, y: 0.0m))) + emit end + time_out: serial: + wait elapsed(240s) + emit fail diff --git a/scenario_coverage/scenarios/test_log.osc b/scenario_coverage/scenarios/test_log.osc new file mode 100644 index 00000000..b18d658f --- /dev/null +++ b/scenario_coverage/scenarios/test_log.osc @@ -0,0 +1,7 @@ +import osc.helpers + +scenario test_log: + do serial: + log() with: + keep(it.msg in ["foo", "bar"]) + emit end diff --git a/scenario_coverage/scenarios/test_nav_to_pose.osc b/scenario_coverage/scenarios/test_nav_to_pose.osc new file mode 100644 index 00000000..4fa749f3 --- /dev/null +++ b/scenario_coverage/scenarios/test_nav_to_pose.osc @@ -0,0 +1,19 @@ +import osc.ros + +scenario nav2_simulation_nav_to_pose: + turtlebot4: differential_drive_robot with: + keep(it.model == 'topic:///robot_description') + do parallel: + test_drive: serial: + turtlebot4.init_nav2() with: + keep(it.initial_pose.position == position_3d(x: 0.0m, y: 0.0m)) + #keep(it.use_initial_pose == false) + turtlebot4.nav_to_pose() with: + keep(it.goal_pose in [ + pose_3d(position: position_3d(x: 3.0m, y: -3.0m), orientation: orientation_3d(yaw: 0.0rad)), + pose_3d(position: position_3d(x: 3.0m, y: 3.0m), orientation: orientation_3d(yaw: 0.0rad)) + ]) + emit end + time_out: serial: + wait elapsed(240s) + emit fail diff --git a/scenario_coverage/setup.cfg b/scenario_coverage/setup.cfg new file mode 100644 index 00000000..d7c3c20d --- /dev/null +++ b/scenario_coverage/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/scenario_coverage +[install] +install_scripts=$base/lib/scenario_coverage diff --git a/scenario_coverage/setup.py b/scenario_coverage/setup.py new file mode 100644 index 00000000..39cda4b3 --- /dev/null +++ b/scenario_coverage/setup.py @@ -0,0 +1,45 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from glob import glob +import os +from setuptools import find_packages, setup + +PACKAGE_NAME = 'scenario_coverage' + +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=find_packages(), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'launch'), glob('launch/*launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Robotics Scenario Execution', + license='Apache License 2.0', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'scenario_variation = scenario_coverage.scenario_variation:main', + ], + }, +) diff --git a/scenario_coverage/test/test_variations.py b/scenario_coverage/test/test_variations.py new file mode 100644 index 00000000..f2f2eea1 --- /dev/null +++ b/scenario_coverage/test/test_variations.py @@ -0,0 +1,171 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import unittest + +from scenario_coverage.scenario_variation import ScenarioVariation +from scenario_execution_base.model.model_file_loader import ModelFileLoader +from scenario_execution_base.model.model_resolver import resolve_internal_model +from scenario_execution_base.utils.logging import Logger +import tempfile +import copy +import os + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + def setUp(self) -> None: + self.tmpdir = tempfile.TemporaryDirectory() + + def run_coverage(self, scenario_content): + fp = tempfile.NamedTemporaryFile(suffix='.osc', mode='w', delete=False) + fp.write(scenario_content) + fp.close() + coverage = ScenarioVariation(self.tmpdir.name, fp.name, False, False) + model = coverage.load_model() + del fp + return model, coverage + + def test_struct_variation(self): + scenario_content = """ + +struct base_struct: + base1: string + base2: string = "predefined" + +struct test_struct: + member1: string + member2: base_struct + +action foo: + param1: test_struct + +scenario test: + do serial: + foo() with: + keep(it.param1 in [test_struct(member1: 'test1', member2: base_struct(base1: 'foo1')), test_struct(member1: 'test2', member2: base_struct(base1: 'foo2'))]) +""" + model, coverage = self.run_coverage(scenario_content) + self.assertIsNotNone(model) + models = coverage.generate_concrete_models(model) + self.assertIsNotNone(models) + self.assertEqual(2, len(models)) + + # Model 1 + model = copy.deepcopy(models[0]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[3]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': {'member1': 'test1', 'member2': {'base1': 'foo1', 'base2': 'predefined'}}}) + + # Model 2 + model = copy.deepcopy(models[1]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[3]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': {'member1': 'test2', 'member2': {'base1': 'foo2', 'base2': 'predefined'}}}) + + result = coverage.save_resulting_scenarios(models) + self.assertTrue(result) + + dir_content = os.listdir(self.tmpdir.name) + scenarios = [] + for entry in dir_content: + if entry.endswith(".sce"): + scenarios.append(os.path.join(self.tmpdir.name, entry)) + self.assertEqual(2, len(scenarios)) + + # read from file + scenario0 = None + for scenario in scenarios: + if scenario.endswith("0.sce"): + scenario0 = scenario + parser = ModelFileLoader(Logger('test')) + model = parser.load_file(scenario0, True) + self.assertIsNotNone(model) + success = resolve_internal_model(model, parser.logger, False) + self.assertTrue(success) + elem = model._ModelElement__children[3]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': {'member1': 'test1', 'member2': {'base1': 'foo1', 'base2': 'predefined'}}}) + + def test_multi_variation(self): + scenario_content = """ +action foo: + param1: string + param2: string + +scenario test: + do serial: + foo() with: + keep(it.param1 in ['A1', 'A2']) + keep(it.param2 in ['B1', 'B2', 'B3']) +""" + model, coverage = self.run_coverage(scenario_content) + self.assertIsNotNone(model) + models = coverage.generate_concrete_models(model) + self.assertIsNotNone(models) + self.assertEqual(6, len(models)) + + # Model 1 + model = copy.deepcopy(models[0]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': 'A1', 'param2': 'B1'}) + + # Model 2 + model = copy.deepcopy(models[1]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': 'A1', 'param2': 'B2'}) + + # Model 3 + model = copy.deepcopy(models[2]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': 'A1', 'param2': 'B3'}) + + # Model 4 + model = copy.deepcopy(models[3]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': 'A2', 'param2': 'B1'}) + + # Model 5 + model = copy.deepcopy(models[4]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': 'A2', 'param2': 'B2'}) + + # Model 6 + model = copy.deepcopy(models[5]) + ret = resolve_internal_model(model, Logger('test'), False) + self.assertTrue(ret) + elem = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + value = elem.get_resolved_value() + self.assertEqual(value, {'param1': 'A2', 'param2': 'B3'}) diff --git a/scenario_execution/MANIFEST.in b/scenario_execution/MANIFEST.in new file mode 100644 index 00000000..a584b473 --- /dev/null +++ b/scenario_execution/MANIFEST.in @@ -0,0 +1 @@ +include scenario_execution/lib_osc/*.osc \ No newline at end of file diff --git a/scenario_execution/README.md b/scenario_execution/README.md new file mode 100644 index 00000000..a40f319a --- /dev/null +++ b/scenario_execution/README.md @@ -0,0 +1,7 @@ +# Scenario Execution + +The `scenario_execution` package is the ROS2 middleware implementation of the scenario execution. It uses the `py_trees_ros` packages as the `py_trees`'s implementation for ROS2. + +It provides the following scenario execution libraries: + +- `ros.osc`: ROS specific actions like topic publish and service call. diff --git a/scenario_execution/launch/scenario_launch.py b/scenario_execution/launch/scenario_launch.py new file mode 100644 index 00000000..75aef44c --- /dev/null +++ b/scenario_execution/launch/scenario_launch.py @@ -0,0 +1,88 @@ +#!/usr/bin/env python3 +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Scenario Launch """ +from launch_ros.actions import Node +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, Shutdown, LogInfo +from launch.substitutions import LaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition + + +def generate_launch_description(): + """ generate launch description """ + scenario = LaunchConfiguration('scenario') + debug = LaunchConfiguration('debug') + live_tree = LaunchConfiguration('live_tree') + log_model = LaunchConfiguration('log_model') + log_level = LaunchConfiguration('log_level') + scenario_execution = LaunchConfiguration('scenario_execution') + scenario_status = LaunchConfiguration('scenario_status') + test_output = LaunchConfiguration('test_output') + + return LaunchDescription([ + DeclareLaunchArgument('scenario', description='Scenario file to execute'), + DeclareLaunchArgument('debug', description='Debug output', default_value='False'), + DeclareLaunchArgument('live_tree', default_value='False', + description='output live state of scenario'), + DeclareLaunchArgument('log_model', default_value='False', + description='log parsed model'), + DeclareLaunchArgument('scenario_execution', default_value='True', + description='Wether to execute scenario execution'), + DeclareLaunchArgument('scenario_status', default_value='True', + description='Wether to execute scenario status'), + DeclareLaunchArgument('log_level', default_value='info', + description='Log level for scenario execution'), + DeclareLaunchArgument('test_output', description='Test output file', default_value=''), + + Node( + package='scenario_execution', + executable='scenario_execution', + name='scenario_execution', + output='screen', + additional_env={'PYTHONUNBUFFERED': '1'}, + arguments=['--ros-args', '--log-level', log_level], + parameters=[{ + 'use_sim_time': False, + 'debug': debug, + 'live_tree': live_tree, + 'log_model': log_model, + 'test_output': test_output, + 'scenario': scenario + }], + on_exit=Shutdown()), + + Node( + condition=IfCondition(scenario_status), + package='scenario_status', + executable='scenario_status_node', + name='scenario_status_node', + parameters=[{ + 'bt_snapshot_topic': '/bt_snapshot', + 'scenario_status_topic': '/scenario_status', + 'snapshot_srv_name': '/scenario_execution/snapshot_streams/open', + + }], + output='screen' + ), + + # Parse log for message on how to execute scenario separately + LogInfo( + condition=UnlessCondition(scenario_execution), + msg=["Skipping: ros2 launch scenario_execution scenario_launch.py scenario:=", + scenario, ' log_level:="', log_level, '"']), + ]) diff --git a/scenario_execution/package.xml b/scenario_execution/package.xml new file mode 100644 index 00000000..2941d7c3 --- /dev/null +++ b/scenario_execution/package.xml @@ -0,0 +1,30 @@ + + + + scenario_execution + 1.0.0 + Scenario Execution for ROS + Intel Labs + Intel Labs + Apache-2.0 + + scenario_execution_base + + rclpy + py_trees + py_trees_ros + visualization_msgs + nav2_simple_commander + xacro + rcl_interfaces + scenario_status + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/scenario_execution/resource/scenario_execution b/scenario_execution/resource/scenario_execution new file mode 100644 index 00000000..e69de29b diff --git a/scenario_execution/scenario_execution/__init__.py b/scenario_execution/scenario_execution/__init__.py new file mode 100644 index 00000000..c48c9ebf --- /dev/null +++ b/scenario_execution/scenario_execution/__init__.py @@ -0,0 +1,27 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Main entry for scenario execution """ + +from . import actions +from .logging_ros import RosLogger +from .scenario_execution_ros import ROSScenarioExecution + +__all__ = [ + 'actions', + 'RosLogger', + 'ROSScenarioExecution' +] diff --git a/scenario_execution/scenario_execution/actions/__init__.py b/scenario_execution/scenario_execution/actions/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution/scenario_execution/actions/conversions.py b/scenario_execution/scenario_execution/actions/conversions.py new file mode 100644 index 00000000..2fa7b521 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/conversions.py @@ -0,0 +1,73 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" common conversions """ + +import operator +from rclpy.qos import QoSPresetProfiles +import py_trees + + +def get_qos_preset_profile(qos_profile): + """ + Get qos preset for enum value + """ + if qos_profile[0] == 'parameters': + return QoSPresetProfiles.PARAMETERS.value + elif qos_profile[0] == 'parameter_events': + return QoSPresetProfiles.PARAMETER_EVENTS.value + elif qos_profile[0] == 'sensor_data': + return QoSPresetProfiles.SENSOR_DATA.value + elif qos_profile[0] == 'service_default': + return QoSPresetProfiles.SERVICE_DEFAULT.value # pylint: disable=no-member + elif qos_profile[0] == 'system_default': + return QoSPresetProfiles.SYSTEM_DEFAULT.value + else: + raise ValueError(f"Invalid qos_profile: {qos_profile}") + + +def get_comparison_operator(operator_val): # pylint: disable=too-many-return-statements + """ + Get comparison operator for enum value + """ + if operator_val[0] == 'lt': + return operator.lt + elif operator_val[0] == 'le': + return operator.le + elif operator_val[0] == 'eq': + return operator.eq + elif operator_val[0] == 'ne': + return operator.ne + elif operator_val[0] == 'ge': + return operator.ge + elif operator_val[0] == 'gt': + return operator.gt + else: + raise ValueError(f"Invalid comparison_operator: {operator_val}") + + +def get_clearing_policy(clearing_policy): + """ + Get clearing policy for enum value + """ + if clearing_policy[0] == 'on_initialise': + return py_trees.common.ClearingPolicy.ON_INITIALISE + elif clearing_policy[0] == 'on_success': + return py_trees.common.ClearingPolicy.ON_SUCCESS + elif clearing_policy[0] == 'never': + return py_trees.common.ClearingPolicy.NEVER + else: + raise ValueError(f"Invalid clearing_policy: {clearing_policy}") diff --git a/scenario_execution/scenario_execution/actions/init_nav2.py b/scenario_execution/scenario_execution/actions/init_nav2.py new file mode 100644 index 00000000..c60ce312 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/init_nav2.py @@ -0,0 +1,238 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from enum import Enum + + +from geometry_msgs.msg import PoseWithCovarianceStamped +from lifecycle_msgs.srv import GetState +from rclpy.node import Node +from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy +from rclpy.qos import QoSProfile, QoSReliabilityPolicy +from rclpy.callback_groups import ReentrantCallbackGroup +from rclpy.time import Time +from rclpy.duration import Duration +from tf2_ros import Buffer +from datetime import datetime, timedelta +import py_trees + +from .nav2_common import NamespaceAwareBasicNavigator, get_pose_stamped, NamespacedTransformListener + + +class InitNav2State(Enum): + """ + States for executing a initialization of nav2 + """ + IDLE = 1 + LOCALIZER_STATE_REQUESTED = 2 + LOCALIZER_STATE_RECEIVED = 3 + LOCALIZER_STATE_ACTIVE = 4 + WAIT_FOR_INITIAL_POSE = 5 + WAIT_FOR_MAP_BASELINK_TF = 6 + MAP_BASELINK_TF_RECEIVED = 7 + NAVIGATOR_STATE_REQUESTED = 8 + NAVIGATOR_STATE_RECEIVED = 9 + NAVIGATOR_ACTIVE = 10 + DONE = 11 + FAILURE = 12 + + +class InitNav2(py_trees.behaviour.Behaviour): + """ + Class for initializing nav2 by setting an initial pose and activate required nodes + + """ + + def __init__(self, name, associated_actor, initial_pose: list, base_frame_id: str, wait_for_initial_pose: bool, use_initial_pose: bool, namespace_override: str): + super().__init__('InitNav2Action') + self.initial_pose = initial_pose + self.base_frame_id = base_frame_id + self.wait_for_initial_pose = wait_for_initial_pose + self.use_initial_pose = use_initial_pose + self.namespace = associated_actor["namespace"] + self.node = None + self.future = None + self.current_state = InitNav2State.IDLE + self.nav = None + self.bt_navigator_state_client = None + self.amcl_state_client = None + self.localization_pose_sub = None + self.retry_count = None + self.service_called_timestamp = None + self.localizer_state = None + self.navigator_state = None + self.tf_buffer = None + self.tf_listener = None + if namespace_override: + self.namespace = namespace_override + + def setup(self, **kwargs): + """ + Setup ROS2 node and service client + + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + self.tf_buffer = Buffer() + self.tf_listener = NamespacedTransformListener( + node=self.node, buffer=self.tf_buffer, tf_topic=self.namespace + "/tf", tf_static_topic=self.namespace + "/tf_static") + + self.nav = NamespaceAwareBasicNavigator( + node_name="basic_nav_init_nav2", namespace=self.namespace) + self.bt_navigator_state_client = self.node.create_client( + GetState, self.namespace + '/bt_navigator/get_state', + callback_group=ReentrantCallbackGroup()) + self.amcl_state_client = self.node.create_client( + GetState, self.namespace + '/amcl/get_state', + callback_group=ReentrantCallbackGroup()) + + amcl_pose_qos = QoSProfile( + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + reliability=QoSReliabilityPolicy.RELIABLE, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1) + + self.localization_pose_sub = self.node.create_subscription(PoseWithCovarianceStamped, + self.namespace + '/amcl_pose', + self._amcl_pose_callback, + amcl_pose_qos, + callback_group=ReentrantCallbackGroup()) + + def update(self) -> py_trees.common.Status: + """ + Execute states + """ + self.logger.debug(f"Current State {self.current_state}") + result = py_trees.common.Status.FAILURE + if self.current_state == InitNav2State.IDLE: + if self.use_initial_pose: + self.current_state = InitNav2State.LOCALIZER_STATE_REQUESTED + if self.retry_count is None: + self.retry_count = 1000 + else: + self.retry_count -= 1 + if self.future: + self.amcl_state_client.remove_pending_request(self.future) + self.future.cancel() + + if self.retry_count > 0: + req = GetState.Request() + self.feedback_message = f"Waiting for localizer to become active. Try {1001 - self.retry_count}" # pylint: disable= attribute-defined-outside-init + self.future = self.amcl_state_client.call_async(req) + self.service_called_timestamp = datetime.now() + self.future.add_done_callback(self._get_state_done_callback) + result = py_trees.common.Status.RUNNING + else: + self.current_state = InitNav2State.WAIT_FOR_MAP_BASELINK_TF + self.feedback_message = f"Not using initial pose (probably because we localize with slam), waiting for map --> base transform" # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.LOCALIZER_STATE_REQUESTED: + timeout = timedelta(seconds=1) + if timeout < datetime.now() - self.service_called_timestamp: + self.feedback_message = f"Localizer state request timed out after 1s. Requesting again..." # pylint: disable= attribute-defined-outside-init + self.current_state = InitNav2State.IDLE + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.LOCALIZER_STATE_RECEIVED: + if self.localizer_state == "active": + self.current_state = InitNav2State.LOCALIZER_STATE_ACTIVE + self.retry_count = None + else: + self.feedback_message = f"Localizer expected to be active, but is '{self.localizer_state}'. Retrying..." # pylint: disable= attribute-defined-outside-init + self.current_state = InitNav2State.IDLE + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.LOCALIZER_STATE_ACTIVE: + self.current_state = InitNav2State.WAIT_FOR_INITIAL_POSE + if self.wait_for_initial_pose: + self.feedback_message = f"Waiting for externally set initial pose." # pylint: disable= attribute-defined-outside-init + else: + initial_pose = get_pose_stamped( + self.nav.get_clock().now().to_msg(), self.initial_pose) + self.feedback_message = f"Set initial pose." # pylint: disable= attribute-defined-outside-init + self.nav.setInitialPose(initial_pose) + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.WAIT_FOR_INITIAL_POSE: + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.WAIT_FOR_MAP_BASELINK_TF: + if self.tf_buffer.can_transform("map", self.base_frame_id, Time(seconds=0), Duration(seconds=0)): + self.feedback_message = f"Transform map -> {self.base_frame_id} got available." # pylint: disable= attribute-defined-outside-init + self.current_state = InitNav2State.MAP_BASELINK_TF_RECEIVED + else: + self.feedback_message = f"Waiting for transform map -> {self.base_frame_id} to get available..." # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.MAP_BASELINK_TF_RECEIVED: + self.current_state = InitNav2State.NAVIGATOR_STATE_REQUESTED + if self.retry_count is None: + self.retry_count = 1000 + else: + self.retry_count -= 1 + if self.future: + self.bt_navigator_state_client.remove_pending_request(self.future) + self.future.cancel() + if self.retry_count > 0: + req = GetState.Request() + self.feedback_message = f"Request navigator state. Try {1001 - self.retry_count}" # pylint: disable= attribute-defined-outside-init + self.future = self.bt_navigator_state_client.call_async(req) + self.service_called_timestamp = datetime.now() + self.future.add_done_callback(self._get_state_done_callback) + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.NAVIGATOR_STATE_REQUESTED: + timeout = timedelta(seconds=1) + if timeout < datetime.now() - self.service_called_timestamp: + self.feedback_message = f"Navigator state request timed out after 1s. Requesting again..." # pylint: disable= attribute-defined-outside-init + self.current_state = InitNav2State.MAP_BASELINK_TF_RECEIVED + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.NAVIGATOR_STATE_RECEIVED: + if self.navigator_state == "active": + self.feedback_message = f"Navigator active." # pylint: disable= attribute-defined-outside-init + self.current_state = InitNav2State.NAVIGATOR_ACTIVE + self.retry_count = None + else: + self.feedback_message = f"Navigator expected to be active, but is {self.navigator_state}. Retrying..." # pylint: disable= attribute-defined-outside-init + self.current_state = InitNav2State.MAP_BASELINK_TF_RECEIVED + result = py_trees.common.Status.RUNNING + elif self.current_state == InitNav2State.NAVIGATOR_ACTIVE: + result = py_trees.common.Status.SUCCESS + self.current_state = InitNav2State.DONE + elif self.current_state == InitNav2State.DONE: + self.logger.debug("Nothing to do!") + else: + self.logger.error(f"Invalid state {self.current_state}") + + return result + + def _get_state_done_callback(self, future): + """ + Callback function when the GetState future is done + """ + self.logger.debug(f"Received state {future.result()}") + if self.current_state == InitNav2State.LOCALIZER_STATE_REQUESTED: + self.localizer_state = future.result().current_state.label + self.current_state = InitNav2State.LOCALIZER_STATE_RECEIVED + elif self.current_state == InitNav2State.NAVIGATOR_STATE_REQUESTED: + self.navigator_state = future.result().current_state.label + self.current_state = InitNav2State.NAVIGATOR_STATE_RECEIVED + + def _amcl_pose_callback(self, msg): + """ + Callback function when amcl pose is received + """ + if self.current_state == InitNav2State.WAIT_FOR_INITIAL_POSE: + self.current_state = InitNav2State.WAIT_FOR_MAP_BASELINK_TF diff --git a/scenario_execution/scenario_execution/actions/nav2_common.py b/scenario_execution/scenario_execution/actions/nav2_common.py new file mode 100644 index 00000000..d10a50f8 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/nav2_common.py @@ -0,0 +1,208 @@ +# Copyright 2021 Samsung Research America +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from geometry_msgs.msg import PoseStamped, PoseWithCovarianceStamped +from rclpy.qos import QoSDurabilityPolicy, QoSHistoryPolicy +from rclpy.qos import QoSProfile, QoSReliabilityPolicy +from rclpy.qos import DurabilityPolicy +from rclpy.qos import HistoryPolicy +from rclpy.node import Node +from rclpy.action import ActionClient +from rclpy.callback_groups import ReentrantCallbackGroup +from rclpy.executors import SingleThreadedExecutor + +from transforms3d.taitbryan import euler2quat + +from nav2_msgs.action import BackUp, Spin +from nav2_msgs.action import ComputePathThroughPoses, ComputePathToPose +from nav2_msgs.action import FollowPath, FollowWaypoints, NavigateThroughPoses, NavigateToPose +from nav2_msgs.srv import ClearEntireCostmap, GetCostmap, LoadMap + +from nav2_simple_commander.robot_navigator import BasicNavigator # pylint: disable=import-error +from tf2_ros import Buffer +from tf2_msgs.msg import TFMessage +from threading import Thread + +from typing import Optional +from typing import Union + + +def get_pose_stamped(timestamp, in_pose): + """ + Convert pose list to PoseStamped + """ + pose = PoseStamped() + pose.header.frame_id = 'map' + pose.header.stamp = timestamp + pose.pose.position.x = in_pose['position']['x'] + pose.pose.position.y = in_pose['position']['y'] + pose.pose.position.z = in_pose['position']['z'] + + # euler2quat() requires "zyx" convention, + # while in YAML, we define as pitch-roll-yaw (xyz), since it's more intuitive. + quaternion = euler2quat(in_pose['orientation']['yaw'], + in_pose['orientation']['roll'], + in_pose['orientation']['pitch']) + pose.pose.orientation.w = quaternion[0] + pose.pose.orientation.x = quaternion[1] + pose.pose.orientation.y = quaternion[2] + pose.pose.orientation.z = quaternion[3] + return pose + + +class NamespacedTransformListener: + """ + :class:`TransformListener` is a convenient way to listen for coordinate frame transformation info. + This class takes an object that instantiates the :class:`BufferInterface` interface, to which + it propagates changes to the tf frame graph. + """ + + def __init__( + self, + buffer: Buffer, + node: Node, + *, + tf_topic: str = '/tf', + tf_static_topic: str = '/tf_static', + spin_thread: bool = False, + qos: Optional[Union[QoSProfile, int]] = None, + static_qos: Optional[Union[QoSProfile, int]] = None + ) -> None: + """ + Constructor. + + :param buffer: The buffer to propagate changes to when tf info updates. + :param node: The ROS2 node. + :param spin_thread: Whether to create a dedidcated thread to spin this node. + :param qos: A QoSProfile or a history depth to apply to subscribers. + :param static_qos: A QoSProfile or a history depth to apply to tf_static subscribers. + """ + if qos is None: + qos = QoSProfile( + depth=100, + durability=DurabilityPolicy.VOLATILE, + history=HistoryPolicy.KEEP_LAST, + ) + if static_qos is None: + static_qos = QoSProfile( + depth=100, + durability=DurabilityPolicy.TRANSIENT_LOCAL, + history=HistoryPolicy.KEEP_LAST, + ) + self.buffer = buffer + self.node = node + # Default callback group is mutually exclusive, which would prevent waiting for transforms + # from another callback in the same group. + self.group = ReentrantCallbackGroup() + self.tf_sub = node.create_subscription( + TFMessage, tf_topic, self.callback, qos, callback_group=self.group) + self.tf_static_sub = node.create_subscription( + TFMessage, tf_static_topic, self.static_callback, static_qos, callback_group=self.group) + + if spin_thread: + self.executor = SingleThreadedExecutor() + + def run_func(): + self.executor.add_node(self.node) + self.executor.spin() + self.executor.remove_node(self.node) + + self.dedicated_listener_thread = Thread(target=run_func) + self.dedicated_listener_thread.start() + + def __del__(self) -> None: + if hasattr(self, 'dedicated_listener_thread') and hasattr(self, 'executor'): + self.executor.shutdown() + self.dedicated_listener_thread.join() + + self.unregister() + + def unregister(self) -> None: + """ + Unregisters all tf subscribers. + """ + self.node.destroy_subscription(self.tf_sub) + self.node.destroy_subscription(self.tf_static_sub) + + def callback(self, data: TFMessage) -> None: + who = 'default_authority' + for transform in data.transforms: + self.buffer.set_transform(transform, who) + + def static_callback(self, data: TFMessage) -> None: + who = 'default_authority' + for transform in data.transforms: + self.buffer.set_transform_static(transform, who) + + +class NamespaceAwareBasicNavigator(BasicNavigator): + """ + Subclass of BasicNavigator to support namespaces + """ + + def __init__(self, node_name, namespace): + """ + Clone of BasicNavigator init + support for namespaces + """ + super(BasicNavigator, self).__init__(node_name=node_name, # pylint: disable=bad-super-call + namespace=namespace) # pylint: disable=non-parent-init-called + + self.initial_pose = PoseStamped() + self.initial_pose.header.frame_id = 'map' + self.goal_handle = None + self.result_future = None + self.feedback = None + self.status = None + self.cb_group = ReentrantCallbackGroup() + + amcl_pose_qos = QoSProfile( + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + reliability=QoSReliabilityPolicy.RELIABLE, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1) + + self.initial_pose_received = False + self.nav_through_poses_client = ActionClient(self, + NavigateThroughPoses, + 'navigate_through_poses') + self.nav_to_pose_client = ActionClient(self, NavigateToPose, 'navigate_to_pose') + self.follow_waypoints_client = ActionClient(self, FollowWaypoints, 'follow_waypoints') + self.follow_path_client = ActionClient(self, FollowPath, 'follow_path') + self.compute_path_to_pose_client = ActionClient(self, ComputePathToPose, + 'compute_path_to_pose') + self.compute_path_through_poses_client = ActionClient(self, ComputePathThroughPoses, + 'compute_path_through_poses') + self.spin_client = ActionClient(self, Spin, 'spin') + self.backup_client = ActionClient(self, BackUp, 'backup') + self.localization_pose_sub = self.create_subscription(PoseWithCovarianceStamped, + 'amcl_pose', + self._amclPoseCallback, + amcl_pose_qos) + self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped, + 'initialpose', + 10) + self.change_maps_srv = self.create_client(LoadMap, 'map_server/load_map') + self.clear_costmap_global_srv = self.create_client( + ClearEntireCostmap, 'global_costmap/clear_entirely_global_costmap', + callback_group=self.cb_group) + self.clear_costmap_local_srv = self.create_client( + ClearEntireCostmap, 'local_costmap/clear_entirely_local_costmap', + callback_group=self.cb_group) + self.get_costmap_global_srv = self.create_client( + GetCostmap, 'global_costmap/get_costmap', callback_group=self.cb_group) + self.get_costmap_local_srv = self.create_client( + GetCostmap, 'local_costmap/get_costmap', callback_group=self.cb_group) diff --git a/scenario_execution/scenario_execution/actions/nav_through_poses.py b/scenario_execution/scenario_execution/actions/nav_through_poses.py new file mode 100644 index 00000000..6efe26f6 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/nav_through_poses.py @@ -0,0 +1,125 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from enum import Enum + +from rclpy.node import Node +from rclpy.duration import Duration + +import py_trees + +from nav2_simple_commander.robot_navigator import TaskResult # pylint: disable=import-error + +from .nav2_common import NamespaceAwareBasicNavigator +from .nav2_common import get_pose_stamped + + +class NavThroughPosesState(Enum): + """ + States for executing a nav-through-poses with nav2 + """ + IDLE = 1 + NAV_TO_GOAL = 2 + DONE = 3 + + +class NavThroughPoses(py_trees.behaviour.Behaviour): + """ + Class to navigate through poses + """ + + def __init__(self, name: str, associated_actor, goal_poses: list, monitor_progress: bool, namespace_override: str): + super().__init__(name) + self.namespace = associated_actor["namespace"] + self.monitor_progress = monitor_progress + self.node = None + self.future = None + self.current_state = NavThroughPosesState.IDLE + self.nav = None + if namespace_override: + self.namespace = namespace_override + + if not isinstance(goal_poses, list): + raise TypeError(f'goal_poses needs to be list of position_3d, got {type(goal_poses)}.') + else: + self.goal_poses = goal_poses + + def setup(self, **kwargs): + """ + Setup ROS2 node and service client + + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + self.nav = NamespaceAwareBasicNavigator( + node_name="basic_nav_nav_through_poses", namespace=self.namespace) + + def update(self) -> py_trees.common.Status: + """ + Execute states + """ + self.logger.debug(f"Current State {self.current_state}") + result = py_trees.common.Status.FAILURE + if self.current_state == NavThroughPosesState.IDLE: + self.current_state = NavThroughPosesState.NAV_TO_GOAL + goal_poses = [] + for pose in self.goal_poses: + goal_poses.append(get_pose_stamped(self.nav.get_clock().now().to_msg(), pose)) + self.feedback_message = "Execute navigation." # pylint: disable= attribute-defined-outside-init + go_to_pose_result = self.nav.goThroughPoses(goal_poses) + if go_to_pose_result: + if self.monitor_progress: + result = py_trees.common.Status.RUNNING + self.current_state = NavThroughPosesState.NAV_TO_GOAL + else: + result = py_trees.common.Status.SUCCESS + self.current_state = NavThroughPosesState.DONE + else: + self.current_state = NavThroughPosesState.DONE + result = py_trees.common.Status.FAILURE + elif self.current_state == NavThroughPosesState.NAV_TO_GOAL: + if not self.nav.isTaskComplete(): + feedback = self.nav.getFeedback() + if feedback: + self.feedback_message = 'Estimated time of arrival: ' + '{0:.0f}'.format( # pylint: disable= attribute-defined-outside-init + Duration.from_msg(feedback.estimated_time_remaining).nanoseconds / 1e9) + ' seconds.' + + if Duration.from_msg(feedback.navigation_time) > Duration(seconds=600): + self.nav.cancelTask() + result = py_trees.common.Status.RUNNING + else: + self.current_state = NavThroughPosesState.DONE + result = self.nav.getResult() + if result == TaskResult.SUCCEEDED: + self.feedback_message = 'Goal succeeded!' # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.SUCCESS + elif result == TaskResult.CANCELED: + self.feedback_message = 'Goal was canceled!' # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.FAILURE + elif result == TaskResult.FAILED: + self.feedback_message = 'Goal failed!' # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.FAILURE + elif self.current_state == NavThroughPosesState.DONE: + self.logger.debug("Nothing to do!") + else: + self.logger.error(f"Invalid state {self.current_state}") + + return result diff --git a/scenario_execution/scenario_execution/actions/nav_to_pose.py b/scenario_execution/scenario_execution/actions/nav_to_pose.py new file mode 100644 index 00000000..63379644 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/nav_to_pose.py @@ -0,0 +1,180 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from enum import Enum + +from rclpy.node import Node +from rclpy.duration import Duration +from rclpy.action import ActionClient + +import py_trees + +from .nav2_common import get_pose_stamped + +from nav2_msgs.action import NavigateToPose +from action_msgs.msg import GoalStatus + + +class NavToPoseState(Enum): + """ + States for executing a nav-to-pose with nav2 + """ + IDLE = 1 + NAV_TO_GOAL_REQUESTED = 2 + NAV_TO_GOAL = 3 + DONE = 4 + FAILURE = 5 + + +class NavToPose(py_trees.behaviour.Behaviour): + """ + Class to navigate to a pose + """ + + def __init__(self, name: str, associated_actor, goal_pose: list, monitor_progress: bool, action_topic: str, namespace_override: str) -> None: + super().__init__(name) + self.goal_pose = goal_pose + self.namespace = associated_actor["namespace"] + if namespace_override: + self.namespace = namespace_override + + self.monitor_progress = monitor_progress + self.action_topic = action_topic + self.node = None + self.future = None + self.current_state = NavToPoseState.IDLE + self.nav_to_pose_client = None + self.result_future = None + self.goal_handle = None + self.feedback = None + self.request_result = None + self.status = None + + def setup(self, **kwargs): + """ + Setup ROS2 node and service client + + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + self.nav_to_pose_client = ActionClient( + self.node, NavigateToPose, self.namespace + '/' + self.action_topic) + + self.logger.debug("Waiting for 'NavigateToPose' action server") + wait_for_action_server_time = 30 + while wait_for_action_server_time > 0 and not self.nav_to_pose_client.wait_for_server(timeout_sec=1.0): + self.logger.info(f"'NavigateToPose' action server not available, waiting {wait_for_action_server_time}s...") + wait_for_action_server_time -= 1 + if wait_for_action_server_time == 0: + raise ValueError("Timeout while waiting for action server.") + + def update(self) -> py_trees.common.Status: + """ + Execute states + """ + self.logger.debug(f"Current State {self.current_state}") + result = py_trees.common.Status.FAILURE + if self.current_state == NavToPoseState.IDLE: + goal_pose = get_pose_stamped(self.node.get_clock().now().to_msg(), self.goal_pose) + self.feedback_message = "Executing navigation." # pylint: disable= attribute-defined-outside-init + + result = py_trees.common.Status.RUNNING + self.current_state = NavToPoseState.NAV_TO_GOAL_REQUESTED + self.navigate_to_pose(goal_pose) + elif self.current_state == NavToPoseState.NAV_TO_GOAL_REQUESTED: + if self.goal_handle: + if not self.goal_handle.accepted: + self.current_state = NavToPoseState.FAILURE + self.feedback_message = 'Goal was rejected!' # pylint: disable= attribute-defined-outside-init + else: + if self.monitor_progress: + result = py_trees.common.Status.RUNNING + self.current_state = NavToPoseState.NAV_TO_GOAL + + self.result_future = self.goal_handle.get_result_async() + else: + result = py_trees.common.Status.SUCCESS + self.current_state = NavToPoseState.DONE + else: + result = py_trees.common.Status.RUNNING + elif self.current_state == NavToPoseState.NAV_TO_GOAL: + if not self.is_task_complete(): + if self.feedback: + self.feedback_message = 'Estimated time of arrival: ' + '{0:.0f}'.format( # pylint: disable= attribute-defined-outside-init + Duration.from_msg(self.feedback.estimated_time_remaining).nanoseconds / 1e9) + ' seconds.' + + if Duration.from_msg(self.feedback.navigation_time) > Duration(seconds=600): + self.cancel_task() + result = py_trees.common.Status.RUNNING + else: + self.current_state = NavToPoseState.DONE + result = self.status + if result == GoalStatus.STATUS_SUCCEEDED: + self.feedback_message = 'Goal succeeded!' # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.SUCCESS + elif result == GoalStatus.STATUS_CANCELED: + self.feedback_message = 'Goal was canceled!' # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.FAILURE + elif result == GoalStatus.STATUS_ABORTED: + self.feedback_message = 'Goal failed!' # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.FAILURE + elif self.current_state == NavToPoseState.DONE: + self.logger.debug("Nothing to do!") + else: + self.logger.error(f"Invalid state {self.current_state}") + + return result + + def navigate_to_pose(self, pose, behavior_tree=''): + goal_msg = NavigateToPose.Goal() + goal_msg.pose = pose + goal_msg.behavior_tree = behavior_tree + + self.logger.info( + f'Navigating to goal: {pose.pose.position.x:.2f} {pose.pose.position.y:.2f}...') + future = self.nav_to_pose_client.send_goal_async(goal_msg, self.feedback_callback) + future.add_done_callback(self.send_goal_done_callback) + + def send_goal_done_callback(self, future): + self.goal_handle = future.result() + + def is_task_complete(self): + if not self.result_future: + return True + if self.result_future.result(): + self.status = self.result_future.result().status + if self.status != GoalStatus.STATUS_SUCCEEDED: + self.feedback_message = f'Task failed with status code: {self.status}' # pylint: disable= attribute-defined-outside-init + return True + else: + # Timed out, still processing, not complete yet + return False + + self.feedback_message = "Navigation executed." # pylint: disable= attribute-defined-outside-init + return True + + def cancel_task(self): + self.logger.info('Canceling current task.') + if self.result_future: + self.goal_handle.cancel_goal_async() + + def feedback_callback(self, msg): + self.feedback = msg.feedback diff --git a/scenario_execution/scenario_execution/actions/odometry_distance_traveled.py b/scenario_execution/scenario_execution/actions/odometry_distance_traveled.py new file mode 100644 index 00000000..65c3bac2 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/odometry_distance_traveled.py @@ -0,0 +1,108 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from math import sqrt +import rclpy +from rclpy.logging import get_logger +from nav_msgs.msg import Odometry +from py_trees.common import Status +import py_trees + + +class OdometryDistanceTraveled(py_trees.behaviour.Behaviour): + """ + Class to wait for a certain covered distance, based on odometry + """ + + def __init__(self, name, associated_actor, distance: float): + super().__init__(name) + self.namespace = associated_actor["namespace"] + self.distance_expected = distance + self.distance_traveled = 0. + self.previous_x = 0 + self.previous_y = 0 + self.first_run = True + self.logger = None + self.node = None + self.subscriber = None + self.callback_group = None + + def setup(self, **kwargs): + """ + Setup subscription and logger + """ + self.logger = get_logger('odometry_distance_traveled') + self.logger.debug(f"Waiting for traveled distance of {self.distance_expected}") + + try: + self.node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + self.callback_group = rclpy.callback_groups.MutuallyExclusiveCallbackGroup() + self.subscriber = self.node.create_subscription( + Odometry, self.namespace + '/odom', self._callback, 1000, callback_group=self.callback_group) + + def _callback(self, msg): + ''' + Subscriber callback + ''' + self.calculate_distance(msg) + + def calculate_distance(self, msg): + """ + Update the odometry distance + Args: + msg [Odometry]: current odometry message to update + """ + if self.first_run: + self.first_run = False + else: + x = msg.pose.pose.position.x + y = msg.pose.pose.position.y + d_increment = sqrt((x - self.previous_x) * (x - self.previous_x) + + (y - self.previous_y) * (y - self.previous_y)) + self.distance_traveled = self.distance_traveled + d_increment + self.logger.debug(f'Total distance traveled is {self.distance_traveled}m') + + self.previous_x = msg.pose.pose.position.x + self.previous_y = msg.pose.pose.position.y + + def initialise(self): + ''' + Initialize before ticking. + ''' + self.distance_traveled = 0. + self.previous_x = 0 + self.previous_y = 0 + self.first_run = True + + def update(self) -> py_trees.common.Status: + """ + Check if the traveled distance is reached + return: + py_trees.common.Status.SUCCESS if the distanced is reached, else + return py_trees.common.Status.RUNNING. + """ + + self.logger.debug(f"ticking: {self.distance_traveled}") + if self.distance_traveled >= self.distance_expected: + self.feedback_message = f"expected traveled distance reached: {self.distance_expected:.3}" # pylint: disable= attribute-defined-outside-init + return Status.SUCCESS + else: + self.feedback_message = f"distance traveled: {self.distance_traveled:.3} < {self.distance_expected:.3}" # pylint: disable= attribute-defined-outside-init + return Status.RUNNING diff --git a/scenario_execution/scenario_execution/actions/py_trees_ros_common.py b/scenario_execution/scenario_execution/actions/py_trees_ros_common.py new file mode 100644 index 00000000..2831f012 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/py_trees_ros_common.py @@ -0,0 +1,102 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +# +# License: BSD +# https://raw.githubusercontent.com/splintered-reality/py_trees_ros/devel/LICENSE +# + +import py_trees +import py_trees_ros # pylint: disable=import-error +import typing +import rclpy.qos + + +class SubscriberHandler(py_trees_ros.subscribers.Handler): + """ + overrides Handler + """ + + def __init__(self, + name: str, + topic_name: str, + topic_type: typing.Any, + qos_profile: rclpy.qos.QoSProfile, + clearing_policy: py_trees.common.ClearingPolicy = py_trees.common.ClearingPolicy.ON_INITIALISE + ): + """ + override + """ + super(SubscriberHandler, self).__init__(name=name, topic_name=topic_name, + topic_type=topic_type, qos_profile=qos_profile, clearing_policy=clearing_policy) + + def setup(self, **kwargs): + """ + Initialises the subscriber. + """ + try: + self.node = kwargs['node'] # pylint: disable= attribute-defined-outside-init + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + self.subscriber = self.node.create_subscription( # pylint: disable= attribute-defined-outside-init + msg_type=self.topic_type, + topic=self.topic_name, + callback=self._callback, + qos_profile=self.qos_profile, + callback_group=rclpy.callback_groups.ReentrantCallbackGroup() + ) + + +class SubscriberWaitForData(SubscriberHandler): + """ + overrides WaitForData + """ + + def __init__(self, + name: str, + topic_name: str, + topic_type: typing.Any, + qos_profile: rclpy.qos.QoSProfile, + clearing_policy: py_trees.common.ClearingPolicy + ): + """ + overrides WaitForData + """ + super().__init__( + name=name, + topic_name=topic_name, + topic_type=topic_type, + qos_profile=qos_profile, + clearing_policy=clearing_policy + ) + + def update(self): + """ + Returns: + :class:`~py_trees.common.Status`: :attr:`~py_trees.common.Status.RUNNING` (no data) or :attr:`~py_trees.common.Status.SUCCESS` + """ + self.logger.debug("%s.update()]" % self.__class__.__name__) + with self.data_guard: + if self.msg is None: # pylint: disable= access-member-before-definition + self.feedback_message = "no message received yet" # pylint: disable= attribute-defined-outside-init + return py_trees.common.Status.RUNNING + else: + self.feedback_message = "got incoming" # pylint: disable= attribute-defined-outside-init + if self.clearing_policy == py_trees.common.ClearingPolicy.ON_SUCCESS: + self.msg = None # pylint: disable= attribute-defined-outside-init + return py_trees.common.Status.SUCCESS diff --git a/scenario_execution/scenario_execution/actions/ros_bag_record.py b/scenario_execution/scenario_execution/actions/ros_bag_record.py new file mode 100644 index 00000000..704c160e --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_bag_record.py @@ -0,0 +1,149 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +from datetime import datetime +from enum import Enum + +import py_trees +from scenario_execution_base.actions import RunExternalProcess +import shutil +import signal + + +class RosBagRecordActionState(Enum): + """ + States for executing a ros bag recording + """ + WAITING_FOR_TOPICS = 1 + RECORDING = 2 + FAILURE = 5 + + +class RosBagRecord(RunExternalProcess): + """ + Class to execute ros bag recording + """ + + def __init__(self, name, destination_dir: str, topics: list, timestamp_suffix: bool, hidden_topics: bool, storage: str): + super().__init__(name) + if not isinstance(topics, list): + raise TypeError(f'Topics needs to be list of topics, got {type(topics)}.') + else: + self.topics = topics + self.destination_dir = destination_dir + self.timestamp_suffix = timestamp_suffix + self.include_hidden_topics = hidden_topics + self.current_state = RosBagRecordActionState.WAITING_FOR_TOPICS + self.bag_dir = '' + self.storage = storage + self.command = None + + def setup(self, **kwargs): + """ + set up + """ + if self.destination_dir: + if not os.path.exists(self.destination_dir): + raise ValueError( + f"Specified destination dir '{self.destination_dir}' does not exist") + self.bag_dir = self.destination_dir + '/' + self.bag_dir += self.get_scenario_name() + + if self.timestamp_suffix: + self.bag_dir += '_' + datetime.now().strftime("%Y%m%d%H%M%S") + + self.command = ["ros2", "bag", "record"] + if self.include_hidden_topics: + self.command.append("--include-hidden-topics") + if self.storage: + self.command.extend(["--storage", self.storage]) + + self.command.extend(["-o", self.bag_dir] + self.topics) + + self.logger.info(f'Command: {" ".join(self.command)}') + + def get_scenario_name(self): + """ + get scenario name from py tree root + """ + parent = self.parent + scenario_name = "INVALID" + while parent: + scenario_name = parent.name + parent = parent.parent + return scenario_name + + def get_logger_stderr(self): + """ + get logger for stderr messages + """ + return self.logger.info # ros2 bag record reports all messages on stderr + + def on_executed(self): + """ + Hook when process gets executed + """ + self.feedback_message = f"Waiting for all topics to subscribe..." # pylint: disable= attribute-defined-outside-init + self.current_state = RosBagRecordActionState.WAITING_FOR_TOPICS + + def check_running_process(self): + """ + hook to check running process + + return: + py_trees.common.Status + """ + if self.current_state == RosBagRecordActionState.WAITING_FOR_TOPICS: + while True: + try: + line = self.output.popleft() + if line.endswith('All requested topics are subscribed. Stopping discovery...'): + self.feedback_message = f"Recording..." # pylint: disable= attribute-defined-outside-init + self.current_state = RosBagRecordActionState.RECORDING + return py_trees.common.Status.SUCCESS + except IndexError: + break + return py_trees.common.Status.RUNNING + else: + self.current_state = RosBagRecordActionState.FAILURE + return py_trees.common.Status.FAILURE + + def cleanup(self): + """ + Cleanup on shutdown + """ + if self.current_state != RosBagRecordActionState.FAILURE: + self.logger.info('Waiting for process to quit...') + if self.process: + self.process.send_signal(signal.SIGINT) + self.process.wait() + self.logger.info('Process finished.') + if self.current_state == RosBagRecordActionState.WAITING_FOR_TOPICS and self.bag_dir and os.path.exists(self.bag_dir): + self.logger.info( + f'Cleanup while waiting for topics. Removing incomplete bag {self.bag_dir}...') + shutil.rmtree(self.bag_dir) + + def on_process_finished(self, ret): + """ + check result of process + + return: + py_trees.common.Status + """ + if self.current_state == RosBagRecordActionState.RECORDING: + self.current_state = RosBagRecordActionState.FAILURE + return py_trees.common.Status.FAILURE diff --git a/scenario_execution/scenario_execution/actions/ros_log_check.py b/scenario_execution/scenario_execution/actions/ros_log_check.py new file mode 100644 index 00000000..77c5d4b9 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_log_check.py @@ -0,0 +1,82 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import py_trees +from rclpy.qos import QoSProfile, DurabilityPolicy, HistoryPolicy +import rclpy +from rcl_interfaces.msg import Log +from py_trees.common import Status + + +class RosLogCheck(py_trees.behaviour.Behaviour): + """ + Class for scanning the ros log for specific content + """ + + def __init__(self, name, values: list): + super().__init__(name) + if not isinstance(values, list): + raise TypeError(f'Value needs to be list of strings, got {type(values)}.') + else: + self.values = values + + self.subscriber = None + self.node = None + self.found = False + + def setup(self, **kwargs): + """ + Setup the subscriber + """ + try: + self.node: rclpy.Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + topic_qos = QoSProfile( + depth=100, + durability=DurabilityPolicy.TRANSIENT_LOCAL, + history=HistoryPolicy.KEEP_LAST) + + self.subscriber = self.node.create_subscription( # pylint: disable= attribute-defined-outside-init + msg_type=Log, + topic='/rosout', + callback=self._callback, + qos_profile=topic_qos, + callback_group=rclpy.callback_groups.ReentrantCallbackGroup() + ) + self.feedback_message = f"Waiting for log" # pylint: disable= attribute-defined-outside-init + + def update(self) -> py_trees.common.Status: + """ + Wait for specified log entries + + return: + py_trees.common.Status if found + """ + if self.found: + return Status.SUCCESS + else: + return Status.RUNNING + + def _callback(self, msg): + for val in self.values: + if val in msg.msg: + self.feedback_message = f"Found string '{val}' in '{msg.msg}'" # pylint: disable= attribute-defined-outside-init + self.found = True + break diff --git a/scenario_execution/scenario_execution/actions/ros_service_call.py b/scenario_execution/scenario_execution/actions/ros_service_call.py new file mode 100644 index 00000000..660af0f7 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_service_call.py @@ -0,0 +1,121 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from ast import literal_eval +import importlib +from enum import Enum +from rclpy.node import Node +from rclpy.callback_groups import ReentrantCallbackGroup +from rosidl_runtime_py.set_message import set_message_fields +import py_trees # pylint: disable=import-error + + +class ServiceCallActionState(Enum): + """ + States for executing a service call + """ + IDLE = 1 + SERVICE_CALLED = 2 + DONE = 3 + ERROR = 4 + + +class RosServiceCall(py_trees.behaviour.Behaviour): + """ + ros service call behavior + """ + + def __init__(self, name, service_name: str, service_type: str, data: str): + super().__init__(name) + self.node = None + self.client = None + self.future = None + self.service_type = service_type + self.service_name = service_name + try: + trimmed_data = data.encode('utf-8').decode('unicode_escape') + self.data = literal_eval(trimmed_data) + except Exception as e: # pylint: disable=broad-except + raise ValueError(f"Error while parsing sevice call data:") from e + self.current_state = ServiceCallActionState.IDLE + self.cb_group = ReentrantCallbackGroup() + + def setup(self, **kwargs): + """ + Setup ROS2 node and service client + + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + datatype_in_list = self.service_type.split(".") + self.service_type = getattr( + importlib.import_module(".".join(datatype_in_list[0:-1])), + datatype_in_list[-1]) + + self.client = self.node.create_client( + self.service_type, self.service_name, callback_group=self.cb_group) + + def update(self) -> py_trees.common.Status: + """ + Execute states + """ + self.logger.debug(f"Current State {self.current_state}") + result = py_trees.common.Status.FAILURE + if self.current_state == ServiceCallActionState.IDLE: + self.current_state = ServiceCallActionState.SERVICE_CALLED + if self.future: + self.future.cancel() + req = self.service_type.Request() + set_message_fields(req, self.data) + self.future = self.client.call_async(req) + self.future.add_done_callback(self.done_callback) + self.feedback_message = f"service request sent to {self.service_name}" # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.RUNNING + elif self.current_state == ServiceCallActionState.SERVICE_CALLED: + self.feedback_message = f"waiting for response from {self.service_name}" # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.RUNNING + elif self.current_state == ServiceCallActionState.DONE: + self.feedback_message = f"service response received" # pylint: disable= attribute-defined-outside-init + result = py_trees.common.Status.SUCCESS + else: + self.logger.error(f"Invalid state {self.current_state}") + + return result + + def done_callback(self, future): + """ + Callback function when the service future is done + """ + self.logger.debug(f"Received state {future.result()}") + if self.current_state == ServiceCallActionState.SERVICE_CALLED: + if self.check_response(future.result()): + self.current_state = ServiceCallActionState.DONE + else: + self.current_state = ServiceCallActionState.ERROR + else: + self.current_state = ServiceCallActionState.ERROR + + def check_response(self, _): + """ + Check the result of a service call + Can be overriden by subclasses + """ + return True diff --git a/scenario_execution/scenario_execution/actions/ros_set_node_parameter.py b/scenario_execution/scenario_execution/actions/ros_set_node_parameter.py new file mode 100644 index 00000000..4d2e9c79 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_set_node_parameter.py @@ -0,0 +1,79 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from ast import literal_eval + +from .ros_service_call import RosServiceCall +from rcl_interfaces.msg import ParameterType + + +class RosSetNodeParameter(RosServiceCall): + """ + class for setting a node parameter + """ + + def __init__(self, name, node_name: str, parameter_name: str, parameter_value: str): + service_name = node_name + '/set_parameters' + if not service_name.startswith('/'): + service_name = '/' + service_name + + parameter_type = ParameterType.PARAMETER_STRING + parameter_assign_name = 'string_value' + if parameter_value.lower() == 'true' or parameter_value.lower() == 'false': + parameter_type = ParameterType.PARAMETER_BOOL + parameter_assign_name = 'bool_value' + elif parameter_value.isdigit(): + parameter_type = ParameterType.PARAMETER_INTEGER + parameter_assign_name = 'integer_value' + elif RosSetNodeParameter.is_float(parameter_value): + parameter_type = ParameterType.PARAMETER_DOUBLE + parameter_assign_name = 'double_value' + if parameter_value.startswith('['): + try: + vals = literal_eval(parameter_value) + except SyntaxError as e: + self.logger.error(f"Could not parse parameter_value: {parameter_value}: {e}") + pass + if vals: + if vals[0].lower() == 'true' or vals[0].lower() == 'false': + parameter_type = ParameterType.PARAMETER_BOOL_ARRAY + parameter_assign_name = 'bool_array_value' + elif vals[0].isdigit(): + parameter_type = ParameterType.PARAMETER_INTEGER_ARRAY + parameter_assign_name = 'integer_array_value' + elif RosSetNodeParameter.is_float(vals[0]): + parameter_type = ParameterType.PARAMETER_DOUBLE_ARRAY + parameter_assign_name = 'double_array_value' + else: + parameter_type = ParameterType.PARAMETER_STRING_ARRAY + parameter_assign_name = 'string_array_value' + + super().__init__(name, + service_name=service_name, + service_type='rcl_interfaces.srv.SetParameters', + data='{ "parameters": [{ "name": "' + parameter_name + '", "value": { "type": ' + str(parameter_type) + ', "' + parameter_assign_name + '": ' + parameter_value + '}}]}') + + @staticmethod + def is_float(element: any) -> bool: + """ + test for float type + """ + + try: + float(element) + return True + except ValueError: + return False diff --git a/scenario_execution/scenario_execution/actions/ros_topic_check_data.py b/scenario_execution/scenario_execution/actions/ros_topic_check_data.py new file mode 100644 index 00000000..1ebc6de7 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_topic_check_data.py @@ -0,0 +1,56 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import importlib +import py_trees_ros # pylint: disable=import-error +from scenario_execution.actions.conversions import get_qos_preset_profile, \ + get_comparison_operator, get_clearing_policy + + +class RosTopicCheckData(py_trees_ros.subscribers.CheckData): + """ + Class to check if the message on ROS topic equals to the target message + """ + + def __init__(self, + name: str, + topic_name: str, + topic_type: str, + qos_profile: str, + variable_name: str, + expected_value: str, + comparison_operator: int, + fail_if_no_data: bool, + fail_if_bad_comparison: bool, + clearing_policy: int + ): + datatype_in_list = topic_type.split(".") + topic_type = getattr( + importlib.import_module(".".join(datatype_in_list[0:-1])), + datatype_in_list[-1] + ) + + super().__init__( + name=name, + topic_name=topic_name, + topic_type=topic_type, + qos_profile=get_qos_preset_profile(qos_profile), + variable_name=variable_name, + expected_value=expected_value, + comparison_operator=get_comparison_operator(comparison_operator), + fail_if_no_data=fail_if_no_data, + fail_if_bad_comparison=fail_if_bad_comparison, + clearing_policy=get_clearing_policy(clearing_policy)) diff --git a/scenario_execution/scenario_execution/actions/ros_topic_publish.py b/scenario_execution/scenario_execution/actions/ros_topic_publish.py new file mode 100644 index 00000000..2e8efda8 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_topic_publish.py @@ -0,0 +1,85 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import importlib +from ast import literal_eval + +from rosidl_runtime_py.set_message import set_message_fields +from rclpy.node import Node + +import py_trees +from py_trees.common import Status + +from scenario_execution.actions.conversions import get_qos_preset_profile + + +class RosTopicPublish(py_trees.behaviour.Behaviour): + """ + class for publish a message on a ROS topic + """ + + def __init__(self, name, topic_type: str, topic_name: str, qos_profile: str, value: str + ): + super().__init__(name) + self.qos_profile = get_qos_preset_profile(qos_profile) + + # Parse message + datatype_in_list = topic_type.split(".") + self.topic_type = getattr( + importlib.import_module(".".join(datatype_in_list[0:-1])), + datatype_in_list[-1] + ) + self.topic_name = topic_name + self.msg_to_pub = self.topic_type() + parsed_value = literal_eval("".join(value.split('\\'))) + if not isinstance(parsed_value, dict): + raise TypeError(f'Parsed value needs type "dict", got {type(parsed_value)}.') + set_message_fields(self.msg_to_pub, parsed_value) + + # Initialize publisher and ROS node + self.publisher = None + self.node = None + + def setup(self, **kwargs): + """ + Setup the publisher + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + try: + self.publisher = self.node.create_publisher( + msg_type=self.topic_type, + topic=self.topic_name, + qos_profile=self.qos_profile + ) + except TypeError as e: + raise TypeError(f"{self.name}") from e + + def update(self) -> py_trees.common.Status: + """ + Publish the msg to topic + + return: + py_trees.common.Status if published + """ + self.publisher.publish(self.msg_to_pub) + self.feedback_message = f"published {self.msg_to_pub}" # pylint: disable= attribute-defined-outside-init + return Status.SUCCESS diff --git a/scenario_execution/scenario_execution/actions/ros_topic_wait_for_data.py b/scenario_execution/scenario_execution/actions/ros_topic_wait_for_data.py new file mode 100644 index 00000000..e50aa10a --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_topic_wait_for_data.py @@ -0,0 +1,45 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import importlib +from scenario_execution.actions.conversions import get_qos_preset_profile, get_clearing_policy +from .py_trees_ros_common import SubscriberWaitForData + + +class RosTopicWaitForData(SubscriberWaitForData): + """ + Class to check if the message on ROS topic equals to the target message + + Args: + topic_name[str]: name of the topic to connect to + topic_type[str]: class of the message type (e.g. std_msgs.msg.String) + qos_profile[str]: qos profile for the subscriber + clearing_policy[str]: when to clear the data + """ + + def __init__(self, name: str, topic_name: str, topic_type: str, qos_profile: str, clearing_policy: str): + datatype_in_list = topic_type.split(".") + topic_type = getattr( + importlib.import_module(".".join(datatype_in_list[0:-1])), + datatype_in_list[-1] + ) + + super().__init__( + name=name, + topic_name=topic_name, + topic_type=topic_type, + qos_profile=get_qos_preset_profile(qos_profile), + clearing_policy=get_clearing_policy(clearing_policy)) diff --git a/scenario_execution/scenario_execution/actions/ros_topic_wait_for_topics.py b/scenario_execution/scenario_execution/actions/ros_topic_wait_for_topics.py new file mode 100644 index 00000000..5c985720 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/ros_topic_wait_for_topics.py @@ -0,0 +1,58 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import py_trees +from rclpy.node import Node + + +class RosTopicWaitForTopics(py_trees.behaviour.Behaviour): + """ + Class to check if ROS topic are available + """ + + def __init__(self, topics: list): + super().__init__('RosTopicWaitForTopics') + if not isinstance(topics, list): + raise TypeError(f'Topics needs to be list of topics, got {type(topics)}.') + else: + self.topics = topics + self.node = None + + def setup(self, **kwargs): + """ + Setup the publisher + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + def update(self) -> py_trees.common.Status: + """ + Publish the msg to topic + + return: + py_trees.common.Status if published + """ + available_topics = self.node.get_topic_names_and_types() + available_topics = [seq[0] for seq in available_topics] + result = all(elem in available_topics for elem in self.topics) + if result: + return py_trees.common.Status.SUCCESS + else: + return py_trees.common.Status.RUNNING diff --git a/scenario_execution/scenario_execution/actions/tf_close_to.py b/scenario_execution/scenario_execution/actions/tf_close_to.py new file mode 100644 index 00000000..7912a1f1 --- /dev/null +++ b/scenario_execution/scenario_execution/actions/tf_close_to.py @@ -0,0 +1,198 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from math import sqrt + +import rclpy +from rclpy.node import Node +import py_trees +from py_trees.common import Status +from visualization_msgs.msg import Marker +from geometry_msgs.msg import PoseStamped + +from tf2_ros.buffer import Buffer +from tf2_ros import TransformException # pylint: disable= no-name-in-module + +from scenario_execution.actions.nav2_common import NamespacedTransformListener + + +class TfCloseTo(py_trees.behaviour.Behaviour): + """ + class for distance condition in ROS Gazebo simulation + """ + + def __init__( + self, + name, + associated_actor: dict, + namespace_override: str, + reference_point, + threshold: float, + sim: bool, + robot_frame_id: str, + ): + super().__init__(name) + + if not reference_point: + raise TypeError(f'reference_point not initialized.') + if not threshold: + raise TypeError(f'threshold not initialized.') + + self.namespace = associated_actor["namespace"] + if namespace_override: + self.namespace = namespace_override + self.reference_point = reference_point + self.threshold = threshold + self.sim = sim + + if robot_frame_id: + self.robot_frame_id = robot_frame_id + else: + self.robot_frame_id = 'base_link' + + self.node = None + self.marker_handler = None + self.marker_id = None + self.tf_buffer = None + self.tf_listener = None + self.success = False + + def setup(self, **kwargs): + """ + Setup ROS node handle and subscriber before ticking + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + try: + self.marker_handler = kwargs['marker_handler'] + except KeyError as e: + error_message = "didn't find 'marker_handler' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__ + ) + raise KeyError(error_message) from e + self.feedback_message = f"Waiting for transform map --> base_link" # pylint: disable= attribute-defined-outside-init + self.tf_buffer = Buffer() + tf_prefix = self.namespace + if not tf_prefix.startswith('/') and tf_prefix != '': + tf_prefix = "/" + tf_prefix + self.tf_listener = NamespacedTransformListener( + node=self.node, + buffer=self.tf_buffer, + tf_topic=(tf_prefix + "/tf"), + tf_static_topic=(tf_prefix + "/tf_static"), + ) + + marker = Marker() + marker.header.frame_id = 'map' + marker.type = Marker.CYLINDER + marker.scale.x = self.threshold + marker.scale.y = self.threshold + marker.scale.z = 0.01 + marker.color.a = 1.0 + marker.color.r = 0.5 + marker.color.g = 0.5 + marker.color.b = 0.5 + marker.pose.position.x = self.reference_point['x'] + marker.pose.position.y = self.reference_point['y'] + marker.pose.position.z = 0.0 + self.marker_id = self.marker_handler.add_marker(marker) + + def update(self) -> py_trees.common.Status: + """ + Check if the subscriber already received the right msg while ticking + """ + robot_pose, success = self.get_robot_pose_from_tf() + if not success: + self.feedback_message = f"the pose of {self.namespace} could not be retrieved from tf" # pylint: disable= attribute-defined-outside-init + return Status.RUNNING + dist = self.euclidean_dist(robot_pose.pose.position) + marker = self.marker_handler.get_marker(self.marker_id) + self.success = dist <= self.threshold + if self.success: + self.feedback_message = f"{self.namespace} reached point." # pylint: disable= attribute-defined-outside-init + marker.color.r = 0.0 + marker.color.g = 1.0 + marker.color.b = 0.0 + self.marker_handler.update_marker(self.marker_id, marker) + return Status.SUCCESS + else: + self.feedback_message = f"{self.namespace} has not reached point (distance={dist-self.threshold:.2f})" # pylint: disable= attribute-defined-outside-init + marker.color.r = 1.0 + marker.color.g = 1.0 + marker.color.b = 0.0 + self.marker_handler.update_marker(self.marker_id, marker) + return Status.RUNNING + + def get_robot_pose_from_tf(self): + ''' + function to get pose of the robot (i.e., the base_link frame) with + respect to the map frame via tf + + returns: + pose: pose of the robot in the map frame + ''' + pose = PoseStamped() + when = self.node.get_clock().now() + if self.sim: + when = rclpy.time.Time() + try: + t = self.tf_buffer.lookup_transform( + 'map', + self.robot_frame_id, + when, + timeout=rclpy.duration.Duration(seconds=1.0), + ) + self.feedback_message = f"Transform map -> base_link got available." # pylint: disable= attribute-defined-outside-init + except TransformException as ex: + self.feedback_message = f"Could not transform map to base_link" # pylint: disable= attribute-defined-outside-init + self.node.get_logger().warn( + f'Could not transform map to base_link at time {when}: {ex}') + return pose, False + + pose.header = t.header + pose.header.frame_id = 'map' + + pose.pose.position.x = t.transform.translation.x + pose.pose.position.y = t.transform.translation.y + pose.pose.orientation.x = t.transform.rotation.x + pose.pose.orientation.y = t.transform.rotation.y + pose.pose.orientation.z = t.transform.rotation.z + pose.pose.orientation.w = t.transform.rotation.w + + return pose, True + + def euclidean_dist(self, pos): + ''' + Calculate the euclidean distance between the robot position and the reference point + + Args: + pos: Position of the robot + + return: + Euclidean distance in float + ''' + return sqrt((self.reference_point['x'] - pos.x) ** 2 + (self.reference_point['y'] - pos.y) ** 2) + + def cleanup(self): + """ + Cleanup on shutdown + """ + self.marker_handler.remove_markers([self.marker_id]) diff --git a/scenario_execution/scenario_execution/get_osc_library.py b/scenario_execution/scenario_execution/get_osc_library.py new file mode 100644 index 00000000..91b46520 --- /dev/null +++ b/scenario_execution/scenario_execution/get_osc_library.py @@ -0,0 +1,19 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +def get_ros_library(): + return 'scenario_execution', 'ros.osc' diff --git a/scenario_execution/scenario_execution/lib_osc/ros.osc b/scenario_execution/scenario_execution/lib_osc/ros.osc new file mode 100644 index 00000000..d57de868 --- /dev/null +++ b/scenario_execution/scenario_execution/lib_osc/ros.osc @@ -0,0 +1,135 @@ +import osc.robotics + +# Policy rules for behaviours to dictate when data should be cleared/reset. +# on_initialise Clear when entering the py_trees.behaviour.Behaviour.initialise method. +# on_success Clear when returning py_trees.common.Status.SUCCESS +# never Never clear the data +enum clearing_policy: [ + on_initialise, + on_success, + never +] + +enum qos_preset_profiles: [ + parameters, + parameter_events, + sensor_data, + services_default, + system_default +] + +enum comparison_operator: [ + lt, + le, + eq, + ne, + ge, + gt +] + +action wait_for_data: + topic_name: string # name of the topic to connect to + topic_type: string # class of the message type (e.g. std_msgs.msg.String) + qos_profile: qos_preset_profiles = qos_preset_profiles!system_default # qos profile for the subscriber + clearing_policy: clearing_policy = clearing_policy!on_initialise # when to clear the data + +action wait_for_topics: + # wait for topics to get available + topics: list of topics + +action check_data: + topic_name: string # name of the topic to connect to + topic_type: string # class of the message type (e.g. std_msgs.msg.String) + qos_profile: qos_preset_profiles = qos_preset_profiles!system_default # qos profile for the subscriber + variable_name: string # name of the variable to check + expected_value: string # expected value of the variable + comparison_operator: comparison_operator = comparison_operator!eq # one from the python `operator module`_ + fail_if_no_data: bool = false # py_trees.common.Status.FAILURE instead of py_trees.common.Status.RUNNING if there is no data yet + fail_if_bad_comparison: bool = true # py_trees.common.Status.FAILURE instead of py_trees.common.Status.RUNNING if comparison failed + clearing_policy: clearing_policy = clearing_policy!on_initialise # when to clear the data + +action topic_to_blackboard: + topic_name: string # name of the topic to connect to + topic_type: string # class of the message type (e.g. std_msgs.msg.String) + qos_profile: qos_preset_profiles = qos_preset_profiles!system_default # qos profile for the subscriber + blackboard_variables: string # blackboard variable string or dict (names (keys) - message subfields (values)), use a value of None to indicate the entire message + initialise_variables: string = '{}' # initialise the blackboard variables to some defaults + clearing_policy: clearing_policy = clearing_policy!on_initialise # when to clear the data + +action event_to_blackboard: + topic_name: string # name of the topic to connect to + qos_profile: qos_preset_profiles = qos_preset_profiles!system_default # qos profile for the subscriber + variable_name: string # name of the variable to check + +action topic_from_blackboard: + topic_name: string # name of the topic to connect to + topic_type: string # class of the message type (e.g. std_msgs.msg.String) + qos_profile: qos_preset_profiles = qos_preset_profiles!system_default # qos profile for the publisher + blackboard_variable: string # name of the variable on the blackboard (can be nested) + +action service_call: + service_name: string # name of the service to connect to + service_type: string # class of the message type (e.g. std_srvs.msg.Empty) + data: string # call content + +action wait_for_blackboard_variable: + variable_name: string # name of the service to connect to + +action set_blackboard_variable: + variable_name: string # name of the blackboard variable + variable_value: string # value of the variable to set + +action unset_blackboard_variable: + key: string # name of the blackboard variable + +action topic_publish: + topic_name: string # name of the topic to connect to + topic_type: string # class of the message type (e.g. std_msgs.msg.String) + qos_profile: qos_preset_profiles = qos_preset_profiles!system_default # qos profile for the subscriber + value: string # value of the published topic + +action set_node_parameter: + node_name: string # name of the node + parameter_name: string # name of the parameter + parameter_value: string # new value of the parameter + +action record_bag: + # Record a dataset + destination_dir: string = '' # If destination dir is empty, the current directory is used + topics: list of topics + timestamp_suffix: bool = true# Add a timestamp suffix to output directory name + hidden_topics: bool = false # whether to record hidden topics + storage: string = '' # storage type to use (empty string: use default) + +action log_check: + # Check the log for specific output + values: list of string # string to check for. If found, action succeeds + +action differential_drive_robot.init_nav2: + initial_pose: pose_3d + base_frame_id: string = 'base_link' + use_initial_pose: bool = true # if false, no initial_pose is needed (useful when using slam instead of amcl for localization) + namespace_override: string = '' # if set, it's used as namespace (instead of the associated actor's name) + wait_for_initial_pose: bool = false # if true the initial pose needs to be set externally (e.g. manually through rviz) + +action differential_drive_robot.nav_to_pose: + goal_pose: pose_3d + namespace_override: string = '' # if set, it's used as namespace (instead of the associated actor's name) + action_topic: string = 'navigate_to_pose' # Name of action + monitor_progress: bool = true # if yes, the action returns after the goal is reached or on failure. If no, the action returns after request. + +action differential_drive_robot.nav_through_poses: + goal_poses: list of pose_3d + namespace_override: string = '' # if set, it's used as namespace (instead of the associated actor's name) + monitor_progress: bool = true # if yes, the action returns after the goal is reached or on failure. If no, the action returns after request. + +action differential_drive_robot.tf_close_to: + namespace_override: string = '' # if set, it's used as namespace (instead of the associated actor's name) + reference_point: position_3d # z is not considered + threshold: length + sim: bool = false # in simulation, we need to look up the transform map --> base_link at a different time as the scenario execution node is not allowed to use the sim time + robot_frame_id: string = 'base_link' # defines the TF frame id of the robot + +action differential_drive_robot.odometry_distance_traveled: + namespace: string = '' + distance: length diff --git a/scenario_execution/scenario_execution/logging_ros.py b/scenario_execution/scenario_execution/logging_ros.py new file mode 100644 index 00000000..88f67278 --- /dev/null +++ b/scenario_execution/scenario_execution/logging_ros.py @@ -0,0 +1,69 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Logger Class for ROS""" + +import rclpy +from scenario_execution_base.utils.logging import BaseLogger + + +class RosLogger(BaseLogger): + """ + Class for logger for ROS scenario execution + + Args: + name [str]: name of the logger + """ + + def __init__(self, name: str): + super().__init__(name) + self.logger = rclpy.logging.get_logger(name) + + def info(self, msg: str): + """ + Log info in ROS2 + + Args: + msg [str]: msg to print + """ + self.logger.info(msg) + + def debug(self, msg: str): + """ + Log debug info in ROS2 + + Args: + msg [str]: msg to print + """ + self.logger.debug(msg) + + def warning(self, msg: str): + """ + Log warning in ROS2 + + Args: + msg [str]: msg to print + """ + self.logger.warning(msg) + + def error(self, msg: str): + """ + Log error in ROS2 + + Args: + msg [str]: msg to print + """ + self.logger.error(msg) diff --git a/scenario_execution/scenario_execution/marker_handler.py b/scenario_execution/scenario_execution/marker_handler.py new file mode 100644 index 00000000..dcf14432 --- /dev/null +++ b/scenario_execution/scenario_execution/marker_handler.py @@ -0,0 +1,60 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Marker handler""" + +from visualization_msgs.msg import Marker + + +class MarkerHandler(object): + """ + Class for managing markers + + Args: + name [str]: name of the logger + """ + + def __init__(self, node): + self.node = node + self.markers = [] + self.marker_publisher = self.node.create_publisher(Marker, '/scenario_marker', 5) + + def add_marker(self, marker: Marker): + marker.header.frame_id = 'map' + marker.action = marker.ADD + self.markers.append(marker) + + self.marker_publisher.publish(marker) + + return self.markers.index(marker) + + def get_marker(self, marker_id): + return self.markers[marker_id] + + def remove_markers(self, marker_id_list): + for marker_id in marker_id_list: + if marker_id is not None and marker_id < len(self.markers): + marker = self.markers[marker_id] + marker.action = marker.DELETE + self.marker_publisher.publish(marker) + + def update_marker(self, marker_id, marker): + self.markers[marker_id] = marker + self.markers[marker_id].id = marker_id + self.markers[marker_id].header.frame_id = 'map' + self.markers[marker_id].action = marker.MODIFY + + self.marker_publisher.publish(self.markers[marker_id]) diff --git a/scenario_execution/scenario_execution/scenario_execution_ros.py b/scenario_execution/scenario_execution/scenario_execution_ros.py new file mode 100644 index 00000000..04cfec7b --- /dev/null +++ b/scenario_execution/scenario_execution/scenario_execution_ros.py @@ -0,0 +1,158 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Main entry for scenario_execution_ros """ +import sys +from datetime import datetime +import rclpy # pylint: disable=import-error +import py_trees_ros # pylint: disable=import-error +from scenario_execution_base import ScenarioExecution +from .logging_ros import RosLogger +from .marker_handler import MarkerHandler + + +class ROSScenarioExecution(ScenarioExecution): + """ + Class for scenario execution using ROS2 as middleware + """ + + def __init__(self) -> None: + self.node = rclpy.create_node(node_name="scenario_execution") + + # parse from commandline + args_without_ros = rclpy.utilities.remove_ros_args(sys.argv[1:]) + args = ScenarioExecution.parse_args(args_without_ros) + debug = args.debug + log_model = args.log_model + live_tree = args.live_tree + scenario = args.scenario + test_output = args.test_output + + # override commandline by ros parameters + self.node.declare_parameter('debug', False) + self.node.declare_parameter('log_model', False) + self.node.declare_parameter('live_tree', False) + self.node.declare_parameter('test_output', "") + self.node.declare_parameter('scenario', "") + + if self.node.get_parameter('debug').value: + debug = self.node.get_parameter('debug').value + if self.node.get_parameter('log_model').value: + log_model = self.node.get_parameter('log_model').value + if self.node.get_parameter('live_tree').value: + live_tree = self.node.get_parameter('live_tree').value + if self.node.get_parameter('scenario').value: + scenario = self.node.get_parameter('scenario').value + if self.node.get_parameter('test_output').value: + test_output = self.node.get_parameter('test_output').value + super().__init__(debug=debug, log_model=log_model, live_tree=live_tree, scenario=scenario, test_output=test_output) + + def _get_logger(self): + """ + Get a logger from ROS2 with name "scenario_execution" + Overriden parent class method + """ + return RosLogger('scenario_execution') + + def setup_behaviour_tree(self, tree): + """ + Setup the behaviour tree + Using py_trees_ros to get a node handle on ROS2 and tick in syn with ROS2 + + Args: + tree [py_trees.behaviour.Behaviour]: root of the behaviour tree + + return: + py_trees_ros.trees.BehaviourTree + """ + return py_trees_ros.trees.BehaviourTree(tree) + + def run(self) -> bool: + """ + Setup behaviour tree and run ROS node + + return: + True if all scenarios are executed successfully + """ + executor = rclpy.executors.MultiThreadedExecutor() + marker_handler = MarkerHandler(self.node) + executor.add_node(self.node) + + if not self.scenarios: + self.logger.info("No scenarios to execute.") + + failure = False + for tree in self.scenarios: + self.logger.info(f"Executing scenario '{tree.name}'") + start = datetime.now() + if not tree: + self.logger.error(f'Scenario {tree.name} has no executables.') + failure = True + continue + + result = self.setup(tree, node=self.node, marker_handler=marker_handler) + if not result: + failure = True + + if result: + self.behaviour_tree.tick_tock(period_ms=1000. * self.tick_tock_period) + + # Spin ROS node + while rclpy.ok() and not self.shutdown_requested: + try: + # rclpy.spin_once(self.behaviour_tree.node) + executor.spin_once() + except KeyboardInterrupt: + self.blackboard.fail = True + break + + self.behaviour_tree.interrupt() + failure = failure or self.blackboard.fail + result = not self.blackboard.fail + if result: + self.logger.info(f"Scenario '{tree.name}' succeeded.") + else: + self.logger.error(f"Scenario '{tree.name}' failed.") + self.logger.error(self.last_snapshot_visitor.last_snapshot) + + self.add_result((tree.name, self.blackboard.fail, "execution failed", + self.last_snapshot_visitor.last_snapshot, datetime.now() - start)) + self.cleanup_behaviours(tree) + self.behaviour_tree.shutdown() + + return not failure + + +def main(): + """ + main function + """ + rclpy.init(args=sys.argv) + ros_scenario_execution = ROSScenarioExecution() + result = ros_scenario_execution.parse() + + if result: + result = ros_scenario_execution.run() + rclpy.shutdown() + ros_scenario_execution.report_results() + if result: + sys.exit(0) + else: + sys.exit(1) + + +if __name__ == '__main__': + main() diff --git a/scenario_execution/scenarios/test/test_ros_service_call.osc b/scenario_execution/scenarios/test/test_ros_service_call.osc new file mode 100644 index 00000000..b68007c7 --- /dev/null +++ b/scenario_execution/scenarios/test/test_ros_service_call.osc @@ -0,0 +1,14 @@ +import osc.ros + +scenario test_ros_service_call: + do parallel: + test: serial: + service_call() with: + keep(it.service_name == '/bla') + keep(it.service_type == 'std_srvs.srv.SetBool') + keep(it.data == '{\"data\": True}') + wait elapsed(2s) + emit_arrival: emit end + time_out: serial: + wait_for_30s: wait elapsed(30s) + time_out_shutdown: emit fail diff --git a/scenario_execution/scenarios/test/test_ros_service_call_blocking.osc b/scenario_execution/scenarios/test/test_ros_service_call_blocking.osc new file mode 100644 index 00000000..64e54412 --- /dev/null +++ b/scenario_execution/scenarios/test/test_ros_service_call_blocking.osc @@ -0,0 +1,74 @@ +import osc.ros + +scenario test_ros_service_call_blocking: + do parallel: + test: serial: + service_call() with: + keep(it.service_name == '/bla_service') + keep(it.service_type == 'std_srvs.srv.SetBool') + keep(it.data == '{\"data\": True}') + wait elapsed(10s) + emit end + test2: serial: + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 0}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 1}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 2}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 3}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 4}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 5}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 6}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 7}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 8}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 9}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 10}') + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Int32') + keep(it.value == '{\"data\": 11}') + time_out: serial: + wait_for_30s: wait elapsed(30s) + time_out_shutdown: emit fail diff --git a/scenario_execution/scenarios/test/test_ros_set_node_parameter.osc b/scenario_execution/scenarios/test/test_ros_set_node_parameter.osc new file mode 100644 index 00000000..e9b621d3 --- /dev/null +++ b/scenario_execution/scenarios/test/test_ros_set_node_parameter.osc @@ -0,0 +1,18 @@ +import osc.ros + +scenario test_ros_set_node_parameter: + do parallel: + test: serial: + set_node_parameter() with: + keep(it.node_name == '/test_node') + keep(it.parameter_name == 'testFloatParam') + keep(it.parameter_value == '3.14') + second_call: set_node_parameter() with: + keep(it.node_name == '/test_node') + keep(it.parameter_name == 'testBoolParam') + keep(it.parameter_value == 'True') + wait elapsed(3s) + emit end + time_out: serial: + wait elapsed(10s) + time_out_shutdown: emit fail diff --git a/scenario_execution/scenarios/test/test_ros_topic_check_data.osc b/scenario_execution/scenarios/test/test_ros_topic_check_data.osc new file mode 100644 index 00000000..2a3c0038 --- /dev/null +++ b/scenario_execution/scenarios/test/test_ros_topic_check_data.osc @@ -0,0 +1,16 @@ +import osc.ros + +scenario test_ros_topic_check_data: + do parallel: + test: serial: + check_data() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.String') + keep(it.clearing_policy == on_initialise) + keep(it.variable_name == 'data') + keep(it.expected_value == 'hallo') + keep(it.comparison_operator == eq) + emit_arrival: emit end + time_out: serial: + wait_for_30s: wait elapsed(30s) + time_out_shutdown: emit fail diff --git a/scenario_execution/scenarios/test/test_ros_topic_publish.osc b/scenario_execution/scenarios/test/test_ros_topic_publish.osc new file mode 100644 index 00000000..d7eede99 --- /dev/null +++ b/scenario_execution/scenarios/test/test_ros_topic_publish.osc @@ -0,0 +1,13 @@ +import osc.ros + +scenario test_ros_topic_publish: + do parallel: + test: serial: + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Bool') + keep(it.value == '{\"data\": True}') + emit end + time_out: serial: + wait elapsed(10s) + emit fail diff --git a/scenario_execution/scenarios/test/test_ros_topic_wait_for_data.osc b/scenario_execution/scenarios/test/test_ros_topic_wait_for_data.osc new file mode 100644 index 00000000..6d58058c --- /dev/null +++ b/scenario_execution/scenarios/test/test_ros_topic_wait_for_data.osc @@ -0,0 +1,13 @@ +import osc.ros + +scenario test_ros_topic_wait_for_data: + do parallel: + test: serial: + wait_for_data() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Empty') + keep(it.clearing_policy == on_initialise) + emit_arrival: emit end + time_out: serial: + wait_for_30s: wait elapsed(30s) + time_out_shutdown: emit fail diff --git a/scenario_execution/setup.cfg b/scenario_execution/setup.cfg new file mode 100644 index 00000000..f0a819ee --- /dev/null +++ b/scenario_execution/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/scenario_execution +[install] +install_scripts=$base/lib/scenario_execution diff --git a/scenario_execution/setup.py b/scenario_execution/setup.py new file mode 100644 index 00000000..21ca4314 --- /dev/null +++ b/scenario_execution/setup.py @@ -0,0 +1,69 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Setup python package """ +from glob import glob +import os +from setuptools import find_packages, setup + +PACKAGE_NAME = 'scenario_execution' + +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=find_packages(), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'scenarios'), glob('scenarios/*.osc')), + (os.path.join('share', PACKAGE_NAME, 'scenarios', 'test'), glob('scenarios/test/*osc')), + (os.path.join('share', PACKAGE_NAME, 'launch'), glob('launch/*launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Scenario Execution for ROS', + license='Apache License 2.0', + tests_require=['pytest'], + include_package_data=True, + entry_points={ + 'console_scripts': [ + 'scenario_execution = scenario_execution.scenario_execution_ros:main', + ], + 'scenario_execution.actions': [ + 'differential_drive_robot.init_nav2 = scenario_execution.actions.init_nav2:InitNav2', + 'differential_drive_robot.nav_to_pose = scenario_execution.actions.nav_to_pose:NavToPose', + 'differential_drive_robot.nav_through_poses = scenario_execution.actions.nav_through_poses:NavThroughPoses', + 'wait_for_data = scenario_execution.actions.ros_topic_wait_for_data:RosTopicWaitForData', + 'check_data = scenario_execution.actions.ros_topic_check_data:RosTopicCheckData', + 'service_call = scenario_execution.actions.ros_service_call:RosServiceCall', + 'topic_publish = scenario_execution.actions.ros_topic_publish:RosTopicPublish', + 'odometry_distance_traveled = ' + 'scenario_execution.actions.odometry_distance_traveled:OdometryDistanceTraveled', + 'set_node_parameter = scenario_execution.actions.ros_set_node_parameter:RosSetNodeParameter', + 'record_bag = scenario_execution.actions.ros_bag_record:RosBagRecord', + 'wait_for_topics = scenario_execution.actions.ros_topic_wait_for_topics:RosTopicWaitForTopics', + 'log_check = scenario_execution.actions.ros_log_check:RosLogCheck', + 'differential_drive_robot.tf_close_to = scenario_execution.actions.tf_close_to:TfCloseTo', + ], + 'scenario_execution.osc_libraries': [ + 'ros = ' + 'scenario_execution.get_osc_library:get_ros_library', + ] + }, +) diff --git a/scenario_execution/test/test_ros_publish_receive.py b/scenario_execution/test/test_ros_publish_receive.py new file mode 100644 index 00000000..b32515c8 --- /dev/null +++ b/scenario_execution/test/test_ros_publish_receive.py @@ -0,0 +1,72 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import unittest +import rclpy +from scenario_execution import ROSScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestScenarioExectionSuccess(unittest.TestCase): + # pylint: disable=missing-function-docstring + + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ROSScenarioExecution() + + def test_success(self): + scenario_content = """ +import osc.ros + +scenario test_ros_topic_publish: + do serial: + parallel: + test: serial: + wait elapsed(1s) + topic_publish() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Bool') + keep(it.value == '{\\\"data\\\": True}') + receive: serial: + wait_for_data() with: + keep(it.topic_name == '/bla') + keep(it.topic_type == 'std_msgs.msg.Bool') + keep(it.clearing_policy == clearing_policy!on_initialise) + emit end + time_out: serial: + wait elapsed(10s) + emit fail +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) diff --git a/scenario_execution/test/test_ros_service_call.py b/scenario_execution/test/test_ros_service_call.py new file mode 100644 index 00000000..e6733846 --- /dev/null +++ b/scenario_execution/test/test_ros_service_call.py @@ -0,0 +1,71 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import unittest +import rclpy +import threading +from scenario_execution import ROSScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from ament_index_python.packages import get_package_share_directory + +from std_srvs.srv import SetBool + +os.environ["PYTHONUNBUFFERED"] = '1' + + +class TestScenarioExectionSuccess(unittest.TestCase): + # pylint: disable=missing-function-docstring + + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self): + self.request_received = None + self.node = rclpy.create_node('test_node') + + self.executor = rclpy.executors.MultiThreadedExecutor() + self.executor.add_node(self.node) + self.executor_thread = threading.Thread(target=self.executor.spin, daemon=True) + self.executor_thread.start() + + self.scenario_dir = get_package_share_directory('scenario_execution') + + self.srv = self.node.create_service(SetBool, "/bla", self.service_callback) + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ROSScenarioExecution() + + def tearDown(self): + self.node.destroy_node() + + def service_callback(self, msg, response): + self.request_received = msg.data + return response + + def test_success(self): + scenarios = self.parser.process_file(os.path.join( + self.scenario_dir, 'scenarios', 'test', 'test_ros_service_call.osc'), False) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) + self.assertTrue(self.request_received) diff --git a/scenario_execution/test/test_ros_service_call_blocking.py b/scenario_execution/test/test_ros_service_call_blocking.py new file mode 100644 index 00000000..f2a85e86 --- /dev/null +++ b/scenario_execution/test/test_ros_service_call_blocking.py @@ -0,0 +1,98 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +import os +import time +import unittest +import rclpy +import threading +from scenario_execution import ROSScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from ament_index_python.packages import get_package_share_directory + +from std_srvs.srv import SetBool +from std_msgs.msg import Int32 + +os.environ["PYTHONUNBUFFERED"] = '1' + + +class TestScenarioExectionSuccess(unittest.TestCase): + # pylint: disable=missing-function-docstring + + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self): + self.received_msgs = [] + self.node = rclpy.create_node('test_node') + + self.executor = rclpy.executors.MultiThreadedExecutor() + self.executor.add_node(self.node) + self.executor_thread = threading.Thread(target=self.executor.spin, daemon=True) + self.executor_thread.start() + + self.callback_group = rclpy.callback_groups.ReentrantCallbackGroup() + self.srv = self.node.create_service( + SetBool, "/bla_service", self.service_callback, callback_group=self.callback_group) + self.sub = self.node.create_subscription( + Int32, "/bla", self.topic_callback, 10, callback_group=self.callback_group) + + self.scenario_dir = get_package_share_directory('scenario_execution') + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ROSScenarioExecution() + + def tearDown(self): + self.node.destroy_node() + + def service_callback(self, msg, response): + self.assertTrue(msg.data, "Invalid request received") + current_time = self.node.get_clock().now() + end_time = current_time + rclpy.duration.Duration(seconds=5) + while current_time <= end_time: + time.sleep(0.1) + current_time = self.node.get_clock().now() + return response + + def topic_callback(self, msg): + current_time = self.node.get_clock().now() + # print(f"Received {msg}") + # if self.received_msgs: + # print(f"Since last: {current_time - self.received_msgs[-1][0]}") + self.received_msgs.append((current_time, msg)) + + def test_success(self): + scenarios = self.parser.process_file(os.path.join( + self.scenario_dir, 'scenarios', 'test', 'test_ros_service_call_blocking.osc'), False) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) + + self.assertGreater(len(self.received_msgs), 0) + prev_elem = self.received_msgs[0] + for elem in self.received_msgs[1:]: + self.assertGreater(elem[1].data, prev_elem[1].data) + time_since_last = elem[0]-prev_elem[0] + self.assertGreaterEqual(time_since_last, rclpy.duration.Duration(seconds=0.8)) + self.assertLessEqual(time_since_last, rclpy.duration.Duration(seconds=1.6)) + prev_elem = elem diff --git a/scenario_execution/test/test_ros_set_node_parameter.py b/scenario_execution/test/test_ros_set_node_parameter.py new file mode 100644 index 00000000..84a61961 --- /dev/null +++ b/scenario_execution/test/test_ros_set_node_parameter.py @@ -0,0 +1,81 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Test for spawn and exists """ +import os +import unittest +import threading + +from ament_index_python.packages import get_package_share_directory + +import rclpy +from rcl_interfaces.msg import SetParametersResult + +from scenario_execution import ROSScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger + + +class TestRosSetNodeParameter(unittest.TestCase): + # pylint: disable=missing-function-docstring,missing-class-docstring + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self): + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ROSScenarioExecution() + self.scenario_dir = get_package_share_directory('scenario_execution') + + self.node = rclpy.create_node('test_node') + self.node.declare_parameter('testBoolParam', False) + self.node.declare_parameter('testFloatParam', 0.) + self.bool_value = self.node.get_parameter('testBoolParam').value + self.float_value = self.node.get_parameter('testFloatParam').value + self.node.add_on_set_parameters_callback(self.callback) + # self.srv = self.node.create_service(SetBool, "/bla", self.service_callback) + + self.executor = rclpy.executors.MultiThreadedExecutor() + self.executor.add_node(self.node) + self.executor_thread = threading.Thread(target=self.executor.spin, daemon=True) + self.executor_thread.start() + + def tearDown(self): + self.node.destroy_node() + + def callback(self, params): + print(f"set_parameters callback called.") + for param in params: + print(f" {param.name}: {param.value}") + if param.name == "testBoolParam": + self.bool_value = param.value + if param.name == "testFloatParam": + self.float_value = param.value + return SetParametersResult(successful=True) + + def test_success(self): + scenarios = self.parser.process_file(os.path.join( + self.scenario_dir, 'scenarios', 'test', 'test_ros_set_node_parameter.osc'), False) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) + self.assertTrue(self.bool_value) + self.assertEqual(self.float_value, 3.14) diff --git a/scenario_execution/test/test_ros_topic_publish.py b/scenario_execution/test/test_ros_topic_publish.py new file mode 100644 index 00000000..b72cffe2 --- /dev/null +++ b/scenario_execution/test/test_ros_topic_publish.py @@ -0,0 +1,69 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import unittest +import threading + +from ament_index_python.packages import get_package_share_directory + +import rclpy +from std_msgs.msg import Bool + +from scenario_execution import ROSScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger + + +class TestRosTopicPublish(unittest.TestCase): + # pylint: disable=missing-function-docstring,missing-class-docstring + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ROSScenarioExecution() + + self.scenario_dir = get_package_share_directory('scenario_execution') + + self.received_msgs = [] + self.node = rclpy.create_node('test_node') + self.srv = self.node.create_subscription(Bool, "/bla", self.callback, 10) + + self.executor = rclpy.executors.MultiThreadedExecutor() + self.executor.add_node(self.node) + self.executor_thread = threading.Thread(target=self.executor.spin, daemon=True) + self.executor_thread.start() + + def tearDown(self): + self.node.destroy_node() + + def callback(self, msg): + self.received_msgs.append(msg) + + def test_success(self): + scenarios = self.parser.process_file(os.path.join( + self.scenario_dir, 'scenarios', 'test', 'test_ros_topic_publish.osc'), False) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) + self.assertEqual(len(self.received_msgs), 1) diff --git a/scenario_execution_base/MANIFEST.in b/scenario_execution_base/MANIFEST.in new file mode 100644 index 00000000..f597b803 --- /dev/null +++ b/scenario_execution_base/MANIFEST.in @@ -0,0 +1 @@ +include scenario_execution_base/lib_osc/*.osc \ No newline at end of file diff --git a/scenario_execution_base/README.md b/scenario_execution_base/README.md new file mode 100644 index 00000000..83da6452 --- /dev/null +++ b/scenario_execution_base/README.md @@ -0,0 +1,11 @@ +# Scenario Execution Base Package + +The `scenario_execution_base` package is the base package for scenario execution. It provides functionalities like parsing, py-trees creation and execution. + +It provides the following scenario execution libraries: + +- `standard.osc`: The OpenSCENARIO 2 standard library. It is slightly modified to be in sync with the feature set of scenario execution. For convenience, numerical struct members are initialized with 0. +- `robotics.osc`: robotic-specific specifications +- `helper.osc`: helper actions +- `networking.osc`: actions related to networking + diff --git a/scenario_execution_base/package.xml b/scenario_execution_base/package.xml new file mode 100644 index 00000000..d6f65b08 --- /dev/null +++ b/scenario_execution_base/package.xml @@ -0,0 +1,21 @@ + + + + scenario_execution_base + 1.0.0 + Robotics Scenario Execution + Intel Labs + Intel Labs + Apache-2.0 + + py_trees + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/scenario_execution_base/resource/scenario_execution_base b/scenario_execution_base/resource/scenario_execution_base new file mode 100644 index 00000000..e69de29b diff --git a/scenario_execution_base/scenario_execution_base/__init__.py b/scenario_execution_base/scenario_execution_base/__init__.py new file mode 100644 index 00000000..bbdeabb5 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/__init__.py @@ -0,0 +1,30 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from . import actions +from . import utils +from . import model +from scenario_execution_base.scenario_execution import ScenarioExecution +from scenario_execution_base.utils.logging import BaseLogger, Logger + +__all__ = [ + 'actions', + 'utils', + 'model', + 'BaseLogger', + "Logger", + 'ScenarioExecution' +] diff --git a/scenario_execution_base/scenario_execution_base/actions/__init__.py b/scenario_execution_base/scenario_execution_base/actions/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/actions/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_base/scenario_execution_base/actions/log.py b/scenario_execution_base/scenario_execution_base/actions/log.py new file mode 100644 index 00000000..1dc82761 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/actions/log.py @@ -0,0 +1,54 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import py_trees +from py_trees.common import Status + + +class Log(py_trees.behaviour.Behaviour): + """ + Class for logging + + Args: + msg [str]: message to log + """ + + def __init__(self, name, msg: str): + super().__init__(name) + self.msg = msg + self.published = False + self.logger = None + + def setup(self, **kwargs) -> None: + """ + setup before ticking + + Args: + kwargs: arguments passed from py_trees.behaviour.Behaviour + """ + self.logger = kwargs['logger'] + + def update(self) -> py_trees.common.Status: + """ + execute the action + + return: + py_trees.common.Status.SUCCESS if the action is executed + """ + if not self.published: + self.published = True + self.logger.info(self.msg) + return Status.SUCCESS diff --git a/scenario_execution_base/scenario_execution_base/actions/run_external_process.py b/scenario_execution_base/scenario_execution_base/actions/run_external_process.py new file mode 100644 index 00000000..fcac0673 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/actions/run_external_process.py @@ -0,0 +1,135 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import py_trees # pylint: disable=import-error +import subprocess # nosec B404 +from threading import Thread +from collections import deque + + +class RunExternalProcess(py_trees.behaviour.Behaviour): + """ + Class to execute an external process. It finishes when the process finishes + + Args: + command[str]: external command to execute + """ + + def __init__(self, name, command=None): + super().__init__(name) + self.command = command + self.executed = False + self.process = None + self.log_stdout_thread = None + self.log_stderr_thread = None + self.output = deque() + + def update(self) -> py_trees.common.Status: + """ + Start/monitor external process + + return: + py_trees.common.Status + """ + if not self.executed: + self.executed = True + try: + self.process = subprocess.Popen( + self.command, stdout=subprocess.PIPE, stderr=subprocess.PIPE) + except Exception as e: # pylint: disable=broad-except + self.logger.error(str(e)) + return py_trees.common.Status.FAILURE + + self.feedback_message = f"Executing '{self.command}'" # pylint: disable= attribute-defined-outside-init + self.on_executed() + + def log_output(out, log_fct, buffer): + try: + for line in iter(out.readline, b''): + msg = line.decode().strip() + if log_fct: + log_fct(msg) + buffer.append(msg) + out.close() + except ValueError: + pass + + self.log_stdout_thread = Thread(target=log_output, args=( + self.process.stdout, self.get_logger_stdout(), self.output)) + self.log_stdout_thread.daemon = True # die with the program + self.log_stdout_thread.start() + + self.log_stderr_thread = Thread(target=log_output, args=( + self.process.stderr, self.get_logger_stderr(), self.output)) + self.log_stderr_thread.daemon = True # die with the program + self.log_stderr_thread.start() + + if self.process is None: + return py_trees.common.Status.FAILURE + + ret = self.process.poll() + + if ret is None: + return self.check_running_process() + else: + return self.on_process_finished(ret) + + def get_logger_stdout(self): + """ + get logger for stderr messages + """ + return self.logger.info + + def get_logger_stderr(self): + """ + get logger for stderr messages + """ + return self.logger.error + + def check_running_process(self): + """ + hook to check running process + + return: + py_trees.common.Status + """ + return py_trees.common.Status.RUNNING + + def on_process_finished(self, ret): + """ + hook to check finished process + + return: + py_trees.common.Status + """ + if ret == 0: + self.feedback_message = f"Successfully executed '{self.command}'" # pylint: disable= attribute-defined-outside-init + return py_trees.common.Status.SUCCESS + else: + self.feedback_message = f"Execution of '{self.command}' failed with {ret}" # pylint: disable= attribute-defined-outside-init + return py_trees.common.Status.FAILURE + + def on_executed(self): + """ + hook for subclassed + """ + pass + + def set_command(self, command): + self.command = command + + def get_command(self): + return self.command diff --git a/scenario_execution_base/scenario_execution_base/get_osc_library.py b/scenario_execution_base/scenario_execution_base/get_osc_library.py new file mode 100644 index 00000000..17179c3c --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/get_osc_library.py @@ -0,0 +1,26 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +def get_robotics_library(): + return 'scenario_execution_base', 'robotics.osc' + + +def get_helpers_library(): + return 'scenario_execution_base', 'helpers.osc' + + +def get_standard_library(): + return 'scenario_execution_base', 'standard.osc' diff --git a/scenario_execution_base/scenario_execution_base/lib_osc/helpers.osc b/scenario_execution_base/scenario_execution_base/lib_osc/helpers.osc new file mode 100644 index 00000000..c57fbae5 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/lib_osc/helpers.osc @@ -0,0 +1,8 @@ + +action log: + # Print out a message + msg: string # Message to print + +action run_external_process: + # Run an external process + command: string # Command to execute diff --git a/scenario_execution_base/scenario_execution_base/lib_osc/robotics.osc b/scenario_execution_base/scenario_execution_base/lib_osc/robotics.osc new file mode 100644 index 00000000..b55b38e1 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/lib_osc/robotics.osc @@ -0,0 +1,4 @@ +import osc.standard + +actor differential_drive_robot inherits osc_actor: + namespace: string = '' diff --git a/scenario_execution_base/scenario_execution_base/lib_osc/standard.osc b/scenario_execution_base/scenario_execution_base/lib_osc/standard.osc new file mode 100644 index 00000000..52d1cb94 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/lib_osc/standard.osc @@ -0,0 +1,1227 @@ +########### +# Standard: OpenSCENARIO 2.0 domain model +# Copyright: ASAM 2021-2022 +# Version: +# Standard Publication Date: +# Publication Reference Document: +# Reference Document Date: +########### + +# ATTENTION: This file is modified to be compatible with +# the feature set of scenario execution. + +######################## +# Scalar types and units +######################## + +# tag::library-physical-length[] +type length is SI(m: 1) +unit nanometer of length is SI(m: 1, factor: 0.000000001) +unit nm of length is SI(m: 1, factor: 0.000000001) +unit micrometer of length is SI(m: 1, factor: 0.000001) +unit millimeter of length is SI(m: 1, factor: 0.001) +unit mm of length is SI(m: 1, factor: 0.001) +unit centimeter of length is SI(m: 1, factor: 0.01) +unit cm of length is SI(m: 1, factor: 0.01) +unit meter of length is SI(m: 1, factor: 1) +unit m of length is SI(m: 1, factor: 1) +unit kilometer of length is SI(m: 1, factor: 1000) +unit km of length is SI(m: 1, factor: 1000) +unit inch of length is SI(m: 1, factor: 0.0254) +unit feet of length is SI(m: 1, factor: 0.3048) +unit mile of length is SI(m: 1, factor: 1609.344) +unit mi of length is SI(m: 1, factor: 1609.344) +# end::library-physical-length[] + +# tag::library-physical-time[] +type time is SI(s: 1) +unit millisecond of time is SI(s: 1, factor: 0.001) +unit ms of time is SI(s: 1, factor: 0.001) +unit second of time is SI(s: 1, factor: 1) +unit sec of time is SI(s: 1, factor: 1) +unit s of time is SI(s: 1, factor: 1) +unit minute of time is SI(s: 1, factor: 60) +unit min of time is SI(s: 1, factor: 60) +unit hour of time is SI(s: 1, factor: 3600) +unit h of time is SI(s: 1, factor: 3600) +# end::library-physical-time[] + +# tag::library-physical-speed[] +type speed is SI(m: 1, s: -1) +unit meter_per_second of speed is SI(m: 1, s: -1, factor: 1) +unit mps of speed is SI(m: 1, s: -1, factor: 1) +unit kilometer_per_hour of speed is SI(m: 1, s: -1, factor: 0.277777778) +unit kmph of speed is SI(m: 1, s: -1, factor: 0.277777778) +unit kph of speed is SI(m: 1, s: -1, factor: 0.277777778) +unit mile_per_hour of speed is SI(m: 1, s: -1, factor: 0.447038889) +unit mph of speed is SI(m: 1, s: -1, factor: 0.447038889) +unit miph of speed is SI(m: 1, s: -1, factor: 0.447038889) +unit mmph of speed is SI(m: 1, s: -1, factor: 0.000000278) +unit millimeter_per_hour of speed is SI(m: 1, s: -1, factor: 0.000000278) +# end::library-physical-speed[] + +# tag::library-physical-acceleration[] +type acceleration is SI(m: 1, s: -2) +unit meter_per_sec_sqr of acceleration is SI(m: 1, s: -2, factor: 1) +unit mpsps of acceleration is SI(m: 1, s: -2, factor: 1) +unit mpss of acceleration is SI(m: 1, s: -2, factor: 1) +unit kilometer_per_hour_per_sec of acceleration is SI(m: 1, s: -2, factor: 0.277777778) +unit kmphps of acceleration is SI(m: 1, s: -2, factor: 0.277777778) +unit mile_per_hour_per_sec of acceleration is SI(m: 1, s: -2, factor: 0.447038889) +unit miphps of acceleration is SI(m: 1, s: -2, factor: 0.447038889) +# end::library-physical-acceleration[] + +# tag::library-physical-jerk[] +type jerk is SI(m: 1, s: -3) +unit meter_per_sec_cubed of jerk is SI(m: 1, s: -3, factor: 1) +unit mpspsps of jerk is SI(m: 1, s: -3, factor: 1) +unit mile_per_sec_cubed of jerk is SI(m: 1, s: -3, factor: 1609.344) +unit mipspsps of jerk is SI(m: 1, s: -3, factor: 1609.344) +# end::library-physical-jerk[] + +# tag::library-physical-angle[] +type angle is SI(rad: 1) +unit degree of angle is SI(rad: 1, factor: 57.295779513) +unit deg of angle is SI(rad: 1, factor: 57.295779513) +unit radian of angle is SI(rad: 1, factor: 1) +unit rad of angle is SI(rad: 1, factor: 1) +# end::library-physical-angle[] + +# tag::library-physical-angular_rate[] +type angular_rate is SI(rad: 1, s: -1) +unit degree_per_sec of angular_rate is SI(rad: 1, s: -1, factor: 57.295779513) +unit degps of angular_rate is SI(rad: 1, s: -1, factor: 57.295779513) +unit radian_per_sec of angular_rate is SI(rad: 1, s: -1, factor: 1) +unit radps of angular_rate is SI(rad: 1, s: -1, factor: 1) +# end::library-physical-angular_rate[] + +# tag::library-physical-angular_acceleration[] +type angular_acceleration is SI(rad: 1, s: -2) +unit degree_per_sec_sqr of angular_acceleration is SI(rad: 1, s: -2, factor: 57.295779513) +unit degpsps of angular_acceleration is SI(rad: 1, s: -2, factor: 57.295779513) +unit radian_per_sec_sqr of angular_acceleration is SI(rad: 1, s: -2, factor: 1) +unit radpsps of angular_acceleration is SI(rad: 1, s: -2, factor: 1) +# end::library-physical-angular_acceleration[] + +# tag::library-physical-mass[] +type mass is SI(kg: 1) +unit gram of mass is SI(kg: 1, factor: 0.001) +unit kilogram of mass is SI(kg: 1, factor: 1) +unit kg of mass is SI(kg: 1, factor: 1) +unit ton of mass is SI(kg: 1, factor: 1000) +unit pound of mass is SI(kg: 1, factor: 0.45359237) +unit lb of mass is SI(kg: 1, factor: 0.45359237) +# end::library-physical-mass[] + +# tag::library-physical-temperature[] +type temperature is SI(K: 1) +unit K of temperature is SI(K: 1, factor: 1) +unit kelvin of temperature is SI(K: 1, factor: 1) +unit celsius of temperature is SI(K: 1, factor: 1, offset: 273.15) +unit C of temperature is SI(K: 1, factor: 1, offset: 273.15) +unit fahrenheit of temperature is SI(K: 1, factor: 0.555555556, offset: 255.372222222) +unit F of temperature is SI(K: 1, factor: 0.555555556, offset: 255.372222222) +# end::library-physical-temperature[] + +# tag::library-physical-pressure[] +type pressure is SI(kg: 1, m: -1, s: -2) +unit newton_per_meter_sqr of pressure is SI(kg: 1, m: -1, s: -2, factor: 1) +unit Pa of pressure is SI(kg: 1, m: -1, s: -2, factor: 1) +unit pascal of pressure is SI(kg: 1, m: -1, s: -2, factor: 1) +unit hPa of pressure is SI(kg: 1, m: -1, s: -2, factor: 100) +unit atm of pressure is SI(kg: 1, m: -1, s: -2, factor: 101325) +# end::library-physical-pressure[] + +# tag::library-physical-luminous_intensity[] +type luminous_intensity is SI(cd: 1) +unit cd of luminous_intensity is SI(cd: 1, factor: 1) +unit candela of luminous_intensity is SI(cd: 1, factor: 1) +# end::library-physical-luminous_intensity[] + +# tag::library-physical-luminous_flux[] +type luminous_flux is SI(cd: 1, rad: 2) +unit lm of luminous_flux is SI(cd: 1, rad: 2, factor: 1) +unit lumen of luminous_flux is SI(cd: 1, rad: 2, factor: 1) +# end::library-physical-luminous_flux[] + +# tag::library-physical-illuminance[] +type illuminance is SI(cd: 1, rad: 2, m: -2) +unit lx of illuminance is SI(cd: 1, rad: 2, m: -2, factor: 1) +unit lux of illuminance is SI(cd: 1, rad: 2, m: -2, factor: 1) +# end::library-physical-illuminance[] + +# tag::library-physical-electrical_current[] +type electrical_current is SI(A: 1) +unit ampere of electrical_current is SI(A: 1, factor: 1) +unit A of electrical_current is SI(A: 1, factor: 1) +# end::library-physical-electrical_current[] + +# tag::library-physical-amount_of_substance[] +type amount_of_substance is SI(mol: 1) +unit mole of amount_of_substance is SI(mol: 1, factor: 1) +unit mol of amount_of_substance is SI(mol: 1, factor: 1) +# end::library-physical-amount_of_substance[] + +########### +# Structs +########### + +# tag::library-position_3d[] +struct position_3d: + x: length = 0.0m + y: length = 0.0m + z: length = 0.0m + #def norm() -> length is undefined +# end::library-position_3d[] + +# tag::library-celestial_position_2d[] +struct celestial_position_2d: + azimuth: angle = 0.0rad + elevation: angle = 0.0rad +# end::library-celestial_position_2d[] + +# tag::library-geodetic_position_2d[] +struct geodetic_position_2d: + latitude: angle = 0.0rad + longitude: angle = 0.0rad +# end::library-geodetic_position_2d[] + +# tag::library-orientation_3d[] +struct orientation_3d: + roll: angle = 0.0rad + pitch: angle = 0.0rad + yaw: angle = 0.0rad +# end::library-orientation_3d[] + +# tag::library-pose_3d[] +struct pose_3d: + position: position_3d + orientation: orientation_3d +# end::library-pose_3d[] + +# tag::library-translational_velocity_3d[] +struct translational_velocity_3d: + x: speed = 0.0mps + y: speed = 0.0mps + z: speed = 0.0mps +# def norm() -> speed is undefined +# end::library-translational_velocity_3d[] + +# tag::library-orientation_rate_3d[] +struct orientation_rate_3d: + roll: angular_rate = 0.0radps + pitch: angular_rate = 0.0radps + yaw: angular_rate = 0.0radps +# end::library-orientation_rate_3d[] + +# tag::library-velocity_6d[] +struct velocity_6d: + translational: translational_velocity_3d + angular: orientation_rate_3d +# end::library-velocity_6d[] + +# tag::library-translational_acceleration_3d[] +struct translational_acceleration_3d: + x: acceleration = 0.0mpsps + y: acceleration = 0.0mpsps + z: acceleration = 0.0mpsps +# def norm() -> acceleration is undefined +# end::library-translational_acceleration_3d[] + +# tag::library-orientation_acceleration_3d[] +struct orientation_acceleration_3d: + roll: angular_acceleration = 0.0radpsps + pitch: angular_acceleration = 0.0radpsps + yaw: angular_acceleration = 0.0radpsps +# end::library-orientation_acceleration_3d[] + +# tag::library-acceleration_6d[] +struct acceleration_6d: + translational: translational_acceleration_3d + angular: orientation_acceleration_3d +# end::library-acceleration_6d[] + +struct axle: + max_steering: angle # Mandatory: Maximum steering angle for the wheels on the axle. + wheel_diameter: length # Mandatory: Diameter for the wheels on this axle + track_width: length # Mandatory: Distance between the centerline of the outer wheels on opposing sides of the axle + position_x: length # Mandatory: Longitudinal position of the axle in the x-axis of the vehicle. For a 2-axle vehicle, the rear axle must have position_x = 0m + position_z: length # Mandatory: Vertical position of the axle in the vehicle's z-axis + number_of_wheels: uint # Mandatory: Number of wheels on the axle. + +struct bounding_box: + center: position_3d # Mandatory: Represents the geometrical center of the bounding box expressed in coordinates that refer to the coordinate system of the physical_object + length: length # Mandatory: Dimension in x-direction of the coordinate system of the physical_object + width: length # Mandatory: Dimension in y-direction of the coordinate system of the physical_object + height: length # Mandatory: Dimension in z-direction of the coordinate system of the physical_object + +struct crossing_type: + marking: crossing_marking # Optional: Define the type of markings on the crossing + use: crossing_use # Optional: Define the type of use for the crossing + elevation: crossing_elevation # Optional: Define the type of elevation for the crossing + + +######################### +# MODIFICATION: type definition must be done before usage +######################### + +enum path_interpolation: [ + straight_line, # Join the points with straight lines + smooth] # Join the points with a smooth line + +struct route: # Object of map + length: length # Optional: Nominal length of the route, measured along the s-axis of the route. Does not apply to route_point + directionality: directionality # Mandatory: Directionality for movement of traffic_participant actors on the route + min_lanes: uint # Optional: Minimum number of drivable lanes along this route. Applies only to these children: road, lane_section + max_lanes: uint # Optional: Maximum number of drivable lanes along this route. Applies only to these children: road, lane_section + anchors: list of string # Optional: The strings in here can be matched to unique items in the map files specified in file_name +# def start_point() -> route_point is undefined +# def end_point() -> route_point is undefined + +struct route_point inherits route_element: + route: route # Mandatory: route in which this point is located + #s: length = 0.0m # Optional: Coordinate along the s-axis of the corresponding route #TODO: s gets misinterpreted + t: length = 0.0m # Optional: Coordinate along the t-axis of the corresponding route + +struct xyz_point inherits route_element: + position: position_3d # Optional: Position in Cartesian (xyz) coordinates + +struct odr_point inherits route_element: + road_id: string # Mandatory: ASAM OpenDRIVE identifier for the road + lane_id: string # Optional: ASAM OpenDRIVE identifier for the lane. If specified, the t-coordinate is measured from the lane centerline. If not specified, the t-coordinate is measured from the ASAM OpenDRIVE reference line +# s: length = 0.0m # Optional: Coordinate along the ASAM OpenDRIVE s-axis + t: length = 0.0m # Optional: Coordinate along the ASAM OpenDRIVE t-axis + +# tag::library-path[] +struct path inherits route: + points: list of pose_3d # Mandatory: List of points in world x-y-z-coordinates. The individual pose_3d elements can have unconstrained coordinates. + interpolation: path_interpolation # Mandatory: Choose how to join the points of the path. + +struct relative_path: + interpolation: path_interpolation # Mandatory: Choose how to join the points of the path. + +struct relative_path_pose_3d inherits relative_path: + points: list of pose_3d # Mandatory: List of points in world x-y-z-coordinates. The individual pose_3d elements can have unconstrained coordinates. + +struct relative_path_st inherits relative_path: + points: list of route_point # Mandatory: Sequence of route_point that form the relative path + +struct relative_path_odr inherits relative_path: + points: list of odr_point # Mandatory: Sequence of odr_point that form the relative path +# end::library-path[] + +# tag::library-trajectory[] +struct trajectory: + points: list of pose_3d # Mandatory: List of points in world x-y-z-coordinates. The individual pose_3d elements can have unconstrained coordinates. + time_stamps: list of time # Mandatory: Time stamps for each element in points. The lists time_stamps and points must have the same length + interpolation: path_interpolation # Mandatory: Choose how to join the points of the trajectory. + +struct relative_trajectory: + time_stamps: list of time # Mandatory: Time stamps for each element in points. The lists time_stamps and points must have the same length + interpolation: path_interpolation # Mandatory: Choose how to join the points of the trajectory. + +struct relative_trajectory_pose_3d inherits relative_trajectory: + points: list of pose_3d # Mandatory: List of points in world x-y-z-coordinates. The individual pose_3d elements can have unconstrained coordinates. + +struct relative_trajectory_st inherits relative_trajectory: + points: list of route_point # Mandatory: Sequence of route_point that form the relative trajectory + +struct relative_trajectory_odr inherits relative_trajectory: + points: list of odr_point # Mandatory: Sequence of odr_point that form the relative trajectory +# end::library-trajectory[] + +# tag::library-shape-any[] +struct any_shape +# def duration() -> time is undefined + +struct any_acceleration_shape inherits any_shape +# def compute(time: time) -> acceleration is undefined + +struct any_speed_shape inherits any_shape +# def compute(time: time) -> speed is undefined + +struct any_position_shape inherits any_shape +# def compute(time: time) -> length is undefined + +struct any_lateral_shape inherits any_shape +# def compute(time: time) -> length is undefined +# end::library-shape-any[] + +# tag::library-shape-common[] +struct common_acceleration_shape inherits any_acceleration_shape: + rate_profile: dynamic_profile + rate_peak: jerk = 0.0mpspsps + target: acceleration = 0.0mpsps + +struct common_speed_shape inherits any_speed_shape: + rate_profile: dynamic_profile + rate_peak: acceleration = 0.0mpsps + target: speed = 0.0mps + +struct common_position_shape inherits any_position_shape: + rate_profile: dynamic_profile + rate_peak: speed = 0.0mps + target: length = 0.0m + +struct common_lateral_shape inherits any_lateral_shape: + rate_profile: dynamic_profile + rate_peak: speed = 0.0mps + target: length = 0.0m +# end::library-shape-common[] + +struct bm_engine # Reference to an object representing the bm_engine, whose content is implementation-dependent. + # Fields to be defined by the user or implementation + +struct behavioral_model: + bm_engine: bm_engine # Reference to the "behavioral model engine" + +########### +# Enums +########### + +enum color: [ + white, # RGB(255,255,255) + silver, # RGB(192,192,192) + gray, # RGB(128,128,128) + black, # RGB(0,0,0) + red, # RGB(255,0,0) + maroon, # RGB(128,0,0) + yellow, # RGB(255,255,0) + olive, # RGB(128,128,0) + lime, # RGB(0,255,0) + green, # RGB(0,128,0) + aqua, # RGB(0,255,255) + teal, # RGB(0,128,128) + blue, # RGB(0,0,255) + navy, # RGB(0,0,128) + fuchsia, # RGB(255,255,0) + purple] # RGB(255,0,255) + +enum intended_infrastructure: [ + driving, # OpenDRIVE: "normal" drivable road, which is not one of the other types + sidewalk, # OpenDRIVE: Lane on which pedestrians can walk safely + biking, # OpenDRIVE: Lane reserved for Cyclists + rail, # OpenDRIVE: Lane reserved for trains + tram, # OpenDRIVE: Lane reserved for trams + bus, # OpenDRIVE: Lane reserved for bus + taxi, # OpenDRIVE: Lane reserved for taxi + hov] # OpenDRIVE: Lane reserved for High Occupancy Vehicles (HOV) + +enum vehicle_category: [ + car, # Power-driven vehicle with maximum mass not exceeding 3.5 t having at least four wheels comprising not more than eight seats in addition to the driver seat. (UN category L7,M1,N1) + bus, # Power-driven vehicle having at least four wheels comprising more than eight seats in addition to the driver seat.(UN category M2,M3) + truck, # Power-driven vehicle with maximum mass exceeding 3.5t having at least four wheels. Designed for the carriage of goods. (UN category N2,N3) + trailer, # Vehicle designed to be towed by another vehicle. Non-permanently connected to towing vehicle, meaning it can be separated by an operation without involving facilities normally only found in workshop. + vru_vehicle, # Vehicle without a crash-resistant passenger cell intended for one to few passengers or small goods transport. With its occupant it results in a vulnerable road user. (UN category L1-L6 plus bicycles, pedelecs, e-bicycles, personal mobility devices, wheelchairs, mobility scooters and so on.) + other] # Unspecified but known type of vehicle (for example, stroller, shopping cart, etc) + +enum driving_rule: [ + left_hand_traffic, # Traffic drives on the left side of the road + right_hand_traffic] # Traffic drives on the right side of the road + +enum directionality: [ + uni_direction, # A traffic_participant can move legally in only one direction along the s-axis. + longitudinal, # Usually applies to lane_type driving and vru_vehicles + bi_direction, # A traffic_participant can move legally in both directions along the longitudinal s-axis. Usually applies to lane_type driving and vru_vehicles + split, # Applies for multi-lane elements: there are lanes with opposing uni_direction traffic flow within the route + free, # A traffic_participant can legally move in any direction (longitudinal or lateral). Usually applies to lane_type pedestrian or lane_use mix_traffic_vru + none, # No expected traffic flow. Usually applies to lane_type non_driving + other] # Other type of directionality + +enum lane_type: [ + driving, # Driving lane for road vehicles. See the driving_lane_use subtype + non_driving, # Non-driving lanes in road vehicles infrastructure. See the non_driving_lane_use subtype + vru_vehicles, # Lanes designated for VRU vehicles. See the vru_vehicles_lane_use subtype + pedestrian, # Lanes for pedestrians. See the pedestrian_lane_use subtype + other] # If the lane has another type + +enum lane_use: [ + normal, # A normal driving lane for road vehicles (OSI). Should be used in combination with lane_type == driving. + exit, # A deceleration lane in parallel to the main road (OSI). Should be used in combination with lane_type == driving. + entry, # An acceleration lane in parallel to the main road (OSI). Should be used in combination with lane_type == driving. + on_ramp, # A ramp from rural or urban roads joining a motorway (OSI). Should be used in combination with lane_type == driving. + off_ramp, # A ramp leading off a motorway onto rural or urban roads (OSI). Should be used in combination with lane_type == driving. + connecting_ramp, # A ramp that connects two motorways (OSI). Should be used in combination with lane_type == driving. + hov, # A lane for High Occupancy Vehicles (HOV), usually in highways. Should be used in combination with lane_type == driving. + bus, # A lane restricted for use only by busses. Should be used in combination with lane_type == driving. + mixed_traffic_vru, # A lane for mixed car and vru (vehicle and pedestrian) traffic, normally in urban areas. Should be used in combination with lane_type == driving or vru_vehicles. + parking, # A lane with parking spaces (OSI). Should be used in combination with lane_type == non_driving. + stop, # A hard shoulder on motorways for emergency stops (OSI). Should be used in combination with lane_type == non_driving. + restricted, # A lane on which road vehicles should not drive (OSI). Should be used in combination with lane_type == non_driving. + border, # A hard border on the edge of a road (OSI). Should be used in combination with lane_type == non_driving. + shoulder, # A soft border on the edge of a road (OSI). Should be used in combination with lane_type == non_driving. + curb, # An elevated surface with different height compared to the drivable lanes. Should be used in combination with lane_type == non_driving. + median, # An inaccessible lane for road vehicles and pedestrians. Typically used to separate the traffic. Should be used in combination with lane_type == non_driving. + bicycle, # A lane that is designated for bicycles (OSI). Should be used in combination with lane_type == vru_vehicles. + motorcycle, # A lane that is designated for motorcycles. Should be used in combination with lane_type == vru_vehicles. + sidewalk, # A lane that is designated for pedestrians (OSI). Should be used in combination with lane_type == pedestrian. + protected_sidewalk, # A lane for pedestrians with a barrier to separate it from road traffic. Should be used in combination with lane_type == pedestrian. + none, # The lane has no use. + other] # The lane has another use. + +enum side_left_right: [ + left, + right] + +enum crossing_marking: [ # Has connection to crossing_type + unmarked, # No crossing-markings on the road + marked, # The road or walking surface has markings that indicate a crossing + zebra, # Common type of marked crossing with thick zebra stripes + other] # Other type of markings for the crossing + +enum crossing_use: [ # Has connection to crossing_type + pedestrian, # Crossing is used by pedestrians (person, animal) and/or vehicles that usually move on sidewalks (wheelchair, stroller) + animal, # Animal crossing. For example, on a rural road or highway + bicycle, # Crossing for bicycles + rail_road, # Crossing for rail vehicles (train, subway, tram, ...) + other] # Other use for crossing + +enum crossing_elevation: [ + road_level, # Crossing is at same level as driving surface + curb_level, # Crossing is elevated from driving surface, often at the same level as a walking surface (sidewalk) or curb + refuge_island, # Along the crossing, the elevation may change between road and curb levels. For example, with refuge island(s) in the middle + other] # Another elevation type + +enum junction_direction: [ + straight, # The out_road is 0deg relative to the in_road + right, # The out_road is 90deg relative to the in_road + u_turn, # The out_road is 180deg relative to the in_road + left, # The out_road is 270deg relative to the in_road + other] # If none of the above apply + +enum route_overlap_kind: [ + equal, # Both routes have the same length, and coincide at the start and end points + start, # Both routes coincide at their start points + end, # Both routes coincide at their end points + inside, # The first route is fully inside the second route. Their start and end points do not have to coincide + any, # Any part of the first route overlaps with any part of the second route + other] # If none of the above apply + +enum lateral_overlap_kind: [ + never, # The two routes never overlap laterally. They never share a common lane. + sometimes, # In some segments of the route, the two routes can share a common lane. + always ] # The always routes share a common lane. + +enum dynamic_profile: [ + none, # No specific dynamic profile + constant, # Use constant first derivative + smooth, # Use smooth first derivative + asap] # Reach value as soon as possible + +enum lane_change_side: [ + left, # Lane to the left of the reference entity + right, # Lane to the right of the reference entity + inside, # Lane to the inside of the reference entity + outside, # Lane to the outside of the reference entity + same] # Same lane as the reference entity + +enum gap_direction: [ + ahead, # Gap in the positive direction of the s-axis, with respect to the reference entity + behind, # Gap in the negative direction of the s-axis, with respect to the reference entity + left, # Gap in the positive direction of the t-axis, with respect to the reference entity + right, # Gap in the negative direction of the t-axis, with respect to the reference entity + inside, # Gap in the direction pointing towards opposing traffic + outside] # Gap in the direction pointing away from opposing traffic + +enum headway_direction: [ + ahead, # Headway in the positive direction of the s-axis, with respect to the reference entity + behind] # Headway in the negative direction of the s-axis, with respect to the reference entity + +enum lat_measure_by: [ + left_to_left, + left_to_center, + left_to_right, + center_to_left, + center_to_right, + right_to_left, + right_to_center, + right_to_right, + closest] + +enum yaw_measure_by: [ + length_to_length, + length_to_width, + width_to_length, + width_to_width, + relative_to_north, + relative_to_road] + +enum orientation_measured_by: [ + absolute, + relative_to_reference, + relative_to_road] + +enum movement_options: [ + prefer_physical, # Perform the movement physical if possible + prefer_non_physical, # Perform the non physical way if the implementation allows that. For example, a test track may ignore this request. + must_be_physical] # An error message is issued, if this action cannot be physically performed for any reason. + +enum connect_route_points: [ + road, # Use the road element that contains this point + lane_section, # Use the lane_section element that contains this point + lane, # Use the lane element that contains this point + crossing, # Use the crossing element that contains this point + waypoint] # Use the point itself. The route must pass exactly through this point + +enum at: [ + start, + end, + all] + +enum movement_mode: [ + monotonous, # This movement mode adheres to the laws of physics. On top of that it limits the level of surprise that a movement may have. + other] # Not necessarily monotonous. This is the default. + +enum track: [ + actual, # Actual or projected. The default is actual, meaning that the vehicle reacts to the behavior of the referenced vehicle. + projected] # + +enum distance_direction: [ + longitudinal, # Measure distance in the x-coordinate. Positive means that the `reference` is in front of the `physical_object` that calls the method. + lateral] # Measure distance in the y-coordinate. Positive means that the `reference` is to the left of the `physical_object` that calls the method. + +enum distance_mode: [ + reference_points, # Measures the distance between the reference points. + bounding_boxes] # Measures the distance between the bounding boxes. + +enum relative_transform: [ + world_relative, + object_relative, + road_relative, + lane_relative +] + +enum on_route_type: [ on_road, on_lane_section, on_lane, on_crossing ] + +enum route_distance_enum: [ from_start, from_end ] + +########### +# Actor +########### + +actor osc_actor + +actor physical_object inherits osc_actor: + bounding_box: bounding_box # Mandatory: See bounding_box struct + color: color # Optional: See color enum + geometry_reference: string # Optional: Opaque reference of an associated 3D geometry model of the physical object. It is implementation-specific how model references are resolved to 3D models. + center_of_gravity: position_3d # Mandatory: Center of gravity of the object. If unknown, the center of the bounding box may be used instead. + var pose: pose_3d # Position and orientation measured in world coordinates with world system as reference. +# def object_distance(reference: physical_object, direction: distance_direction, mode: distance_mode = reference_points) -> length is undefined +# def get_s_coord(route_type: on_route_type = on_road) -> length is undefined +# def get_t_coord(route_type: on_route_type= on_road) -> length is undefined +# def get_route_point(route_type: on_route_type = on_road) -> route_point is undefined + +actor stationary_object inherits physical_object + +actor movable_object inherits physical_object: +# def distance_along_route(route: route, from: route_distance_enum = from_start) -> length is undefined + var velocity: velocity_6d # Mandatory: Translational and rotational velocity measured in object coordinates with world system as reference. + var acceleration: acceleration_6d # Mandatory: Translational and rotational acceleration measured in object coordinates with world system as reference. + var speed: speed # Mandatory: Speed in center_of_gravity defined as sqrt(velocity.translational.x^2 + velocity.translational.y^2) * sign(velocity.translational.x) + +actor traffic_participant inherits movable_object: + intended_infrastructure: list of intended_infrastructure # Mandatory: See intended_infrastructure for definition. Intended usage is for further specification of an entity. For example, together with vehicle_category or to provide hints for implemenations where to spawn and / or auto-route entities. Note that multiple types of infrastructure can be assigned because of the list character of this type. +# def time_to_collision(reference: physical_object) -> time is undefined +# def time_headway(reference: physical_object) -> time is undefined +# def space_gap(reference: physical_object, direction: distance_direction) -> length is undefined + +actor vehicle inherits traffic_participant: + vehicle_category: vehicle_category # Mandatory: See vehicle_category + axles: list of axle # Mandatory: See axle + rear_overhang: length # Mandatory: Rear overhang of the vehicle or more explicitly the horizontal distance between the end of the bounding_box and the center of the rear axle. + +actor person inherits traffic_participant + +actor animal inherits traffic_participant + +########### +# environment (an Actor) +########### +struct weather: + air: air # Optional: See struct air + rain: precipitation # Optional: Liquid water in form of droplets falling under gravity. + snow: precipitation # Optional: Frozen water in delicately-crystalline flakes falling under gravity. + wind: wind # Optional: See struct wind + fog: fog # Optional: See struct fog + clouds: clouds # Optional: See struct clouds + +actor environment inherits osc_actor: + geodetic_position: geodetic_position_2d # Optional: Geodetic position of world coordinate frame regarding WGS84. Regarding usage for determination of angle of celestial light sources see remark above. + datetime: time # Optional: Date and time at start of scenario as Unix time, i.e. Number of seconds that have elapsed since January 1, 1970 (midnight UTC/GMT), not counting leap seconds. Regarding usage for determination of angle of celestial light sources see remark above. + var weather: weather # Optional: See struct weather + sun: celestial_light_source # Optional: Sun as instance of celestial_light_source. + moon: celestial_light_source # Optional: Moon as instance of celestial_light_source. +# def local_to_unix_time(year: uint, month: uint, day: uint, hour: uint, minute: uint, second: uint, time_zone: float) -> time is undefined + +struct air: + temperature: temperature = 25.0celsius # Optional: Temperature on ground level. + atmospheric_pressure: pressure = 101325pascal # Optional: Atmospheric pressure on ground level. + relative_humidity: float = 0.0 # Optional: Relative humidity on ground level. + +struct precipitation: + intensity: speed = 0.0mps # Optional: Global intensity of precipitation given as volumetric flux. In case of (partially) solid precipitation, the equivalent melted volume shall be considered. Note that volumetric flux is describing a volume flow across an area, but after reduction the unit results in the same unit as for speeds. As of now it is not possible in + +struct wind: + speed: speed # Mandatory: The expected value of wind speed. To estimate the expected value, rolling mean value over a specific short interval (for example, 3s) can be used. + direction: angle # Mandatory: The origin direction of the wind (not target direction) in the ground/x-y-plane with clockwise increasing values to match common definitions. This results in 0 deg for a wind blowing from the North 90 deg for a wind blowing from the East 90 deg, if x-axis and y-axis are mapped to East and North. + +struct fog: + visual_range: length # Mandatory: Value of optical range of visible light in the standard setting, which corresponds to a certain density of fog. + +struct clouds: + cloudiness: uint # Mandatory: Using okta scale to define which portion of the sky is covered with clouds. Ranging from 0 for completely clear sky to 8 for a completely overcast sky. Values above 8 shall not be used. + +struct celestial_light_source: + var position: celestial_position_2d # Mandatory: Position of the light source, see definition of physical type celestial_position_2d. + +########### +# Map (an Actor) +########### + +actor map inherits osc_actor: + map_file: string + routes: list of route + junctions: list of junction + driving_rule: driving_rule +# def odr_to_route_point(road_id: string, lane_id: string, s: length, t: length) -> route_point is undefined +# def xyz_to_route_point(x: length, y: length, z: length) -> route_point is undefined +# def route_point_to_xyz(route_point: route_point) -> xyz_point is undefined +# def outer_side() -> side_left_right is undefined +# def inner_side() -> side_left_right is undefined +# def create_route(routes: list of route, connect_points_by: connect_route_points, legal_route: bool) -> compound_route is undefined +# def create_route_point(route: route, s: length, t: length) -> route_point is undefined +# def create_xyz_point(x: length, y: length, z: length) -> xyz_point is undefined +# def create_odr_point(road_id: string, lane_id: string, s: length, t: length) -> odr_point is undefined +# def create_path(points: list of pose_3d, interpolation: path_interpolation) -> path is undefined +# def create_path_odr_points(points: list of odr_point, interpolation: path_interpolation, on_road_network: bool) -> path is undefined +# def create_path_route_points(points: list of route_point, interpolation: path_interpolation, on_road_network: bool) -> path is undefined +# def create_trajectory(points: list of pose_3d, time_stamps: list of time,interpolation: path_interpolation) -> trajectory is undefined +# def create_trajectory_odr_points(points: list of odr_point, time_stamps: list of time, interpolation: path_interpolation, on_road_network: bool) -> trajectory is undefined +# def create_trajectory_route_points(points: list of route_point, time_stamps: list of time, interpolation: path_interpolation, on_road_network: bool) -> trajectory is undefined +# def resolve_relative_path(relative_path: relative_path, reference: physical_object, transform: relative_transform) -> path is undefined +# def resolve_relative_trajectory(relative_trajectory: relative_trajectory, reference: physical_object, transform: relative_transform) -> trajectory is undefined +# def get_map_file() -> string is undefined #from map.map_file + +struct route: # Object of map + length: length # Optional: Nominal length of the route, measured along the s-axis of the route. Does not apply to route_point + directionality: directionality # Mandatory: Directionality for movement of traffic_participant actors on the route + min_lanes: uint # Optional: Minimum number of drivable lanes along this route. Applies only to these children: road, lane_section + max_lanes: uint # Optional: Maximum number of drivable lanes along this route. Applies only to these children: road, lane_section + anchors: list of string # Optional: The strings in here can be matched to unique items in the map files specified in file_name +# def start_point() -> route_point is undefined +# def end_point() -> route_point is undefined + +struct route_element inherits route # Interface Class (of route) + +struct road inherits route_element: + s_positive: list of lane_section # Mandatory: List of lane_section elements that flow in the positive direction of the road s-axis + s_negative: list of lane_section # Optional: List of lane_section elements that flow in the negative direction of the road s-axis + +struct lane_section inherits route_element: + road: road # Mandatory: Where the lane_section resides + lanes: list of lane # Mandatory: List of lanes that compose the lane_section + s_axis: lane # Mandatory: Choose, which lane is used to determine the s-axis of the lane_section. Must be a member of it.lanes + +struct lane inherits route_element: + lane_section: lane_section # Mandatory: Where the lane resides + lane_type: lane_type # Mandatory: Type of lane + lane_use: lane_use # Mandatory: A subtype of the lane_type. Use compatible pairs of lane_type and lane_use + width: length # Optional: Nominal width of the lane + +struct crossing inherits route_element: + start_lane: lane # Mandatory: Crossing starts on this lane + end_lane: lane # Mandatory: Crossing ends on this lane + start_s_coord: length # Mandatory: On the starts_from lane, the crossing connects at this point in the lane s-axis (and zero in the t-axis) + end_s_coord: length # Mandatory: On the ends_on lane, the crossing connects at this point in the lane s-axis (and zero in the t-axis) + width: length # Mandatory: Nominal width of the crossing, measured perpendicular to the crossing s-axis + crossing_type: crossing_type # Mandatory: Type of crossing + +struct junction: + roads: list of road # Mandatory: A list of road + +struct compound_route inherits route: + route_elements: list of route_element # Mandatory: A list of route_element. + +struct compound_lane inherits route: + lanes: list of lane # Mandatory: A list of lane + +########### +# Action - movable_object +########### + +action osc_actor.osc_action + +action movable_object.action_for_movable_object inherits osc_actor.osc_action + +action movable_object.move inherits movable_object.action_for_movable_object + +action movable_object.remain_stationary inherits movable_object.action_for_movable_object + +action movable_object.assign_position inherits movable_object.action_for_movable_object: + position: position_3d # Optional: Desired 3-dimensional position assigned by the user + route_point: route_point # Optional: Desired route_point assigned by the user + odr_point: odr_point # Optional: Desired odr_point assigned by the user + +action movable_object.assign_orientation inherits movable_object.action_for_movable_object: + target: orientation_3d # Mandatory: Desired 3-dimensional orientation assigned by the user + +action movable_object.assign_speed inherits movable_object.action_for_movable_object: + target: speed # Mandatory: Desired (scalar) speed assigned by the user + +action movable_object.assign_acceleration inherits movable_object.action_for_movable_object: + target: acceleration # Mandatory: Desired (scalar) acceleration assigned by the user + +action movable_object.replay_path inherits movable_object.action_for_movable_object: + absolute: path # Mandatory: Absolute path. Includes a list of points + relative: relative_path # Mandatory: Relative path. Includes a list of points +# reference: physical_object with: # Optional: Use with relative paths. Specify the reference entity that defines the origin for the point coordinates. Default: the actor itself +# keep(default it == actor) +# transform: relative_transform with: # Optional: Use with relative paths. Coordinates of the points are relative to the reference entity. Default = object_relative +# keep(default it == object_relative) +# start_offset: length with: # Optional: Offset at which to begin following the path, measured from the path's start. Default = 0m +# keep(default it == 0m) +# end_offset: length with: # Optional: Offset at which to end following the path, measured from the path's end. Default = 0m +# keep(default it == 0m) + +action movable_object.replay_trajectory inherits movable_object.action_for_movable_object: + absolute: trajectory # Mandatory: Absolute trajectory. Includes a list of points and a list of corresponding time stamps + relative: relative_trajectory # Mandatory: Relative trajectory. Includes a list of points and a list of corresponding time stamps +# reference: physical_object with: # Optional: Use with relative trajectories. Specify the reference entity that defines the origin for the point coordinates. Default: the actor itself +# keep(default it == actor) +# transform: relative_transform with: # Optional: Use with relative trajectories. Coordinates of the points are relative to the reference entity. Default = object_relative +# keep(default it == object_relative) +# start_offset: length with: # Optional: Offset at which to begin following the trajectory, measured from the trajectory's start. Default = 0m +# keep(default it == 0m) +# end_offset: length with: # Optional: Offset at which to end following the trajectory, measured from the trajectory's end. Default = 0m +# keep(default it == 0m) + +action movable_object.change_position inherits movable_object.action_for_movable_object: + target: position_3d # Mandatory: Target value for the position at the end of the action + interpolation: path_interpolation # Mandatory: The interpolation method used to join the start and end points + on_road_network: bool # Mandatory: The action takes place completely on the road network of the scenario + +action movable_object.change_speed inherits movable_object.action_for_movable_object: + target: speed # Mandatory: Target value for the speed at the end of the action +# rate_profile: dynamic_profile with: # Optional: Assign a shape for the change of the speed variable. This profile affects the acceleration during action execution +# keep(default it == none) + rate_peak: acceleration = 0.0mpsps # Optional: Target value for the peak acceleration that must be achieved during the action + +# action movable_object.keep_speed inherits movable_object.action_for_movable_object + +action movable_object.change_acceleration inherits movable_object.action_for_movable_object: + target: acceleration # Mandatory: Target value for the scalar acceleration at the end of the action +# rate_profile: dynamic_profile with: # Optional: Assign a shape for the change of the speed variable. This profile affects the jerk during action execution +# keep(default it == none) + rate_peak: jerk = 0.0mpspsps # Optional: Target value for the peak jerk that must be achieved during the action + +action movable_object.keep_acceleration inherits movable_object.action_for_movable_object + +action movable_object.follow_path inherits movable_object.action_for_movable_object: + absolute: path # Mandatory: Absolute path. Includes a list of points + relative: relative_path # Mandatory: Relative path. Includes a list of points +# reference: physical_object with: # Optional: Use with relative paths. Specify the reference entity that defines the origin for the point coordinates. Default: the actor itself +# keep(default it == actor) +# transform: relative_transform with: # Optional: Use with relative paths. Coordinates of the points are relative to the reference entity. Default = object_relative +# keep(default it == object_relative) +# start_offset: length with: # Optional: Offset at which to begin following the path, measured from the path's start. Default = 0m +# keep(default it == 0m) +# end_offset: length with: # Optional: Offset at which to end following the path, measured from the path's end. Default = 0m +# keep(default it == 0m) + +action movable_object.follow_trajectory inherits movable_object.action_for_movable_object: + absolute: trajectory # Mandatory: Absolute trajectory. Includes a list of points and a list of corresponding time stamps + relative: relative_trajectory # Mandatory: Relative trajectory. Includes a list of points and a list of corresponding time stamps +# reference: physical_object with: # Optional: Use with relative trajectories. Specify the reference entity that defines the origin for the point coordinates. Default: the actor itself +# keep(default it == actor) +# transform: relative_transform with: # Optional: Use with relative trajectories. Coordinates of the points are relative to the reference entity. Default = object_relative +# keep(default it == object_relative) +# start_offset: length with: # Optional: Offset at which to begin following the trajectory, measured from the trajectory's start. Default = 0m +# keep(default it == 0m) +# end_offset: length with: # Optional: Offset at which to end following the trajectory, measured from the trajectory's end. Default = 0m +# keep(default it == 0m) + +########### +# Action - vehicle +########### + +action vehicle.action_for_vehicle inherits movable_object.action_for_movable_object + +action vehicle.drive inherits vehicle.action_for_vehicle + +action vehicle.follow_lane inherits vehicle.action_for_vehicle: +# offset: length with: # Optional: Default=0.0. Offset from center of the lane for the actor to follow, using the t-axis of the lane +# keep(default it == 0.0m) +# rate_profile: dynamic_profile with: # Optional: Assign a shape for the change of the lateral position variable (t-axis). This profile affects the lateral velocity during action execution +# keep(default it == none) + rate_peak: speed = 0.0mps # Optional: Target value for the peak lateral velocity that must be achieved during the action + target: lane # Optional: The actor must be in this lane at the start, throughout, and the end of the action. If this argument is ignored, the actor follows the current lane when the action is invoked + +action vehicle.change_lane inherits vehicle.action_for_vehicle: +# num_of_lanes: int with: # Optional: The target lane is "num_of_lanes" to the side of the reference entity. Use in conjunction with "side" +# keep(default it == 1) + side: lane_change_side # Optional: Select on which side of the reference entity +# reference: physical_object with: # Optional: Default=it.actor. Reference to the entity that is used to determine the target lane. If this argument is omitted, the actor itself is used as reference +# keep(default it == actor) +# offset: length with: # Optional: Default=0.0. Target offset from center of the target lane that the actor follows at the end of the action +# keep(default it == 0.0m) +# rate_profile: dynamic_profile with: # Optional: Assign a shape for the change of the lateral position variable (t-axis). This profile affects the lateral velocity during action execution '/ +# keep(default it == none) + rate_peak: speed = 0.0mps # Optional: Target value for the peak lateral velocity that must be achieved during the action + target: lane # Mandatory: The actor starts and finishes the action in the target lane + +action vehicle.change_space_gap inherits vehicle.action_for_vehicle: + target: length # Mandatory: Target distance between the actor and the reference entity. Distance is measured according to the space_gap() method + direction: gap_direction # Mandatory: Placement of the actor with respect to the reference entity. [ahead, behind] means distance is measured in the s-axis. [left, right, inside, outside] means distance is measured in the t-axis + reference: physical_object # Mandatory: The actor reaches the driving distance to this reference entity + +action vehicle.keep_space_gap inherits vehicle.action_for_vehicle: + reference: physical_object # Mandatory: The actor keeps the driving distance to this reference entity + direction: distance_direction # Mandatory: Direction in which the space gap is kept with respect to the reference entity. [longitudinal] to keep distance in the s-axis. [lateral] to keep distance in the t-axis + +action vehicle.change_time_headway inherits vehicle.action_for_vehicle: + target: time # Mandatory: Target time headway between the actor and the reference entity. Time headway is measured according to the time_headway() method + direction: headway_direction # Mandatory: Placement of the actor with respect to the reference entity + reference: physical_object # Mandatory: The actor reaches the time headway to this reference entity + +action vehicle.keep_time_headway inherits vehicle.action_for_vehicle: + reference: physical_object # Mandatory: The actor keeps the driving distance to this reference entity + direction: headway_direction # Mandatory: Direction in which the space gap is kept with respect to the reference entity. [longitudinal] to keep distance in the s-axis. [lateral] to keep distance in the t-axis + +########### +# Action - person +########### + +action person.action_for_person inherits movable_object.action_for_movable_object + +action person.walk inherits person.action_for_person + +########### +# Action - environment +########### + +action environment.action_for_environment inherits osc_actor.osc_action + +action environment.air inherits environment.action_for_environment: + temperature: temperature = 25.0celsius + pressure: pressure = 101325pascal + relative_humidity: float = 0.0 + +action environment.rain inherits environment.action_for_environment: + intensity: speed = 0.0mps + +action environment.snow inherits environment.action_for_environment: + intensity: speed = 0.0mps + +action environment.wind inherits environment.action_for_environment: + speed: speed = 0.0mps + direction: angle = 0.0rad + +action environment.fog inherits environment.action_for_environment: + visual_range: length = 0.0m + +action environment.cloud inherits environment.action_for_environment: + cloudiness: uint = 0 + +action environment.assign_celestial_position inherits environment.action_for_environment: + light_source: celestial_light_source + azimuth: angle + elevation: angle + +##################################### +# Modifier - location based modifiers +##################################### + +# modifier position of movable_object.action_for_movable_object: +# distance: length # Mandatory: A value with a distance unit. +# time: time with: # Mandatory: A value with a time unit. +# keep(default it == 0sec) +# ahead_of, behind: physical_object # Optional: A named instance of the vehicle actor example: example, vehicle2 + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier distance of movable_object.action_for_movable_object: +# distance: length # Mandatory: The distance the actor should travel in the current movement. + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier lane of movable_object.action_for_movable_object: +# lane: uint with: # Mandatory: An integer indicating a required lane for a drive +# keep(default it == 1) +# same_as: physical_object +# side_of: physical_object +# side: side_left_right +# from: side_left_right + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier keep_lane of movable_object.action_for_movable_object: +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier lateral of movable_object.action_for_movable_object: +# distance: length with: # Mandatory: The offset from reference line. The default is [-10.0..10.0]centimeter. +# keep(default it in [-10.0cm..10.0cm]) +# left_of, right_of, same_as, side_of: physical_object # Optional: +# side: side_left_right # Optional: +# measure_by: lat_measure_by with: # Optional: This parameter specifies the measurement start and end points. +# keep(default it == closest) + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier yaw of movable_object.action_for_movable_object: +# angle: angle # Mandatory: A value with an angle unit. This parameter is mandatory +# relative_to: physical_object # Optional: A named instance of the vehicle actor example: example, vehicle2 +# measure_by: yaw_measure_by with: # Optional: Defines reference lines of the context and referenced objects, where width is an x-axis and long is a y-axis. +# keep(default it == relative_to_road) + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier orientation of movable_object.action_for_movable_object: +# yaw: angle # Mandatory: A value with an angle unit. This parameter is mandatory for either yaw, pitch and roll +# pitch: angle # Mandatory: A value with an angle unit. This parameter is mandatory for either yaw, pitch and roll +# roll: angle # Mandatory: A value with an angle unit. This parameter is mandatory for either yaw, pitch and roll +# relative_to: physical_object # Optional: A named instance of the vehicle actor example: example, vehicle2 +# measured_by: orientation_measured_by with: # Optional: defines how to measure the desired orientation. Values include absolute, relative_to_reference, relative_to_road. the default is relative_to_road +# keep(default it == relative_to_road) + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +#modifier along of movable_object.action_for_movable_object: +# route: route # Mandatory: The route to move on. +# start_offset: length with: # Optional: Offset at which to begin following the route, measured from the route's start. Default = 0m +# keep(default it == 0m) +# end_offset: length # Optional: Offset at which to end following the route, measured from the route's end. Default = 0m +# keep(default it == 0m) + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier keep_position of movable_object.action_for_movable_object: +# shape: any_shape # Optional: uses struct any_shape + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) + +#modifier along_trajectory of movable_object.action_for_movable_object: +# trajectory: trajectory # The trajectory to move along. +# start_offset: length with: # Offset at which to begin following the trajectory, measured from the trajectory's start. Default = 0m +# keep(default it == 0m) +# end_offset: length with: # Offset at which to end following the trajectory, measured from the trajectory's end. Default = 0m +# keep(default it == 0m) + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) + +# modifier stationary_object.location: +# pose: pose_3d # Mandatory. Location of the stationary object for the whole scenario. + +########################################### +# Modifier - rate of change based modifiers +########################################### + +# modifier speed of movable_object.action_for_movable_object: +# speed: speed # Mandatory: The vehicle's desired speed. +# faster_than, slower_than, same_as: physical_object # Optional: A named instance of the actor example: example, vehicle2 + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier acceleration of movable_object.action_for_movable_object: +# acceleration: acceleration # A value appended with an acceleration unit. +# faster_than, slower_than, same_as: physical_object # Optional: A named instance of the actor example: example, vehicle2 + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier keep_speed of movable_object.action_for_movable_object: +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier change_speed of movable_object.action_for_movable_object: +# speed: speed # Mandatory: The vehicle's desired speed. + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier physical_movement of movable_object.action_for_movable_object: +# option: movement_options + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier avoid_collisions of movable_object.action_for_movable_object: +# avoid: bool # Mandatory: Either true or false. + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# modifier change_lane of movable_object.action_for_movable_object: +# lane: uint with: +# keep(default it == 1) # Mandatory: The number of lanes to change from. The default is 1. +# side: side_left_right # Optional: Left or right. The side is randomized if not specified. + +# at: at with: # Optional: uses enum at to support: start | end | all (default: all) +# keep(default it == all) +# movement_mode: movement_mode with: # Optional: uses enum movement_mode: monotonous | other (default: other) +# keep(default it == other) +# track: track with: # Optional: uses enum track: actual | projected (default: actual) +# keep(default it == actual) +# shape: any_shape # Optional: uses struct any_shape + +# ################################ +# # Modifier - map based modifiers +# ################################ + +# modifier map.number_of_lanes: +# route: route # Mandatory: The route that has these constraints +# num_of_lanes: uint # Mandatory: The desired number of lanes +# lane_type: lane_type with: # Optional: Apply the constraint to the number of lanes with this type. +# keep(default it == driving) +# lane_use: lane_use with: # Optional: Apply the constraint to the number of lanes with this use. +# keep(default it == normal) +# directionality: directionality with: # Optional: Apply the constraint to the number of lanes with this directionality. +# keep(default it == uni_direction) + +# modifier map.routes_are_in_sequence: +# preceding: route # The first route +# succeeding: route # The second route, which follows after the first route. +# road: road # Optional: The road that will contain this sequence of routes. + +# modifier map.roads_follow_in_junction: +# junction: junction # The junction to be used. +# in_road: road # The chosen road that leads into the junction. +# out_road: road # The chosen road that leads away from the junction. +# direction: junction_direction # Indicates the direction of the out_road relative to the in_road. +# clockwise_count: uint # out_road is clockwise_count roads from in_road, counting clockwise. +# number_of_roads: uint # Total number of in_roads connected to the junction. +# in_lane: lane # The chosen lane within in_road. +# out_lane: lane # The chosen lane within out_road. +# junction_route: route # The element(s) that connect the in_lane or in_road to the out_lane or out_road within the junction. +# resulting_route: route # The route going from in_lane or in_road to the out_lane or out_road. + +# modifier map.routes_overlap: +# route1: route # Mandatory: The first of the overlapping routes. +# route2: route # Mandatory: The second of the overlapping routes. +# overlap_kind: route_overlap_kind # Mandatory: The type of expected overlap. Notice route1 is considered the first route to interpret the values of the enum. + +# modifier map.lane_side: +# lane1: lane # Mandatory: The first lane. +# side: side_left_right # Mandatory: Locate lane1 on this side of lane2. +# lane2: lane # Mandatory: The second lane. +# count: uint # Mandatory: How far is lane1 from lane2? +# lane_section: lane_section # Optional: lane_section where the lanes reside. + +# modifier map.compound_lane_side: +# lane1: compound_lane # Mandatory: The first compound_lane +# side: side_left_right # Mandatory: Locate lane1 on this side of lane2 +# lane2: compound_lane # Mandatory: The second compound_lane +# count: uint # Mandatory: number of from lane1 from lane2 +# route: route # Optional: The route where the compound lanes reside + +# modifier map.end_lane: +# lane: lane # Mandatory: This lane ends in its current lane_section + +# modifier map.start_lane: +# lane: lane # Mandatory: This lane starts in its current lane_section + +# modifier map.crossing_connects: +# crossing: crossing # Mandatory: The crossing that is connected to the specified lanes +# start_lane: lane # Mandatory: The lane where crossing starts (starting from the centerline of the lane) +# end_lane: lane # Mandatory: The destination lane where the crossing ends (ending on the centerline of the lane). +# start_s_coord: length # Mandatory: The crossing origin derived from a s-position along the centerline of start_lane. +# start_angle: angle with: # Optional: The angle at which the straight centerline of the crossing originates from the start lane. Default is perpendicular. +# keep(default it == 90deg) + +# modifier map.routes_are_opposite: +# route1: route # Mandatory: The first uni-directional route. +# route2: route # Mandatory: The second uni-directional route. +# containing_road: road # Mandatory: The road to which both routes belong. +# lateral_overlap: lateral_overlap_kind # Mandatory: Specifies if the routes overlap lateral, meaning they become a single two-way lane. + +# modifier map.set_map_file: +# file: string # Mandatory: The path and file name for the map file. diff --git a/scenario_execution_base/scenario_execution_base/model/__init__.py b/scenario_execution_base/scenario_execution_base/model/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_base/scenario_execution_base/model/error.py b/scenario_execution_base/scenario_execution_base/model/error.py new file mode 100644 index 00000000..3de96a29 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/error.py @@ -0,0 +1,38 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +from antlr4 import ParserRuleContext + + +class OSC2ParsingError(Exception): + """ + Error class for OSC2 parser + """ + + def __init__(self, msg: str, context, *args) -> None: + super().__init__(*args) + self.msg = msg + if isinstance(context, ParserRuleContext): + self.line = context.start.line + self.column = context.start.column + self.context = context.getText() + self.filename = "" + else: + self.line = context[0] + self.column = context[1] + self.context = context[2] + self.filename = context[3] diff --git a/scenario_execution_base/scenario_execution_base/model/model_base_visitor.py b/scenario_execution_base/scenario_execution_base/model/model_base_visitor.py new file mode 100644 index 00000000..d82998fc --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/model_base_visitor.py @@ -0,0 +1,266 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +from .types import ModelElement, CompilationUnit, PhysicalTypeDeclaration, UnitDeclaration, SIBaseExponent, EnumDeclaration, EnumMemberDeclaration, EnumValueReference, InheritsCondition, StructDeclaration, StructInherits, ActionDeclaration, ActionInherits, ActorDeclaration, ActorInherits, FieldAccessExpression, FallExpression, FloatLiteral, FunctionApplicationExpression, Argument, BehaviorInvocation, BinaryExpression, BoolLiteral, CallDirective, CastExpression, CoverDeclaration, DoDirective, ElapsedExpression, ElementAccessExpression, DoMember, EmitDirective, EnumTypeExtension, EventCondition, EventDeclaration, EventFieldDecl, EventReference, EveryExpression, GlobalParameterDeclaration, Identifier, IdentifierReference, IntegerLiteral, KeepConstraintDeclaration, ListExpression, LogicalExpression, MethodBody, MethodDeclaration, ModifierDeclaration, ModifierInvocation, NamedArgument, OnDirective, ParameterDeclaration, PhysicalLiteral, ParameterReference, PositionalArgument, RangeExpression, RelationExpression, RecordDeclaration, RemoveDefaultDeclaration, RiseExpression, SampleExpression, ScenarioInherits, SIUnitSpecifier, StringLiteral, ScenarioDeclaration, StructuredTypeExtension, TernaryExpression, TypeTestExpression, UnaryExpression, Type, UntilDirective, VariableDeclaration, WaitDirective + + +class BaseVisitor(object): + def visit(self, tree): + return tree.accept(self) + + def visit_children(self, node): + result = self.default_result() + n = node.get_child_count() + for i in range(n): + if not self.should_visit_next_child(node, result): + return result + + c = node.get_child(i) + if isinstance(c, ModelElement): + child_result = c.accept(self) + result = self.aggregate_result(result, child_result) + + return result + + def default_result(self): + return [] + + def aggregate_result(self, aggregate, next_result): + if aggregate: + return [aggregate, next_result] + else: + return next_result + + def should_visit_next_child(self, node, current_result): + return True + + +class ModelBaseVisitor(BaseVisitor): # pylint: disable=too-many-public-methods + def visit_compilation_unit(self, node: CompilationUnit): + return self.visit_children(node) + + def visit_physical_type_declaration(self, node: PhysicalTypeDeclaration): + return self.visit_children(node) + + def visit_unit_declaration(self, node: UnitDeclaration): + return self.visit_children(node) + + def visit_si_base_exponent(self, node: SIBaseExponent): + return self.visit_children(node) + + def visit_enum_declaration(self, node: EnumDeclaration): + return self.visit_children(node) + + def visit_enum_member_declaration(self, node: EnumMemberDeclaration): + return self.visit_children(node) + + def visit_enum_value_reference(self, node: EnumValueReference): + return self.visit_children(node) + + def visit_inherits_condition(self, node: InheritsCondition): + return self.visit_children(node) + + def visit_struct_declaration(self, node: StructDeclaration): + return self.visit_children(node) + + def visit_struct_inherits(self, node: StructInherits): + return self.visit_children(node) + + def visit_actor_declaration(self, node: ActorDeclaration): + return self.visit_children(node) + + def visit_actor_inherits(self, node: ActorInherits): + return self.visit_children(node) + + def visit_scenario_declaration(self, node: ScenarioDeclaration): + return self.visit_children(node) + + def visit_scenario_inherits(self, node: ScenarioInherits): + return self.visit_children(node) + + def visit_action_declaration(self, node: ActionDeclaration): + return self.visit_children(node) + + def visit_action_inherits(self, node: ActionInherits): + return self.visit_children(node) + + def visit_modifier_declaration(self, node: ModifierDeclaration): + return self.visit_children(node) + + def visit_enum_type_extension(self, node: EnumTypeExtension): + return self.visit_children(node) + + def visit_structured_type_extension(self, node: StructuredTypeExtension): + return self.visit_children(node) + + def visit_global_parameter_declaration( + self, node: GlobalParameterDeclaration + ): + return self.visit_children(node) + + def visit_parameter_declaration(self, node: ParameterDeclaration): + return self.visit_children(node) + + def visit_parameter_reference(self, node: ParameterReference): + return self.visit_children(node) + + def visit_variable_declaration(self, node: VariableDeclaration): + return self.visit_children(node) + + def visit_event_declaration(self, node: EventDeclaration): + return self.visit_children(node) + + def visit_event_reference(self, node: EventReference): + return self.visit_children(node) + + def visit_event_field_declaration(self, node: EventFieldDecl): + return self.visit_children(node) + + def visit_event_condition(self, node: EventCondition): + return self.visit_children(node) + + def visit_method_declaration(self, node: MethodDeclaration): + return self.visit_children(node) + + def visit_method_body(self, node: MethodBody): + return self.visit_children(node) + + def visit_cover_declaration(self, node: CoverDeclaration): + return self.visit_children(node) + + def visit_record_declaration(self, node: RecordDeclaration): + return self.visit_children(node) + + def visit_argument(self, node: Argument): + return self.visit_children(node) + + def visit_named_argument(self, node: NamedArgument): + return self.visit_children(node) + + def visit_positional_argument(self, node: PositionalArgument): + return self.visit_children(node) + + def visit_keep_constraint_declaration(self, node: KeepConstraintDeclaration): + return self.visit_children(node) + + def visit_remove_default_declaration(self, node: RemoveDefaultDeclaration): + return self.visit_children(node) + + def visit_on_directive(self, node: OnDirective): + return self.visit_children(node) + + def visit_do_directive(self, node: DoDirective): + return self.visit_children(node) + + def visit_do_member(self, node: DoMember): + return self.visit_children(node) + + def visit_wait_directive(self, node: WaitDirective): + return self.visit_children(node) + + def visit_emit_directive(self, node: EmitDirective): + return self.visit_children(node) + + def visit_call_directive(self, node: CallDirective): + return self.visit_children(node) + + def visit_until_directive(self, node: UntilDirective): + return self.visit_children(node) + + def visit_behavior_invocation(self, node: BehaviorInvocation): + return self.visit_children(node) + + def visit_modifier_invocation(self, node: ModifierInvocation): + return self.visit_children(node) + + def visit_rise_expression(self, node: RiseExpression): + return self.visit_children(node) + + def visit_fall_expression(self, node: FallExpression): + return self.visit_children(node) + + def visit_elapsed_expression(self, node: ElapsedExpression): + return self.visit_children(node) + + def visit_every_expression(self, node: EveryExpression): + return self.visit_children(node) + + def visit_sample_expression(self, node: SampleExpression): + return self.visit_children(node) + + def visit_cast_expression(self, node: CastExpression): + return self.visit_children(node) + + def visit_type_test_expression(self, node: TypeTestExpression): + return self.visit_children(node) + + def visit_element_access_expression(self, node: ElementAccessExpression): + return self.visit_children(node) + + def visit_function_application_expression(self, node: FunctionApplicationExpression): + return self.visit_children(node) + + def visit_binary_expression(self, node: BinaryExpression): + return self.visit_children(node) + + def visit_unary_expression(self, node: UnaryExpression): + return self.visit_children(node) + + def visit_ternary_expression(self, node: TernaryExpression): + return self.visit_children(node) + + def visit_list_expression(self, node: ListExpression): + return self.visit_children(node) + + def visit_range_expression(self, node: RangeExpression): + return self.visit_children(node) + + def visit_physical_literal(self, node: PhysicalLiteral): + return self.visit_children(node) + + def visit_integer_literal(self, node: IntegerLiteral): + return self.visit_children(node) + + def visit_float_literal(self, node: FloatLiteral): + return self.visit_children(node) + + def visit_bool_literal(self, node: BoolLiteral): + return self.visit_children(node) + + def visit_string_literal(self, node: StringLiteral): + return self.visit_children(node) + + def visit_type(self, node: Type): + return self.visit_children(node) + + def visit_identifier(self, node: Identifier): + return self.visit_children(node) + + def visit_identifier_reference(self, node: IdentifierReference): + return self.visit_children(node) + + def visit_field_access_expression(self, node: FieldAccessExpression): + return self.visit_children(node) + + def visit_logical_expression(self, node: LogicalExpression): + return self.visit_children(node) + + def visit_si_unit_specifier(self, node: SIUnitSpecifier): + return self.visit_children(node) + + def visit_relation_expression(self, node: RelationExpression): + return self.visit_children(node) diff --git a/scenario_execution_base/scenario_execution_base/model/model_builder.py b/scenario_execution_base/scenario_execution_base/model/model_builder.py new file mode 100644 index 00000000..05ad277e --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/model_builder.py @@ -0,0 +1,1994 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +from .types import CompilationUnit, PhysicalTypeDeclaration, UnitDeclaration, EnumDeclaration, EnumMemberDeclaration, EnumValueReference, StructDeclaration, StructInherits, ActionDeclaration, ActionInherits, ActorDeclaration, ActorInherits, FieldAccessExpression, FloatLiteral, FunctionApplicationExpression, Argument, BehaviorInvocation, BinaryExpression, BoolLiteral, DoDirective, ElapsedExpression, DoMember, EmitDirective, EventCondition, EventDeclaration, EventFieldDecl, EventReference, GlobalParameterDeclaration, Identifier, IdentifierReference, IntegerLiteral, KeepConstraintDeclaration, LogicalExpression, MethodBody, NamedArgument, OnDirective, ParameterDeclaration, PhysicalLiteral, ParameterReference, PositionalArgument, RelationExpression, ScenarioInherits, SIUnitSpecifier, StringLiteral, ScenarioDeclaration, StructuredTypeExtension, Type, VariableDeclaration, WaitDirective, ListExpression + + +from ..osc2_parsing.OpenSCENARIO2Parser import OpenSCENARIO2Parser +from ..osc2_parsing.OpenSCENARIO2Listener import OpenSCENARIO2Listener + +from scenario_execution_base.model.error import OSC2ParsingError +import ast + +from antlr4.tree.Tree import ParseTreeWalker +import os +from pkg_resources import iter_entry_points, resource_filename + + +class ModelBuilder(OpenSCENARIO2Listener): # pylint: disable=too-many-public-methods + + def __init__(self, logger, parse_file_fct, file_name, log_model): + super().__init__() + self.__node_stack = [] + self.__cur_node = None + self.__current_label = None + self.model = None + self.logger = logger + self.imported_files = [] + self.parse_file = parse_file_fct + self.current_file = file_name + self.log_model = log_model + + def get_model(self): + return self.model + + # Enter a parse tree produced by OpenSCENARIO2Parser#osc_file. + def enterOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): + if self.model is None: # only on first file + node = CompilationUnit() + node.set_ctx(ctx, self.current_file) + + self.__node_stack.append(node) + self.__cur_node = node + self.model = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#osc_file. + def exitOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#preludeStatement. + def enterPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#preludeStatement. + def exitPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#importStatement. + def enterImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#importStatement. + def exitImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#importReference. + def enterImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): + file = None + if ctx.StringLiteral(): + file = ctx.getText() + if ctx.structuredIdentifier(): + import_reference = [] + for child in ctx.structuredIdentifier().getChildren(): + import_reference.append(child.getText()) + + self.logger.debug(f'import_reference is: {import_reference}') + if len(import_reference) < 3 or import_reference[0] != 'osc' or import_reference[1] != '.': + raise OSC2ParsingError( + msg=f'import_reference can only be of format osc., found "{import_reference}', context=ctx) + + # iterate through all packages + libraries_found = [] + for entry_point in iter_entry_points(group='scenario_execution.osc_libraries', name=None): + if entry_point.name == import_reference[2]: + libraries_found.append(entry_point) + if not libraries_found: + raise OSC2ParsingError( + msg=f'No import library "{".".join(import_reference)}" found.', context=ctx) + if len(libraries_found) > 1: + pkgs = [] + for elem in libraries_found: + try: + lib_class = elem.load() + resource, _ = lib_class() + pkgs.append(resource) + except ModuleNotFoundError: + pkgs.append('') + pass + + raise OSC2ParsingError( + msg=f'More than one import library for "{".".join(import_reference)}" found: {", ".join(pkgs)}', context=ctx) + + lib_class = libraries_found[0].load() + resource, filename = lib_class() + + lib_osc_dir = resource_filename(resource, 'lib_osc') + file = os.path.join(lib_osc_dir, filename) + + # Skip files that are already imported + if file in self.imported_files: + return + + imported_tree, errors = self.parse_file(file, self.log_model, f"{file} :") + + if errors: + raise OSC2ParsingError(msg=f'{errors} parsing errors found in import {file}.', context=ctx) + + walker = ParseTreeWalker() + prev_file = self.current_file + self.current_file = file + walker.walk(self, imported_tree) + self.current_file = prev_file + self.imported_files.append(import_reference) + + # Exit a parse tree produced by OpenSCENARIO2Parser#importReference. + def exitImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. + def enterStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. + def exitStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. + def enterOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. + def exitOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. + def enterPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + self.__node_stack.append(self.__cur_node) + type_name = ctx.physicalTypeName().getText() + + node = PhysicalTypeDeclaration(type_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. + def exitPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. + def enterPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. + def exitPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. + def enterBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. + def exitBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. + def enterSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. + def exitSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. + def enterUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): + self.__node_stack.append(self.__cur_node) + unit_name = ctx.unitName().getText() + + physical_name = ctx.physicalTypeName().getText() + + node = UnitDeclaration(unit_name, physical_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. + def exitUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. + def enterUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. + def exitUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#sIUnitSpecifier. + def enterSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): + factor = None + offset = None + if ctx.siFactor().FloatLiteral(): + factor = float(ctx.siFactor().FloatLiteral().getText()) + elif ctx.siFactor().integerLiteral(): + factor = int(ctx.siFactor().integerLiteral().getText()) + + if ctx.siOffset(): + if ctx.siOffset().FloatLiteral(): + offset = float(ctx.siOffset().FloatLiteral().getText()) + elif ctx.siOffset().integerLiteral(): + offset = int(ctx.siOffset().integerLiteral().getText()) + + node = SIUnitSpecifier(factor, offset) + self.__cur_node.set_children(node) + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. + def enterEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): + self.__node_stack.append(self.__cur_node) + enum_name = ctx.enumName().getText() + + node = EnumDeclaration(enum_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. + def exitEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. + def enterEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): + self.__node_stack.append(self.__cur_node) + member_name = ctx.enumMemberName().getText() + + member_value = None + if ctx.enumMemberValue(): + if ctx.enumMemberValue().UintLiteral(): + member_value = int(ctx.enumMemberValue().UintLiteral().getText()) + elif ctx.enumMemberValue().HexUintLiteral(): + member_value = int(ctx.enumMemberValue().HexUintLiteral().getText(), 16) + else: + pass + + # The ModelElement enumeration value is the value stored in the symbol table + node = EnumMemberDeclaration(member_name, member_value) + # node.set_ctx(ctx, self.current_file) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. + def exitEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. + def enterEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. + def exitEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumName. + def enterEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumName. + def exitEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberName. + def enterEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberName. + def exitEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumValueReference. + def enterEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): + self.__node_stack.append(self.__cur_node) + enum_name = None + if ctx.enumName(): + enum_name = ctx.enumName().getText() + + enum_member_name = ctx.enumMemberName().getText() + + node = EnumValueReference(enum_name, enum_member_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumValueReference. + def exitEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. + def enterInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): + raise OSC2ParsingError(msg=f"inherits condition not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # field_name = ctx.fieldName().getText() + + # # Since there is no function to process bool_literal, + # # so we manually add a bool literal node to tree. + # bool_literal_node = None + # if ctx.BoolLiteral(): + # bool_literal = ctx.BoolLiteral().getText() + # bool_literal_node = BoolLiteral(bool_literal) + + # node = InheritsCondition(field_name, bool_literal_node) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. + def exitInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): + self.__cur_node = self.__node_stack.pop() + # Enter a parse tree produced by OpenSCENARIO2Parser#structDeclaration. + + def enterStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): + self.__node_stack.append(self.__cur_node) + struct_name = ctx.structName().getText() + + node = StructDeclaration(struct_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#structDeclaration. + def exitStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#structInherits. + def enterStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): + self.__node_stack.append(self.__cur_node) + struct_name = ctx.structName().getText() + + node = StructInherits(struct_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#structInherits. + def exitStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. + def enterStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. + def exitStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldName. + def enterFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldName. + def exitFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structName. + def enterStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structName. + def exitStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. + def enterActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): + self.__node_stack.append(self.__cur_node) + actor_name = ctx.actorName().getText() + + node = ActorDeclaration(actor_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. + def exitActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorInherits. + def enterActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): + self.__node_stack.append(self.__cur_node) + actor_name = ctx.actorName().getText() + + node = ActorInherits(actor_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorInherits. + def exitActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. + def enterActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. + def exitActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorName. + def enterActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorName. + def exitActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. + def enterScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): + self.__node_stack.append(self.__cur_node) + qualified_behavior_name = ctx.qualifiedBehaviorName().getText() + + node = ScenarioDeclaration(qualified_behavior_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. + def exitScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. + def enterScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): + self.__node_stack.append(self.__cur_node) + qualified_behavior_name = ctx.qualifiedBehaviorName().getText() + + node = ScenarioInherits(qualified_behavior_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. + def exitScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. + def enterScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): + self.__node_stack.append(self.__cur_node) + + # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. + def exitScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. + def enterQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. + def exitQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorName. + def enterBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorName. + def exitBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. + def enterActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): + self.__node_stack.append(self.__cur_node) + qualified_behavior_name = ctx.qualifiedBehaviorName().getText() + node = ActionDeclaration(qualified_behavior_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. + def exitActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#actionInherits. + def enterActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): + self.__node_stack.append(self.__cur_node) + qualified_behavior_name = ctx.qualifiedBehaviorName().getText() + + node = ActionInherits(qualified_behavior_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#actionInherits. + def exitActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. + def enterModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): + raise OSC2ParsingError(msg=f"modifier declaration not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # actor_name = None + # if ctx.actorName(): + # actor_name = ctx.actorName().getText() + + # modifier_name = ctx.modifierName().getText() + + # node = ModifierDeclaration(actor_name, modifier_name) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. + def exitModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#modifierName. + def enterModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#modifierName. + def exitModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeExtension. + def enterTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeExtension. + def exitTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. + def enterEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): + raise OSC2ParsingError(msg=f"enum type extension not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # enum_name = ctx.enumName().getText() + + # node = EnumTypeExtension(enum_name) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. + def exitEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. + def enterStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): + self.__node_stack.append(self.__cur_node) + + type_name = None + if ctx.extendableTypeName().typeName(): + type_name = ctx.extendableTypeName().typeName().getText() + # Even if a symbol table with the corresponding name is found, + # it is necessary to determine whether the extended symbol table matches the original type + + # The two ifs here are syntactically mutually exclusive + qualified_behavior_name = None + if ctx.extendableTypeName().qualifiedBehaviorName(): + qualified_behavior_name = ( + ctx.extendableTypeName().qualifiedBehaviorName().getText() + ) + + node = StructuredTypeExtension(type_name, qualified_behavior_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. + def exitStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. + def enterExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. + def exitExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. + def enterExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. + def exitExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. + def enterGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + default_value = None + field_type = ctx.typeDeclarator().getText() + self.__node_stack.append(self.__cur_node) + if len(ctx.fieldName()) != 1: + raise OSC2ParsingError(msg="Only single field names are currently supported", context=ctx) + field_name = ctx.fieldName()[0].Identifier().getText() + # TODO field_name = [] + # multi_field_name = "" + # for fn in ctx.fieldName(): + # name = fn.Identifier().getText() + # if name in field_name: + # raise OSC2ParsingError( + # msg= "Can not define same param in same scope!", + # line=ctx.start.line, + # column=ctx.start.column, + # context=ctx.getText() + # ) + # field_name.append(name) + # multi_field_name = multi_field_name_append(multi_field_name, name) + + node = GlobalParameterDeclaration(field_name, field_name, field_type, default_value) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. + def exitGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. + def enterTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): + self.__node_stack.append(self.__cur_node) + type_name = None + is_list = False + if ctx.nonAggregateTypeDeclarator(): + type_name = ctx.nonAggregateTypeDeclarator().getText() + if type_name.startswith('listof'): + raise OSC2ParsingError(msg=f"Type name starting with listof is not allowed.", context=ctx) + elif ctx.aggregateTypeDeclarator(): + is_list = True + type_name = ctx.aggregateTypeDeclarator().getText() + + node = Type(type_name, is_list) + + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. + def exitTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. + def enterNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. + def exitNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. + def enterAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. + def exitAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. + def enterListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. + def exitListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#primitiveType. + def enterPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#primitiveType. + def exitPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeName. + def enterTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeName. + def exitTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. + def enterEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): + self.__node_stack.append(self.__cur_node) + event_name = ctx.eventName().getText() + + node = EventDeclaration(event_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. + def exitEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventSpecification. + def enterEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventSpecification. + def exitEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventReference. + def enterEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): + self.__node_stack.append(self.__cur_node) + event_path = ctx.eventPath().getText() + node = EventReference(event_path) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventReference. + def exitEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. + def enterEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): + self.__node_stack.append(self.__cur_node) + event_field_name = ctx.eventFieldName().getText() + node = EventFieldDecl(event_field_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. + def exitEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventFieldName. + def enterEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventFieldName. + def exitEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventName. + def enterEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventName. + def exitEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventPath. + def enterEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventPath. + def exitEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventCondition. + def enterEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): + self.__node_stack.append(self.__cur_node) + node = EventCondition() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventCondition. + def exitEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#riseExpression. + def enterRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): + raise OSC2ParsingError(msg=f"rise expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = RiseExpression() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#riseExpression. + def exitRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#fallExpression. + def enterFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): + raise OSC2ParsingError(msg=f"fall expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = FallExpression() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#fallExpression. + def exitFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. + def enterElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): + self.__node_stack.append(self.__cur_node) + node = ElapsedExpression() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. + def exitElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#everyExpression. + def enterEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): + raise OSC2ParsingError(msg=f"every expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = EveryExpression() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#everyExpression. + def exitEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#boolExpression. + def enterBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#boolExpression. + def exitBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#durationExpression. + def enterDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#durationExpression. + def exitDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. + def enterFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. + def exitFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. + def enterParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): + default_value = None + if ctx.defaultValue(): + default_value = ctx.defaultValue().getText() + field_type = ctx.typeDeclarator().getText() + self.__node_stack.append(self.__cur_node) + + if len(ctx.fieldName()) != 1: + raise OSC2ParsingError(msg="Only single field names are currently supported", context=ctx) + field_name = ctx.fieldName()[0].Identifier().getText() + + # TODO field_name = [] + # for fn in ctx.fieldName(): + # name = fn.Identifier().getText() + # if name in field_name: + # raise OSC2ParsingError( + # msg= "Can not define same param in same scope!", + # line=ctx.start.line, + # column=ctx.start.column, + # context=ctx.getText() + # ) + # field_name.append(name) + + node = ParameterDeclaration(field_name, field_type, default_value) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. + def exitParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. + def enterVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): + self.__node_stack.append(self.__cur_node) + field_name = [] + default_value = None + if ctx.sampleExpression(): + default_value = ctx.sampleExpression().getText() + elif ctx.valueExp(): + if ctx.valueExp().listConstructor(): + default_value = ast.literal_eval(ctx.valueExp().getText()) + else: + default_value = ctx.valueExp().getText() + + # TODO multi_field_name = "" + # for fn in ctx.fieldName(): + # name = fn.Identifier().getText() + # if name in field_name: + # raise OSC2ParsingError(msg="Can not define same param in same scope!", context=ctx) + # field_name.append(name) + # multi_field_name = multi_field_name_append(multi_field_name, name) + + field_type = ctx.typeDeclarator().getText() + + node = VariableDeclaration(field_name, field_type, default_value) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. + def exitVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#sampleExpression. + def enterSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): + raise OSC2ParsingError(msg=f"sample expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = SampleExpression() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#sampleExpression. + def exitSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#defaultValue. + def enterDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#defaultValue. + def exitDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. + def enterParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. + def exitParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. + def enterParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. + def exitParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. + def enterConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. + def exitConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. + def enterKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + self.__node_stack.append(self.__cur_node) + constraint_qualifier = None + if ctx.constraintQualifier(): + constraint_qualifier = ctx.constraintQualifier().getText() + + node = KeepConstraintDeclaration(constraint_qualifier) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. + def exitKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. + def enterConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. + def exitConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#constraintExpression. + def enterConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#constraintExpression. + def exitConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. + def enterRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + raise OSC2ParsingError(msg=f"remove default declaration not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = RemoveDefaultDeclaration() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. + def exitRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterReference. + def enterParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): + self.__node_stack.append(self.__cur_node) + field_name = None + if ctx.fieldName(): + field_name = ctx.fieldName().getText() + + field_access = None + if ctx.fieldAccess(): + field_access = ctx.fieldAccess().getText() + + node = ParameterReference(field_name, field_access) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterReference. + def exitParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. + def enterModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): + raise OSC2ParsingError(msg=f"modifier invocation not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # modifier_name = ctx.modifierName().getText() + + # actor = None + # if ctx.actorExpression(): + # actor = ctx.actorExpression().getText() + + # if ctx.behaviorExpression(): + # actor = ctx.behaviorExpression().getText() + + # node = ModifierInvocation(actor, modifier_name) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. + def exitModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. + def enterBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. + def exitBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. + def enterBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. + def exitBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#onDirective. + def enterOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): + self.__node_stack.append(self.__cur_node) + node = OnDirective() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#onDirective. + def exitOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#onMember. + def enterOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#onMember. + def exitOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#doDirective. + def enterDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): + self.__node_stack.append(self.__cur_node) + + node = DoDirective() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#doDirective. + def exitDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#doMember. + def enterDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): + self.__node_stack.append(self.__cur_node) + self.__current_label = None + + if ctx.labelName(): + self.__current_label = ctx.labelName().getText() + + composition_operator = None + if ctx.composition(): + composition_operator = ctx.composition().compositionOperator().getText().strip("\'").strip("\"") + + if composition_operator is not None: + node = DoMember(self.__current_label, composition_operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#doMember. + def exitDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): + self.__cur_node = self.__node_stack.pop() + self.__current_label = None + + # Enter a parse tree produced by OpenSCENARIO2Parser#composition. + def enterComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#composition. + def exitComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#compositionOperator. + def enterCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#compositionOperator. + def exitCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. + def enterBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): + self.__node_stack.append(self.__cur_node) + actor = None + name = "" + behavior_name = ctx.behaviorName().getText() + if ctx.actorExpression(): + actor = ctx.actorExpression().getText() + name += actor + "." + + name += behavior_name + + node = BehaviorInvocation(self.__current_label, actor, behavior_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. + def exitBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. + def enterBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. + def exitBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. + def enterBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): + self.__node_stack.append(self.__cur_node) + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. + def exitBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#labelName. + def enterLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#labelName. + def exitLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorExpression. + def enterActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorExpression. + def exitActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#waitDirective. + def enterWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): + self.__node_stack.append(self.__cur_node) + + node = WaitDirective() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#waitDirective. + def exitWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#emitDirective. + def enterEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): + self.__node_stack.append(self.__cur_node) + event_name = ctx.eventName().getText() + node = EmitDirective(event_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#emitDirective. + def exitEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#callDirective. + def enterCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): + raise OSC2ParsingError(msg=f"call directive not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # method_name = ctx.methodInvocation().postfixExp().getText() + + # node = CallDirective(method_name) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#callDirective. + def exitCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#untilDirective. + def enterUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): + raise OSC2ParsingError(msg=f"until declaration not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = UntilDirective() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#untilDirective. + def exitUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodInvocation. + def enterMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodInvocation. + def exitMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. + def enterMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): + raise OSC2ParsingError(msg=f"method declaration not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # method_name = ctx.methodName().getText() + # return_type = None + # if ctx.returnType(): + # return_type = ctx.returnType().getText() + + # node = MethodDeclaration(method_name, return_type) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. + def exitMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#returnType. + def enterReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#returnType. + def exitReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodImplementation. + def enterMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): + self.__node_stack.append(self.__cur_node) + qualifier = None + if ctx.methodQualifier(): + qualifier = ctx.methodQualifier().getText() + + if ctx.expression(): + _type = "expression" + elif ctx.structuredIdentifier(): + _type = "external" + else: + _type = "undefined" + + external_name = None + if ctx.structuredIdentifier(): + external_name = ctx.structuredIdentifier().getText() + + node = MethodBody(qualifier, _type, external_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodImplementation. + def exitMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodQualifier. + def enterMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodQualifier. + def exitMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodName. + def enterMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodName. + def exitMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. + def enterCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. + def exitCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. + def enterCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): + raise OSC2ParsingError(msg=f"cover declaration not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # target_name = None + # if ctx.targetName(): + # target_name = ctx.targetName().getText() + + # node = CoverDeclaration(target_name) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. + def exitCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. + def enterRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): + raise OSC2ParsingError(msg=f"record declaration not supported yet.", context=ctx) + # self.__node_stack.append(self.__cur_node) + # target_name = None + # if ctx.targetName(): + # target_name = ctx.targetName().getText() + + # node = RecordDeclaration(target_name) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. + def exitRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageExpression. + def enterCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): + self.__node_stack.append(self.__cur_node) + argument_name = "expression" + node = NamedArgument(argument_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageExpression. + def exitCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageUnit. + def enterCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): + self.__node_stack.append(self.__cur_node) + argument_name = "unit" + node = NamedArgument(argument_name) + node.set_ctx(ctx, self.current_file) + + unit_name = Identifier(ctx.Identifier().getText()) + unit_name.set_loc(ctx.start.line, ctx.start.column) + node.set_children(unit_name) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageUnit. + def exitCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageRange. + def enterCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): + self.__node_stack.append(self.__cur_node) + argument_name = "range" + node = NamedArgument(argument_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageRange. + def exitCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageEvery. + def enterCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): + self.__node_stack.append(self.__cur_node) + argument_name = "every" + node = NamedArgument(argument_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageEvery. + def exitCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageEvent. + def enterCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): + self.__node_stack.append(self.__cur_node) + argument_name = "event" + node = NamedArgument(argument_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageEvent. + def exitCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. + def enterCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. + def exitCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#targetName. + def enterTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#targetName. + def exitTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#expression. + def enterExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#expression. + def exitExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. + def enterTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. + def exitTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#implication. + def enterImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): + self.__node_stack.append(self.__cur_node) + if len(ctx.disjunction()) > 1: + operator = "=>" + node = LogicalExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#implication. + def exitImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#disjunction. + def enterDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): + self.__node_stack.append(self.__cur_node) + if len(ctx.conjunction()) > 1: + operator = "or" + node = LogicalExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#disjunction. + def exitDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#conjunction. + def enterConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): + self.__node_stack.append(self.__cur_node) + if len(ctx.inversion()) > 1: + operator = "and" + node = LogicalExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#conjunction. + def exitConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#inversion. + def enterInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): + self.__node_stack.append(self.__cur_node) + if ctx.relation() is None: + operator = "not" + node = LogicalExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#inversion. + def exitInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#relation. + def enterRelation(self, ctx: OpenSCENARIO2Parser.RelationContext): # pylint: disable=invalid-name + self.__node_stack.append(self.__cur_node) + + # Exit a parse tree produced by OpenSCENARIO2Parser#relation. + def exitRelation(self, ctx: OpenSCENARIO2Parser.RelationContext): # pylint: disable=invalid-name + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#relationExp. + def enterRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): + self.__node_stack.append(self.__cur_node) + operator = ctx.relationalOp().getText() + node = RelationExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#relationExp. + def exitRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#relationalOp. + def enterRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#relationalOp. + def exitRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#sum. + def enterSumExpression(self, ctx: OpenSCENARIO2Parser.SumExpressionContext): # pylint: disable=invalid-name + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#sum. + def exitSumExpression(self, ctx: OpenSCENARIO2Parser.SumExpressionContext): # pylint: disable=invalid-name + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#additiveExp. + def enterAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): + self.__node_stack.append(self.__cur_node) + operator = ctx.additiveOp().getText() + node = BinaryExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#additiveExp. + def exitAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#additiveOp. + def enterAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#additiveOp. + def exitAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. + def enterMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): + self.__node_stack.append(self.__cur_node) + operator = ctx.multiplicativeOp().getText() + node = BinaryExpression(operator) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. + def exitMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#term. + def enterTerm(self, ctx: OpenSCENARIO2Parser.TermContext): # pylint: disable=invalid-name + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#term. + def exitTerm(self, ctx: OpenSCENARIO2Parser.TermContext): # pylint: disable=invalid-name + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. + def enterMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. + def exitMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#factor. + def enterFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#factor. + def exitFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#primaryExpression. + def enterPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#primaryExpression. + def exitPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#castExpression. + def enterCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): + raise OSC2ParsingError(msg=f"cast expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # object = ctx.postfixExp().getText() + # target_type = ctx.typeDeclarator().getText() + # node = CastExpression(object, target_type) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#castExpression. + def exitCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. + def enterFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + self.__node_stack.append(self.__cur_node) + func_name = ctx.postfixExp().getText() + + node = FunctionApplicationExpression(func_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. + def exitFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. + def enterFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): + self.__node_stack.append(self.__cur_node) + field_name = ctx.postfixExp().getText() + "." + ctx.fieldName().getText() + + node = FieldAccessExpression(field_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. + def exitFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. + def enterElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): + raise OSC2ParsingError(msg=f"element access expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # list_name = ctx.postfixExp().getText() + # index = ctx.expression().getText() + # node = ElementAccessExpression(list_name, index) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. + def exitElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. + def enterTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): + raise OSC2ParsingError(msg=f"type test expression not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # object = ctx.postfixExp().getText() + # target_type = ctx.typeDeclarator().getText() + # node = TypeTestExpression(object, target_type) + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. + def exitTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldAccess. + def enterFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): + self.__node_stack.append(self.__cur_node) + field_name = ctx.postfixExp().getText() + "." + ctx.fieldName().getText() + node = FieldAccessExpression(field_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldAccess. + def exitFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#primaryExp. + def enterPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#primaryExp. + def exitPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#valueExp. + def enterValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): + self.__node_stack.append(self.__cur_node) + value = None + node = None + if ctx.FloatLiteral(): + value = ctx.FloatLiteral().getText() + node = FloatLiteral(value) + elif ctx.BoolLiteral(): + value = ctx.BoolLiteral().getText() + node = BoolLiteral(value) + elif ctx.StringLiteral(): + value = ctx.StringLiteral().getText() + value = value.strip('"') + node = StringLiteral(value) + + if node is not None: + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#valueExp. + def exitValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#listConstructor. + def enterListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): + self.__node_stack.append(self.__cur_node) + node = ListExpression() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#listConstructor. + def exitListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. + def enterRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): + raise OSC2ParsingError(msg=f"range constructor not yet supported", context=ctx) + # self.__node_stack.append(self.__cur_node) + # node = RangeExpression() + # node.set_ctx(ctx, self.current_file) + + # self.__cur_node.set_children(node) + # self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. + def exitRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#identifierReference. + def enterIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): + self.__node_stack.append(self.__cur_node) + + field_name = [] + for fn in ctx.fieldName(): + name = fn.Identifier().getText() + + field_name.append(name) + + id_name = ".".join(field_name) # TODO do not merge to single string + + node = IdentifierReference(id_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#identifierReference. + def exitIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. + def enterArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. + def exitArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. + def enterArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): + self.__node_stack.append(self.__cur_node) + argument_name = ctx.argumentName().getText() + argument_type = ctx.typeDeclarator().getText() + default_value = None + if ctx.defaultValue(): + default_value = ctx.defaultValue().getText() + + node = Argument(argument_name, argument_type, default_value) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. + def exitArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentName. + def enterArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentName. + def exitArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentList. + def enterArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentList. + def exitArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#positionalArgument. + def enterPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): + self.__node_stack.append(self.__cur_node) + + node = PositionalArgument() + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#positionalArgument. + def exitPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#namedArgument. + def enterNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): + self.__node_stack.append(self.__cur_node) + argument_name = ctx.argumentName().getText() + + node = NamedArgument(argument_name) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#namedArgument. + def exitNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. + def enterPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): + self.__node_stack.append(self.__cur_node) + unit_name = ctx.unitName().getText() + value = None + if ctx.FloatLiteral(): + value = ctx.FloatLiteral().getText() + else: + value = ctx.integerLiteral().getText() + + node = PhysicalLiteral(unit_name, value) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + if ctx.FloatLiteral(): + self.__node_stack.append(self.__cur_node) + float_value = ctx.FloatLiteral().getText() + value_node = FloatLiteral(float_value) + value_node.set_ctx(ctx, self.current_file) + + node.set_children(value_node) + self.__cur_node = self.__node_stack.pop() + + # Exit a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. + def exitPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): + self.__cur_node = self.__node_stack.pop() + + # Enter a parse tree produced by OpenSCENARIO2Parser#integerLiteral. + def enterIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): + self.__node_stack.append(self.__cur_node) + value = None + type_def = "uint" + if ctx.UintLiteral(): + value = int(ctx.UintLiteral().getText()) + type_def = "uint" + elif ctx.HexUintLiteral(): + value = int(ctx.HexUintLiteral().getText(), 16) + type_def = "uint" + elif ctx.IntLiteral(): + value = int(ctx.IntLiteral().getText()) + type_def = "int" + else: # only the above three types of integer literal + raise ValueError("invalid literal") + + node = IntegerLiteral(type_def, value) + node.set_ctx(ctx, self.current_file) + + self.__cur_node.set_children(node) + self.__cur_node = node + + # Exit a parse tree produced by OpenSCENARIO2Parser#integerLiteral. + def exitIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): + self.__cur_node = self.__node_stack.pop() + + +del OpenSCENARIO2Parser diff --git a/scenario_execution_base/scenario_execution_base/model/model_file_loader.py b/scenario_execution_base/scenario_execution_base/model/model_file_loader.py new file mode 100644 index 00000000..0b99701c --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/model_file_loader.py @@ -0,0 +1,52 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +import yaml +from scenario_execution_base.model.types import print_tree, deserialize +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.model.model_resolver import resolve_internal_model + + +class ModelFileLoader(object): + + def __init__(self, logger) -> None: + self.logger = logger + + def process_file(self, file_name, log_tree: bool = False, debug: bool = False): + model = self.load_file(file_name, log_tree) + + success = resolve_internal_model(model, self.logger, log_tree) + if not success: + return None + + scenarios = create_py_tree(model, self.logger) + + return scenarios + + def load_file(self, file_name, log_tree): + try: + with open(file_name, 'rb') as input_file: + serialize_data = yaml.safe_load(input_file) # nosec B301 TODO + model = deserialize(serialize_data) + except Exception as e: # pylint: disable=broad-except + self.logger.error(f"Error while loading model from {file_name}: {e}") + return None + + if log_tree: + self.logger.info("----Internal model-----") + print_tree(model, self.logger) + return model diff --git a/scenario_execution_base/scenario_execution_base/model/model_resolver.py b/scenario_execution_base/scenario_execution_base/model/model_resolver.py new file mode 100644 index 00000000..ad6e5b7d --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/model_resolver.py @@ -0,0 +1,284 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from scenario_execution_base.model.types import ActionDeclaration, ActionInherits, EnumDeclaration, EnumValueReference, KeepConstraintDeclaration, EmitDirective, Type + +from .types import UnitDeclaration, EnumValueReference, StructInherits, ActionDeclaration, ActionInherits, ActorInherits, FieldAccessExpression, BehaviorInvocation, EmitDirective, GlobalParameterDeclaration, IdentifierReference, Parameter, ModelElement, StructuredDeclaration, KeepConstraintDeclaration, NamedArgument, ParameterDeclaration, PhysicalLiteral, PositionalArgument, RelationExpression, ScenarioInherits, SIUnitSpecifier, Type, EnumMemberDeclaration, ListExpression, print_tree + +from .model_base_visitor import ModelBaseVisitor +from scenario_execution_base.model.error import OSC2ParsingError + + +def resolve_internal_model(model, logger, log_tree): + osc2scenario_resolver = ModelResolver(logger) + try: + osc2scenario_resolver.visit(model) + except OSC2ParsingError as e: + logger.error( + f'Error while creating tree:\nTraceback in "{e.filename}":\n -> {e.context}\n' + f'{e.__class__.__name__}: {e.msg}' + ) + return False + + if log_tree: + logger.info("----Internal model (resolved)-----") + print_tree(model, logger) + return True + + +class ModelResolver(ModelBaseVisitor): + + def __init__(self, logger) -> None: + super().__init__() + self.logger = logger + + def visit_physical_literal(self, node: PhysicalLiteral): + unit = node.resolve(node.unit) + if unit is None: + raise OSC2ParsingError( + msg=f'Physical unit "{node.unit}" not defined.', context=node.get_ctx()) + node.unit = unit + si_unit_specifier = node.unit.find_first_child_of_type(SIUnitSpecifier) + if si_unit_specifier is None: + raise OSC2ParsingError( + msg=f'SIUnitSpecifier of physical unit "{node.unit.name}" not defined.', context=node.get_ctx()) + + def visit_identifier_reference(self, node: IdentifierReference): + resolved = node.resolve(node.ref) + if resolved is None: + raise OSC2ParsingError( + msg=f'Identifier "{node.ref}" not defined.', context=node.get_ctx()) + node.ref = resolved + + def visit_type(self, node: Type): + type_string = node.type_def + if node.is_list: + if not type_string.startswith('listof'): + raise OSC2ParsingError( + msg=f'Invalid list type "{type_string}".', context=node.get_ctx()) + type_string = type_string.removeprefix('listof') + + if type_string not in ['string', 'int', 'bool', 'float', 'uint']: + resolved = node.resolve(type_string) + if resolved is None: + raise OSC2ParsingError( + msg=f'Type "{type_string}" not defined.', context=node.get_ctx()) + node.type_def = resolved + + def visit_unit_declaration(self, node: UnitDeclaration): + resolved = node.resolve(node.physical_name) + if resolved is None: + raise OSC2ParsingError( + msg=f'Unit declaration refers to unknown physical name "{node.physical_name}".', context=node.get_ctx()) + node.physical_name = resolved + + def visit_keep_constraint_declaration(self, node: KeepConstraintDeclaration): + self.visit_children(node) + if node.get_child_count() == 1 and isinstance(node.get_child(0), RelationExpression) and node.get_child(0).get_child_count() == 2: + if node.get_child(0).operator != "==": + raise OSC2ParsingError( + msg=f'Only relation "==" is currently supported in "keep".', context=node.get_ctx()) + field_exp = node.get_child(0).find_first_child_of_type(FieldAccessExpression) + + if not field_exp: + raise OSC2ParsingError( + msg=f'FieldAccessExpression not found.', context=node.get_ctx()) + if not field_exp.field_name.startswith('it.'): + raise OSC2ParsingError( + msg=f'FieldAccessExpression only supports "it." prefix, not "{field_exp.field_name}".', context=node.get_ctx()) + + definition, _ = node.get_parent().get_type() + if not isinstance(definition, StructuredDeclaration): + raise OSC2ParsingError( + msg=f'keep expected reference to structured type.', context=node.get_ctx()) + + parameters = definition.get_resolved_value() + expected_member_name = field_exp.field_name.removeprefix("it.") + + member_path = expected_member_name.split('.') + current_params = parameters + for current in member_path: + if current not in current_params: + raise OSC2ParsingError( + msg=f'keep reference {field_exp.field_name} not found in {definition.name}. Unknown key "{current}"', context=node.get_ctx()) + current_params = current_params[current] + else: + raise OSC2ParsingError( + msg=f'Keep uses unsupported expression: allowed "==" only.', context=node.get_ctx()) + + def check_parameter_type(self, node: Parameter): + val = node.get_value_child() + if isinstance(val, KeepConstraintDeclaration): + pass + else: + if val is not None: + val_type = val.get_type_string() + param_type = node.field_type + # if isinstance(node.field_type, Type) and node.field_type.is_list: + # param_type = "listof" + param_type + if param_type == 'uint': + param_type = 'int' + if val_type != param_type: + raise OSC2ParsingError( + msg=f'Parameter type "{param_type}" does not match value type "{val_type}".', context=node.get_ctx()) + + # check list entries + if isinstance(val, ListExpression): + expected_type = param_type.removeprefix('listof') + for child in val.get_children(): + member_type = child.get_type_string() + if expected_type != member_type: + raise OSC2ParsingError( + msg=f'List entry does not have valid type. Expected "{expected_type}", found "{member_type}".', context=node.get_ctx()) + + def visit_global_parameter_declaration(self, node: GlobalParameterDeclaration): + self.visit_children(node) + self.check_parameter_type(node) + + def visit_parameter_declaration(self, node: ParameterDeclaration): + self.visit_children(node) + self.check_parameter_type(node) + + def visit_actor_inherits(self, node: ActorInherits): + resolved = node.resolve(node.actor) + if resolved is None: + raise OSC2ParsingError( + msg=f'Actor inherits from unknown "{node.actor}".', context=node.get_ctx()) + node.actor = resolved + + def visit_struct_inherits(self, node: StructInherits): + resolved = node.resolve(node.struct_name) + if resolved is None: + raise OSC2ParsingError( + msg=f'Struct inherits from unknown "{node.struct_name}".', context=node.get_ctx()) + node.struct_name = resolved + + def visit_action_inherits(self, node: ActionInherits): + resolved = node.resolve(node.qualified_behavior_name) + if resolved is None: + raise OSC2ParsingError( + msg=f'Action inherits from unknown "{node.qualified_behavior_name}".', context=node.get_ctx()) + node.qualified_behavior_name = resolved + + def visit_scenario_inherits(self, node: ScenarioInherits): + resolved = node.resolve(node.qualified_behavior_name) + if resolved is None: + raise OSC2ParsingError( + msg=f'Scenario inherits from unknown "{node.qualified_behavior_name}".', context=node.get_ctx()) + node.qualified_behavior_name = resolved + + def visit_behavior_invocation(self, node: BehaviorInvocation): + qualified_behavior_name = node.behavior + if node.actor: + resolved_actor = node.resolve(node.actor) + if resolved_actor is None: + raise OSC2ParsingError( + msg=f'BehaviorInvocation refers to unknown actor "{node.actor}".', context=node.get_ctx()) + node.actor = resolved_actor + + current, _ = node.actor.get_type() + resolved = None + while current and resolved is None: # look for action in all base_types + qualified_behavior_name = current.name + "." + node.behavior + resolved = node.resolve(qualified_behavior_name) + current = current.get_base_type() + else: + resolved = node.resolve(node.behavior) + + if not resolved: + raise OSC2ParsingError( + msg=f'BehaviorInvocation uses unknown behavior "{qualified_behavior_name}".', context=node.get_ctx()) + node.behavior = resolved + + pos_arg_count = 0 + named = False + param_keys = node.get_parameter_names() + max_named_arg_count = len(param_keys) + for child in node.get_children(): + if isinstance(child, NamedArgument): + named = True + if child.argument_name not in param_keys: + raise OSC2ParsingError( + msg=f'Named argument {child.argument_name} unknown.', context=node.get_ctx()) + + elif isinstance(child, PositionalArgument): + if named: + raise OSC2ParsingError( + msg=f'No positional argument allowed after named.', context=node.get_ctx()) + if pos_arg_count >= max_named_arg_count: + raise OSC2ParsingError( + msg=f'Too many positional arguments.', context=node.get_ctx()) + pos_arg_count += 1 + + super().visit_behavior_invocation(node) + + def visit_action_declaration(self, node: ActionDeclaration): + super().visit_action_declaration(node) + + param_names = node.get_parameter_names() + if 'name' in param_names: + raise OSC2ParsingError( + msg=f'ActionDeclaration {node.name} uses reserved paramater name "name".', context=node.get_ctx()) + if 'associated_actor' in param_names: + raise OSC2ParsingError( + msg=f'ActionDeclaration {node.name} uses reserved paramater name "associated_actor".', context=node.get_ctx()) + + actor_name = None + if "." in node.qualified_behavior_name: + actor_name = node.qualified_behavior_name.split('.')[0] + if actor_name: + resolved_actor = node.resolve(actor_name) + if resolved_actor is None: + raise OSC2ParsingError( + msg=f'ActionDeclaration {node.name} refers to unknown actor "{actor_name}".', context=node.get_ctx()) + node.actor = resolved_actor + + def visit_enum_value_reference(self, node: EnumValueReference): + # skip parameter level (to allow parameter names to be similar to enum-type-names) + enum_type = node.get_parent().resolve(node.enum_name) + if enum_type is None: + raise OSC2ParsingError( + msg=f'Enum type {node.enum_name} unknown.', context=node.get_ctx()) + node.enum_name = enum_type + + member = None + for child in enum_type.get_children(): + if isinstance(child, ModelElement) and child.member_name == node.enum_member_name: + member = child + break + if member is None: + raise OSC2ParsingError( + msg=f'Enum type {node.enum_name} does not have a member "{node.enum_member_name}".', context=node.get_ctx()) + node.enum_member_name = member + + def visit_emit_directive(self, node: EmitDirective): + if node.event_name not in ['start', 'end', 'fail']: + node.event = node.resolve(node.event_name) + if node.event is None: + raise OSC2ParsingError( + msg=f'EmitDirective refers to unknown event {node.event_name}.', context=node.get_ctx()) + + def visit_enum_declaration(self, node: EnumDeclaration): + next_numeric_val = 0 + for child in node.get_children(): + if isinstance(child, EnumMemberDeclaration): + if child.numeric_value is None: + child.numeric_value = next_numeric_val + next_numeric_val += 1 + else: + next_numeric_val = child.numeric_value + 1 + + return super().visit_enum_declaration(node) diff --git a/scenario_execution_base/scenario_execution_base/model/model_to_py_tree.py b/scenario_execution_base/scenario_execution_base/model/model_to_py_tree.py new file mode 100644 index 00000000..97ce980e --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/model_to_py_tree.py @@ -0,0 +1,282 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import py_trees +from py_trees.common import Access, Status +from pkg_resources import iter_entry_points + +import inspect + +from scenario_execution_base.model.types import EventReference, CoverDeclaration, ScenarioDeclaration, DoMember, WaitDirective, EmitDirective, BehaviorInvocation, EventCondition, EventDeclaration, RelationExpression, LogicalExpression, ElapsedExpression, PhysicalLiteral +from scenario_execution_base.model.model_base_visitor import ModelBaseVisitor +from scenario_execution_base.model.error import OSC2ParsingError + + +def create_py_tree(model, logger): + model_to_py_tree = ModelToPyTree(logger) + scenario = None + try: + scenario = model_to_py_tree.build(model) + except OSC2ParsingError as e: + logger.error( + f'Error while creating tree:\nTraceback in "{e.filename}":\n -> {e.context}\n' + f'{e.__class__.__name__}: {e.msg}' + ) + return None + return [scenario] + + +class TopicEquals(py_trees.behaviour.Behaviour): + """ + Class to listen to a topic in Blackboard and check if it equals the defined message + + Args: + key [str]: topic to listen to + msg [str]: target message to match + namespace [str]: namespace of the key + """ + + def __init__(self, key: str, msg: str, namespace: str = None): + super().__init__(self.__class__.__name__) + + self.namespace = namespace + self.key = key + self.msg = msg + + self.client = self.attach_blackboard_client(namespace=self.namespace) + self.client.register_key(self.key, access=Access.READ) + + def update(self): + """ + Check the message on the topic equals the target message + """ + msg_on_blackboard = self.client.get(self.key) + if msg_on_blackboard == self.msg: + return Status.SUCCESS + return Status.RUNNING + + +class TopicPublish(py_trees.behaviour.Behaviour): + """ + Class to publish a message to a topic + + Args: + key [str]: topic to publish on + msg [str]: message to publish on that topic + namespace [str]: namespace of the key + """ + + def __init__(self, name: "TopicPublish", key: str, msg: str, namespace: str = None): + super().__init__(name) + + self.namespace = namespace + self.key = key + self.msg = msg + + self.client = self.attach_blackboard_client(namespace=self.namespace) + self.client.register_key(self.key, access=Access.WRITE) + + def setup(self, **kwargs): + """ + Setup empty topic on blackboard + + This is to prevent the "Reader" from reading before the topic exists. + """ + self.client.set(self.key, '') + + def update(self): + """ + publish the message to topic + """ + self.client.set(self.key, self.msg) + return Status.SUCCESS + + +class ModelToPyTree(object): + + def __init__(self, logger): + self.logger = logger + + def build(self, tree): + if tree.find_children_of_type(CoverDeclaration): + raise ValueError("Model still contains CoverageDeclarations.") + behavior_builder = self.BehaviorInit(self.logger) + behavior_builder.visit(tree) + + behavior_tree = behavior_builder.get_behavior_tree() + + if behavior_tree: + print(py_trees.display.ascii_tree(behavior_tree)) + + return behavior_tree + + class BehaviorInit(ModelBaseVisitor): + def __init__(self, logger) -> None: + super().__init__() + self.logger = logger + self.root_behavior = None + self.__cur_behavior = None + + def get_behavior_tree(self): + return self.root_behavior + + def visit_scenario_declaration(self, node: ScenarioDeclaration): + scenario_name = node.qualified_behavior_name + if self.root_behavior: + raise ValueError( + f"Could not add scenario {scenario_name}. Scenario {self.root_behavior.name} already defined.") + + self.root_behavior = py_trees.composites.Sequence(name=scenario_name) + self.__cur_behavior = self.root_behavior + + super().visit_scenario_declaration(node) + + def visit_do_member(self, node: DoMember): + composition_operator = node.composition_operator + if composition_operator == "serial": + behavior = py_trees.composites.Sequence(name=node.name) + elif composition_operator == "parallel": + behavior = py_trees.composites.Parallel(name=node.name, policy=py_trees.common.ParallelPolicy.SuccessOnAll()) + elif composition_operator == "one_of": + behavior = py_trees.composites.Parallel(name=node.name, policy=py_trees.common.ParallelPolicy.SuccessOnOne()) + else: + raise NotImplementedError(f"scenario operator {composition_operator} not yet supported.") + + parent = self.__cur_behavior + self.__cur_behavior.add_child(behavior) + self.__cur_behavior = behavior + self.visit_children(node) + self.__cur_behavior = parent + + def visit_wait_directive(self, node: WaitDirective): + child = node.get_only_child() + + if isinstance(child, (EventCondition, EventReference)): + behavior = self.visit(child) + + self.__cur_behavior.add_child(behavior) + else: + raise OSC2ParsingError(msg="Invalid wait directive.", context=node.get_ctx()) + + def visit_emit_directive(self, node: EmitDirective): + if node.event_name in ['start', 'end', 'fail']: + self.__cur_behavior.add_child(TopicPublish( + name=f"emit {node.event_name}", key=f"/{self.root_behavior.name}/{node.event_name}", msg=True)) + else: + qualified_name = node.event.get_qualified_name() + self.__cur_behavior.add_child(TopicPublish( + name=f"emit {node.event_name}", key=qualified_name, msg=True)) + + def visit_behavior_invocation(self, node: BehaviorInvocation): + behavior_name = node.behavior.name + + final_args = node.get_resolved_value() + + available_plugins = [] + for entry_point in iter_entry_points(group='scenario_execution.actions', name=None): + # self.logger.debug(f'entry_point.name is {entry_point.name}') + if entry_point.name == behavior_name: + available_plugins.append(entry_point) + if not available_plugins: + raise OSC2ParsingError( + msg=f'No plugins found for action "{behavior_name}".', + context=node.get_ctx() + ) + if len(available_plugins) > 1: + self.logger.error(f'More than one plugin is found for "{behavior_name}".') + for available_plugin in available_plugins: + self.logger.error( + f'Found available plugin for "{behavior_name}" ' + f'in module "{available_plugin.module_name}".') + raise OSC2ParsingError( + msg=f'More than one plugin is found for "{behavior_name}".', + context=node.get_ctx() + ) + behavior_cls = available_plugins[0].load() + + if not issubclass(behavior_cls, py_trees.behaviour.Behaviour): + raise OSC2ParsingError( + msg=f"Found plugin for '{behavior_name}', but it's not derived from py_trees.behaviour.Behaviour.", + context=node.get_ctx() + ) + + plugin_args = inspect.getfullargspec(behavior_cls.__init__).args + plugin_args.remove("self") + + final_args["name"] = node.name + + if node.actor: + final_args["associated_actor"] = node.actor.get_resolved_value() + final_args["associated_actor"]["name"] = node.actor.name + + missing_args = [] + for element in plugin_args: + if element not in final_args: + missing_args.append(element) + if missing_args: + raise OSC2ParsingError( + msg=f'Plugin {behavior_name} requires arguments that are not defined in osc. Missing: {missing_args}', context=node.get_ctx() + ) + log_name = None + if final_args["name"]: + log_name = final_args["name"] + else: + log_name = type(node).__name__ + self.logger.info( + f"Instantiate action '{log_name}', plugin '{behavior_name}' with:\nArguments: {final_args}") + try: + instance = behavior_cls(**final_args) + except Exception as e: + raise OSC2ParsingError(msg=f'Error while initializing plugin {behavior_name}: {e}', context=node.get_ctx()) from e + self.__cur_behavior.add_child(instance) + + def visit_event_reference(self, node: EventReference): + event = node.resolve(node.event_path) + name = event.get_qualified_name() + return TopicEquals(key=name, msg=True) + + def visit_event_condition(self, node: EventCondition): + expression = "" + for child in node.get_children(): + if isinstance(child, RelationExpression): + raise NotImplementedError() + elif isinstance(child, LogicalExpression): + raise NotImplementedError() + elif isinstance(child, ElapsedExpression): + elapsed_condition = self.visit_elapsed_expression(child) + expression = py_trees.timers.Timer( + name=f"wait {elapsed_condition}s", duration=float(elapsed_condition)) + else: + raise OSC2ParsingError( + msg=f'Invalid event condition {child}', context=node.get_ctx()) + return expression + + def visit_elapsed_expression(self, node: ElapsedExpression): + child = node.find_first_child_of_type(PhysicalLiteral) + if child is None: + raise OSC2ParsingError( + msg=f'Elapsed expression currently only supports PhysicalLiteral.', context=node.get_ctx()) + return child.get_resolved_value() + + def visit_event_declaration(self, node: EventDeclaration): + if node.name in ['start', 'end', 'fail']: + raise OSC2ParsingError( + msg=f'EventDeclaration uses reserved name {node.name}.', context=node.get_ctx() + ) + else: + qualified_name = node.get_qualified_name() + client = self.__cur_behavior.attach_blackboard_client() + client.register_key(qualified_name, access=Access.WRITE) diff --git a/scenario_execution_base/scenario_execution_base/model/osc2_parser.py b/scenario_execution_base/scenario_execution_base/model/osc2_parser.py new file mode 100644 index 00000000..b05f38da --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/osc2_parser.py @@ -0,0 +1,131 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import sys +import re + +from antlr4 import FileStream, CommonTokenStream +from antlr4.error.ErrorListener import ErrorListener +from antlr4.tree.Tree import TerminalNodeImpl, ParseTreeWalker +from scenario_execution_base.osc2_parsing.OpenSCENARIO2Parser import OpenSCENARIO2Parser +from scenario_execution_base.osc2_parsing.OpenSCENARIO2Lexer import OpenSCENARIO2Lexer +from scenario_execution_base.model.error import OSC2ParsingError +from scenario_execution_base.model.model_builder import ModelBuilder +from scenario_execution_base.model.types import print_tree +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.model.model_resolver import resolve_internal_model + + +class OpenScenario2Parser(object): + """ Helper class for parsing openscenario 2 files """ + + def __init__(self, logger) -> None: + self.logger = logger + + def process_file(self, file, log_model: bool = False, debug: bool = False): + """ Convenience method to execute the parsing and print out tree """ + + parsed_tree, errors = self.parse_file(file, log_model) + if errors: + return None + + model = self.create_internal_model(parsed_tree, file, log_model, debug) + if model is None: + return None + + scenarios = create_py_tree(model, self.logger) + + return scenarios + + def load_internal_model(self, tree, file_name: str, log_model: bool = False, debug: bool = False): + model_builder = ModelBuilder(self.logger, self.parse_file, file_name, log_model) + walker = ParseTreeWalker() + + model = None + try: + walker.walk(model_builder, tree) + model = model_builder.get_model() + except OSC2ParsingError as e: + self.logger.error( + f'Error creating internal model: Traceback in "{e.filename}":\n -> {e.context}\n' + f'{e.__class__.__name__}: {e.msg}' + ) + if debug: + self.logger.info(str(e)) + return None + if log_model: + self.logger.info("----Internal model-----") + print_tree(model, self.logger) + return model + + def create_internal_model(self, tree, file_name: str, log_model: bool = False, debug: bool = False): + model = self.load_internal_model(tree, file_name, log_model, debug) + if model is None: + return None + + ret = resolve_internal_model(model, self.logger, log_model) + if ret: + return model + + return None + + def parse_file(self, file: str, log_model: bool = False, error_prefix=""): + """ Execute the parsing """ + try: + input_stream = FileStream(file) + except (OSError, UnicodeDecodeError) as e: + self.logger.error(f'{e}') + sys.exit(1) + return self.parse_input_stream(input_stream, log_model, error_prefix) + + def parse_input_stream(self, input_stream, log_model=False, error_prefix=""): + """ Execute the parsing """ + lexer = OpenSCENARIO2Lexer(input_stream) + stream = CommonTokenStream(lexer) + + parser = OpenSCENARIO2Parser(stream) + # if quiet: + parser.removeErrorListeners() + + class TestErrorListener(ErrorListener): + def __init__(self, prefix: str) -> None: + self.prefix = prefix + super().__init__() + + def syntaxError(self, recognizer, offendingSymbol, line, column, msg, e): # pylint: disable=invalid-name + print(self.prefix + "line " + str(line) + ":" + + str(column) + " " + msg, file=sys.stderr) + + parser.addErrorListener(TestErrorListener(error_prefix)) + tree = parser.osc_file() + errors = parser.getNumberOfSyntaxErrors() # pylint: disable=no-member + if log_model: + self.print_parsed_osc_tree(tree, self.logger, parser.ruleNames) + + del parser + return tree, errors + + @staticmethod + def print_parsed_osc_tree(tree, logger, rule_names, indent=0): + """ Print the parsed tree for debugging purposes """ + if isinstance(tree, TerminalNodeImpl): + if not re.match(r"\r?\n[ \t]*", tree.getText()): + logger.info("{0}TOKEN '{1}'".format(" " * indent, tree.getText())) + else: + logger.info("{0}{1}".format(" " * indent, rule_names[tree.getRuleIndex()])) + if tree.children: + for child in tree.children: + OpenScenario2Parser.print_parsed_osc_tree(child, logger, rule_names, indent+1) diff --git a/scenario_execution_base/scenario_execution_base/model/types.py b/scenario_execution_base/scenario_execution_base/model/types.py new file mode 100644 index 00000000..c71b3f04 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/model/types.py @@ -0,0 +1,2072 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from typing import List +from scenario_execution_base.model.error import OSC2ParsingError +import sys + + +def print_tree(elem, logger, whitespace=""): + + children = "" + for child in elem.get_children(): + if not isinstance(child, ModelElement): + children += f"{child} " + + logger.info(f"{whitespace}{elem}{children}") + + for child in elem.get_children(): + if isinstance(child, ModelElement): + print_tree(child, logger, whitespace + " ") + + +def serialize(elem): + result = {} + children = elem.get_children() + if children: + result[type(elem).__name__] = {} + args = elem.__init__.__code__.co_varnames[1:] + for arg in args: + try: + result[type(elem).__name__][arg] = elem.__dict__[arg] + except KeyError as e: + raise KeyError(f"Invalid key for element {type(elem).__name__}: {e}") from e + result[type(elem).__name__]['_children'] = [] + for child in children: + result[type(elem).__name__]['_children'].append(serialize(child)) + else: + result[type(elem).__name__] = {} + return result + + +def deserialize(elem): + types_module = sys.modules[__name__] + result = getattr(types_module, 'CompilationUnit')() + for current in elem: + for key, value in current.items(): + elem_attributes = {k: v for k, v in value.items() if k != '_children'} + module = getattr(types_module, key) + inst = module(**elem_attributes) + if '_children' in value: + children = deserialize(value['_children']) + for child_node in children.get_children(): + inst.set_children(child_node) + result.set_children(inst) + return result + + +class ModelElement(object): + def __init__(self, name=""): + self.__context = None # For error logging only + self.__line = None + self.__column = None + self.__filename = None + self.__children = [] # child node + self.__parent = None + self.name = name + self.iter = None + + def get_value_child(self): + return None + # raise NotImplementedError() + + def get_child_count(self): + return len(self.__children) + + def get_children(self): + if self.__children is not None: + for child in self.__children: + yield child + + def get_child(self, i): + return self.__children[i] + + def get_only_child(self): + if self.get_child_count() != 1: + raise ValueError(f"Expected only one child. Found {self.get_child_count()}") + return self.get_child(0) + + def set_children(self, *childs): + for child in childs: + if child is not None: + if isinstance(child, List): + for ch in child: + if isinstance(ch, ModelElement): + ch.__parent = self # pylint: disable=protected-access,unused-private-member + self.__children.append(ch) + else: + if isinstance(child, ModelElement): + child.__parent = self # pylint: disable=protected-access,unused-private-member + self.__children.append(child) + + def find_children_of_type(self, typename): + children_of_type = [] + for child in self.__children: + if isinstance(child, typename): + children_of_type.append(child) + elif isinstance(child, ModelElement): + children_of_type.extend(child.find_children_of_type(typename)) + return children_of_type + + def find_first_child_of_type(self, typename, unique=True): + found = None + for child in self.__children: + if isinstance(child, typename): + if unique and found is not None: + raise ValueError(f"Child of type {typename} not unique.") + found = child + return found + + def get_child_with_expected_type(self, pos, typename): + child = self.get_child(pos) + if not isinstance(child, typename): + raise OSC2ParsingError( + msg=f'Child at pos {pos} is expected to be of type {typename.__name__}, but is {type(child).__name__}.', context=child.get_ctx()) + return child + + def find_parent(self, typename): + if self.get_parent() is not None: + child = self.get_parent().find_first_child_of_type(typename) + if child: + return child + else: + return self.get_parent().find_parent(typename) + return None + + def find_reference_by_name(self, name, visited): + + for child in self.__children: + if isinstance(child, ModelElement) and child not in visited: + visited.append(child) + if child.name == name: + return child + + if self.get_parent(): + found = self.get_parent().find_reference_by_name(name, visited) + if found: + return found + return None + + def resolve(self, name): + visited = [self] + if self.get_parent() is not None: + return self.get_parent().find_reference_by_name(name, visited) + return None + + def get_parent(self): + return self.__parent + + def delete_child(self, child): + self.__children.remove(child) + + def set_loc(self, line, column): + self.__line = line + self.__column = column + + def set_ctx(self, ctx, filename: str): + self.__line = ctx.start.line + self.__column = ctx.start.column + self.__context = ctx.getText() + self.__filename = filename + + def get_ctx(self): + return self.__line, self.__column, self.__context, self.__filename + + def accept(self, visitor): + pass + + def enter_node(self, listener): + pass + + def exit_node(self, listener): + pass + + def __iter__(self): + self.iter = iter(self.__children) + return self.iter + + def __next__(self): + return next(self.iter) + + def __str__(self) -> str: + output = f"{self.__class__.__name__}({self.name})" + first = True + for attr in vars(self): + if not attr.startswith('_') and attr != "name" and attr != "iter": + if first: + output += ": " + first = False + else: + output += ", " + output += attr + + attr_val = getattr(self, attr) + if isinstance(attr_val, ModelElement): + output += "=" + f"{attr_val.__class__.__name__}({attr_val.name})" + else: + output += "=" + str(attr_val) + return output + + +class CompilationUnit(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_compilation_unit"): + listener.enter_compilation_unit(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_compilation_unit"): + listener.exit_compilation_unit(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_compilation_unit"): + return visitor.visit_compilation_unit(self) + else: + return visitor.visit_children(self) + + +def merge_nested_dicts(dict1, dict2, key_must_exist=True): + for key, value in dict2.items(): + if key_must_exist and key not in dict1: + raise ValueError(f"Key not found {key}") + if key in dict1 and isinstance(dict1[key], dict) and isinstance(value, dict): + merge_nested_dicts(dict1[key], value, key_must_exist) + else: + dict1[key] = value + + +class Declaration(ModelElement): + + def __init__(self, name=""): + super().__init__(name) + self.base_type = None + self.values = {} + + def get_declaration_string(self): + return f"base_type: {self.base_type}, values: {self.values}" + + def get_qualified_name(self): + res = "" + current = self + while current: + if current.name: + res = "/" + current.name + res + current = current.get_parent() + return res + + def get_base_type(self): + return None + + def get_resolved_value(self): + return None + + def get_type_string(self): + return self.name + + +class Parameter(Declaration): + + def get_value_child(self): + if self.get_child_count() != 2: + return None + + for child in self.get_children(): + if isinstance(child, (StringLiteral, FloatLiteral, BoolLiteral, IntegerLiteral, FunctionApplicationExpression, IdentifierReference, PhysicalLiteral, EnumValueReference, ListExpression)): + return child + return None + + def get_resolved_value(self): + param_type, is_list = self.get_type() + vals = {} + params = {} + if self.get_value_child(): + vals = self.get_value_child().get_resolved_value() + + if isinstance(param_type, StructuredDeclaration) and not is_list: + params = param_type.get_resolved_value() + merge_nested_dicts(params, vals) + else: + params = vals + + for child in self.get_children(): + if isinstance(child, KeepConstraintDeclaration): # for variable only? + tmp = child.get_resolved_value() + merge_nested_dicts(params, tmp) + return params + + def get_type(self): + declared_type = self.find_first_child_of_type(Type) + return declared_type.type_def, declared_type.is_list + + def get_type_string(self): + val_type, is_list = self.get_type() + + if isinstance(val_type, ModelElement): + val_type = val_type.get_type_string() + if is_list: + val_type = 'listof' + val_type + return val_type + + +class StructuredDeclaration(Declaration): + + def get_parameter_names(self): + names = [] + + if self.get_base_type(): + names = self.get_base_type().get_parameter_names() + + for child in self.get_children(): + if isinstance(child, ParameterDeclaration): + names.append(child.name) + return list(set(names)) + + def get_resolved_value(self): + params = {} + + # set values defined in base type + if self.get_base_type(): + params = self.get_base_type().get_resolved_value() + + named = False + pos = 0 + param_keys = list(params.keys()) + for child in self.get_children(): + if isinstance(child, ParameterDeclaration): + param_type, _ = child.get_type() + + # set values defined in type itself + if isinstance(param_type, ModelElement): + params[child.name] = param_type.get_resolved_value() + + # set values from parameter value + val = child.get_value_child() + if val: + if isinstance(val, KeepConstraintDeclaration): + tmp = val.get_resolved_value() + for key, val in tmp.items(): + if key not in params: + raise OSC2ParsingError( + msg=f'Keep Constraint Declaration specifies unknown member "{key}".', context=self.get_ctx()) + else: + params[key] = val + else: + params[child.name] = val.get_resolved_value() + else: + if child.name not in params: + params[child.name] = None + elif isinstance(child, PositionalArgument): + if named: + raise OSC2ParsingError( + msg=f'Positional argument after named argument not allowed.', context=child.get_ctx()) + params[param_keys[pos]] = child.get_resolved_value() + pos += 1 + elif isinstance(child, NamedArgument): + named = True + params[child.name] = child.get_resolved_value() + elif isinstance(child, KeepConstraintDeclaration): # for behaviorinvocation only? + tmp = child.get_resolved_value() + merge_nested_dicts(params, tmp, key_must_exist=False) + + return params + + def get_type(self): + return self, False + + def get_type_string(self): + return self.name + + +class Expression(ModelElement): + pass + + +class PhysicalTypeDeclaration(Declaration): + + def __init__(self, type_name): + super().__init__(type_name) + self.type_name = type_name + + def enter_node(self, listener): + if hasattr(listener, "enter_physical_type_declaration"): + listener.enter_physical_type_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_physical_type_declaration"): + listener.exit_physical_type_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_physical_type_declaration"): + return visitor.visit_physical_type_declaration(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + return None + + def get_type_string(self): + return self.type_name + + +class UnitDeclaration(Declaration): + + def __init__(self, unit_name, physical_name): + super().__init__(unit_name) + self.unit_name = unit_name + self.physical_name = physical_name + + def enter_node(self, listener): + if hasattr(listener, "enter_unit_declaration"): + listener.enter_unit_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_unit_declaration"): + listener.exit_unit_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_unit_declaration"): + return visitor.visit_unit_declaration(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + return self.physical_name.name + + +class SIUnitSpecifier(ModelElement): + + def __init__(self, factor, offset): + super().__init__() + self.factor = factor + self.offset = offset + + def enter_node(self, listener): + if hasattr(listener, "enter_si_unit_specifier"): + listener.enter_si_unit_specifier(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_si_unit_specifier"): + listener.exit_si_unit_specifier(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_si_unit_specifier"): + return visitor.visit_si_unit_specifier(self) + else: + return visitor.visit_children(self) + + +class SIBaseExponent(ModelElement): + + def __init__(self, unit_name): + super().__init__() + self.unit_name = unit_name + + def enter_node(self, listener): + if hasattr(listener, "enter_si_base_exponent"): + listener.enter_si_base_exponent(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_si_base_exponent"): + listener.exit_si_base_exponent(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_si_base_exponent"): + return visitor.visit_si_base_exponent(self) + else: + return visitor.visit_children(self) + + +class EnumDeclaration(Declaration): + + def __init__(self, enum_name): + super().__init__(enum_name) + self.enum_name = enum_name + + def enter_node(self, listener): + if hasattr(listener, "enter_enum_declaration"): + listener.enter_enum_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_enum_declaration"): + listener.exit_enum_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_enum_declaration"): + return visitor.visit_enum_declaration(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + return None + + +class EnumMemberDeclaration(Declaration): + + def __init__(self, member_name, numeric_value): + super().__init__() + self.member_name = member_name + self.numeric_value = numeric_value + + def enter_node(self, listener): + if hasattr(listener, "enter_enum_member_decl"): + listener.enter_enum_member_decl(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_enum_member_decl"): + listener.exit_enum_member_decl(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_enum_member_decl"): + return visitor.visit_enum_member_declaration(self) + else: + return visitor.visit_children(self) + + +class EnumValueReference(ModelElement): + + def __init__(self, enum_name, enum_member_name): + super().__init__() + self.enum_name = enum_name + self.enum_member_name = enum_member_name + + def enter_node(self, listener): + if hasattr(listener, "enter_enum_value_reference"): + listener.enter_enum_value_reference(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_enum_value_reference"): + listener.exit_enum_value_reference(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_enum_value_reference"): + return visitor.visit_enum_value_reference(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + return self.enum_name.name + + def get_resolved_value(self): + return (self.enum_member_name.member_name, self.enum_member_name.numeric_value) + + +class InheritsCondition(ModelElement): + + def __init__(self, field_name, bool_literal): + super().__init__() + self.field_name = field_name + + def enter_node(self, listener): + if hasattr(listener, "enter_inherits_condition"): + listener.enter_inherits_condition(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_inherits_condition"): + listener.exit_inherits_condition(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_inherits_condition"): + return visitor.visit_inherits_condition(self) + else: + return visitor.visit_children(self) + + +class StructDeclaration(StructuredDeclaration): + + def __init__(self, struct_name): + super().__init__(struct_name) + self.struct_name = struct_name + + def enter_node(self, listener): + if hasattr(listener, "enter_struct_declaration"): + listener.enter_struct_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_struct_declaration"): + listener.exit_struct_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_struct_declaration"): + return visitor.visit_struct_declaration(self) + else: + return visitor.visit_children(self) + + def get_base_type(self): + inherits = self.find_first_child_of_type(StructInherits) + if inherits: + return inherits.struct_name + return None + + +class Inheritance(ModelElement): + + def __init__(self): + super().__init__() + + +class StructInherits(Inheritance): + + def __init__(self, struct_name): + super().__init__() + self.struct_name = struct_name + + def enter_node(self, listener): + if hasattr(listener, "enter_struct_inherits"): + listener.enter_struct_inherits(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_struct_inherits"): + listener.exit_struct_inherits(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_struct_inherits"): + return visitor.visit_struct_inherits(self) + else: + return visitor.visit_children(self) + + +class ActorDeclaration(StructuredDeclaration): + + def __init__(self, actor): + super().__init__(actor) + self.actor = actor + + def enter_node(self, listener): + if hasattr(listener, "enter_actor_declaration"): + listener.enter_actor_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_actor_declaration"): + listener.exit_actor_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_actor_declaration"): + return visitor.visit_actor_declaration(self) + else: + return visitor.visit_children(self) + + def get_base_type(self): + inherits = self.find_first_child_of_type(ActorInherits) + if inherits: + return inherits.actor + return None + + +class ActorInherits(Inheritance): + + def __init__(self, actor): + super().__init__() + self.actor = actor + + def enter_node(self, listener): + if hasattr(listener, "enter_actor_inherits"): + listener.enter_actor_inherits(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_actor_inherits"): + listener.exit_actor_inherits(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_actor_inherits"): + return visitor.visit_actor_inherits(self) + else: + return visitor.visit_children(self) + + +class ScenarioDeclaration(StructuredDeclaration): + + def __init__(self, qualified_behavior_name): + super().__init__(qualified_behavior_name) + self.qualified_behavior_name = qualified_behavior_name + + def enter_node(self, listener): + if hasattr(listener, "enter_scenario_declaration"): + listener.enter_scenario_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_scenario_declaration"): + listener.exit_scenario_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_scenario_declaration"): + return visitor.visit_scenario_declaration(self) + else: + return visitor.visit_children(self) + + def get_base_type(self): + inherits = self.find_first_child_of_type(ScenarioInherits) + if inherits: + return inherits.qualified_behavior_name + return None + + +class ScenarioInherits(Inheritance): + + def __init__(self, qualified_behavior_name): + super().__init__() + self.qualified_behavior_name = qualified_behavior_name + + def enter_node(self, listener): + if hasattr(listener, "enter_scenario_inherits"): + listener.enter_scenario_inherits(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_scenario_inherits"): + listener.exit_scenario_inherits(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_scenario_inherits"): + return visitor.visit_scenario_inherits(self) + else: + return visitor.visit_children(self) + + +class ActionDeclaration(StructuredDeclaration): + + def __init__(self, qualified_behavior_name): + self.actor = None + super().__init__(qualified_behavior_name) + self.qualified_behavior_name = qualified_behavior_name + + def enter_node(self, listener): + if hasattr(listener, "enter_action_declaration"): + listener.enter_action_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_action_declaration"): + listener.exit_action_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_action_declaration"): + return visitor.visit_action_declaration(self) + else: + return visitor.visit_children(self) + + def get_base_type(self): + inherits = self.find_first_child_of_type(ActionInherits) + if inherits: + return inherits.qualified_behavior_name + return None + + +class ActionInherits(Inheritance): + + def __init__(self, qualified_behavior_name): + super().__init__() + self.qualified_behavior_name = qualified_behavior_name + + def enter_node(self, listener): + if hasattr(listener, "enter_action_inherits"): + listener.enter_action_inherits(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_action_inherits"): + listener.exit_action_inherits(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_action_inherits"): + return visitor.visit_action_inherits(self) + else: + return visitor.visit_children(self) + + +class ModifierDeclaration(Declaration): + + def __init__(self, actor_name, modifier_name): + super().__init__() + self.actor = actor_name + self.modifier = modifier_name + + def enter_node(self, listener): + if hasattr(listener, "enter_modifier_declaration"): + listener.enter_modifier_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_modifier_declaration"): + listener.exit_modifier_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_modifier_declaration"): + return visitor.visit_modifier_declaration(self) + else: + return visitor.visit_children(self) + + +class EnumTypeExtension(Declaration): + + def __init__(self, enum_name): + super().__init__() + self.enum_name = enum_name + + def enter_node(self, listener): + if hasattr(listener, "enter_enum_type_extension"): + listener.enter_enum_type_extension(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_enum_type_extension"): + listener.exit_enum_type_extension(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_enum_type_extension"): + return visitor.visit_enum_type_extension(self) + else: + return visitor.visit_children(self) + + +class StructuredTypeExtension(Declaration): + + def __init__(self, type_name, qualified_behavior_name): + super().__init__() + self.type_name = type_name + self.qualified_behavior_name = qualified_behavior_name + + def enter_node(self, listener): + if hasattr(listener, "enter_structured_type_extension"): + listener.enter_structured_type_extension(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_structured_type_extension"): + listener.exit_structured_type_extension(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_structured_type_extension"): + return visitor.visit_structured_type_extension(self) + else: + return visitor.visit_children(self) + + +class GlobalParameterDeclaration(Parameter): + + def __init__(self, name, field_name, field_type, default_value): + super().__init__(name) + self.field_name = field_name + self.field_type = field_type + self.default_value = default_value + + def enter_node(self, listener): + if hasattr(listener, "enter_global_parameter_declaration"): + listener.enter_global_parameter_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_global_parameter_declaration"): + listener.exit_global_parameter_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_global_parameter_declaration"): + return visitor.visit_global_parameter_declaration(self) + else: + return visitor.visit_children(self) + + +class ParameterDeclaration(Parameter): + + def __init__(self, field_name, field_type, default_value): + super().__init__(field_name) + self.field_name = field_name + self.field_type = field_type + self.default_value = default_value + + def enter_node(self, listener): + if hasattr(listener, "enter_parameter_declaration"): + listener.enter_parameter_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_parameter_declaration"): + listener.exit_parameter_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_parameter_declaration"): + return visitor.visit_parameter_declaration(self) + else: + return visitor.visit_children(self) + + +class ParameterReference(ModelElement): + + def __init__(self, field_name, field_access): + super().__init__() + self.field_name = field_name + self.field_access = field_access + + def enter_node(self, listener): + if hasattr(listener, "enter_parameter_reference"): + listener.enter_parameter_reference(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_parameter_reference"): + listener.exit_parameter_reference(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_parameter_reference"): + return visitor.visit_parameter_reference(self) + else: + return visitor.visit_children(self) + + +class EventDeclaration(Declaration): + + def __init__(self, event_name): + super().__init__(event_name) + self.field_name = event_name + + def enter_node(self, listener): + if hasattr(listener, "enter_event_declaration"): + listener.enter_event_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_event_declaration"): + listener.exit_event_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_event_declaration"): + return visitor.visit_event_declaration(self) + else: + return visitor.visit_children(self) + + +class EventReference(ModelElement): + + def __init__(self, event_path): + super().__init__() + self.event_path = event_path + + def enter_node(self, listener): + if hasattr(listener, "enter_event_reference"): + listener.enter_event_reference(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_event_reference"): + listener.exit_event_reference(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_event_reference"): + return visitor.visit_event_reference(self) + else: + return visitor.visit_children(self) + + +class EventFieldDecl(ModelElement): + + def __init__(self, event_field_name): + super().__init__() + self.event_field_name = event_field_name + + def enter_node(self, listener): + if hasattr(listener, "enter_event_field_declaration"): + listener.enter_event_field_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_event_field_declaration"): + listener.exit_event_field_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_event_field_declaration"): + return visitor.visit_event_field_declaration(self) + else: + return visitor.visit_children(self) + + +class EventCondition(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_event_condition"): + listener.enter_event_condition(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_event_condition"): + listener.exit_event_condition(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_event_condition"): + return visitor.visit_event_condition(self) + else: + return visitor.visit_children(self) + + +class MethodDeclaration(Declaration): + + def __init__(self, method_name, return_type): + super().__init__() + self.method_name = method_name + self.return_type = return_type + + def enter_node(self, listener): + if hasattr(listener, "enter_method_declaration"): + listener.enter_method_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_method_declaration"): + listener.exit_method_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_method_declaration"): + return visitor.visit_method_declaration(self) + else: + return visitor.visit_children(self) + + +class MethodBody(ModelElement): + + def __init__(self, qualifier, type_ref, external_name): + super().__init__() + self.qualifier = qualifier + self.type_ref = type_ref + self.external_name = external_name + + def enter_node(self, listener): + if hasattr(listener, "enter_method_body"): + listener.enter_method_body(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_method_body"): + listener.exit_method_body(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_method_body"): + return visitor.visit_method_body(self) + else: + return visitor.visit_children(self) + + +class CoverDeclaration(Declaration): + + def __init__(self, target_name): + super().__init__() + self.target_name = target_name + + def enter_node(self, listener): + if hasattr(listener, "enter_cover_declaration"): + listener.enter_cover_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_cover_declaration"): + listener.exit_cover_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_cover_declaration"): + return visitor.visit_cover_declaration(self) + else: + return visitor.visit_children(self) + + +class RecordDeclaration(Declaration): + + def __init__(self, target_name): + super().__init__() + self.target_name = target_name + + def enter_node(self, listener): + if hasattr(listener, "enter_record_declaration"): + listener.enter_record_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_record_declaration"): + listener.exit_record_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_record_declaration"): + return visitor.visit_record_declaration(self) + else: + return visitor.visit_children(self) + + +class Argument(ModelElement): + + def __init__(self, argument_name, argument_type, default_value): + super().__init__() + self.argument_name = argument_name + self.argument_type = argument_type + self.default_value = default_value + + def enter_node(self, listener): + if hasattr(listener, "enter_argument"): + listener.enter_argument(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_argument"): + listener.exit_argument(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_argument"): + return visitor.visit_argument(self) + else: + return visitor.visit_children(self) + + +class NamedArgument(ModelElement): + + def __init__(self, argument_name): + super().__init__(argument_name) + self.argument_name = argument_name + + def enter_node(self, listener): + if hasattr(listener, "enter_named_argument"): + listener.enter_named_argument(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_named_argument"): + listener.exit_named_argument(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_named_argument"): + return visitor.visit_named_argument(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + if self.get_child_count() != 1: + raise OSC2ParsingError( + msg=f'Could not get value of positional argument because the expected child count is not 1, but {self.get_child_count()}.', context=self.get_ctx()) + return self.get_child(0).get_resolved_value() + + +class PositionalArgument(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_positional_argument"): + listener.enter_positional_argument(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_positional_argument"): + listener.exit_positional_argument(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_positional_argument"): + return visitor.visit_positional_argument(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + if self.get_child_count() != 1: + raise OSC2ParsingError( + msg=f'Could not get value of positional argument because the expected child count is not 1, but {self.get_child_count()}.', context=self.get_ctx()) + return self.get_child(0).get_resolved_value() + + +class VariableDeclaration(Parameter): + + def __init__(self, field_name, field_type, default_value): + super().__init__() + self.field_name = field_name # unused? + self.field_type = field_type + self.default_value = default_value + # self.set_children(field_name) + + def enter_node(self, listener): + if hasattr(listener, "enter_variable_declaration"): + listener.enter_variable_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_variable_declaration"): + listener.exit_variable_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_variable_declaration"): + return visitor.visit_variable_declaration(self) + else: + return visitor.visit_children(self) + + +class KeepConstraintDeclaration(Declaration): + + def __init__(self, constraint_qualifier): + super().__init__() + self.constraint_qualifier = constraint_qualifier + + def enter_node(self, listener): + if hasattr(listener, "enter_keep_constraint_declaration"): + listener.enter_keep_constraint_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_keep_constraint_declaration"): + listener.exit_keep_constraint_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_keep_constraint_declaration"): + return visitor.visit_keep_constraint_declaration(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + result = None + if self.get_child_count() == 1 and isinstance(self.get_child(0), RelationExpression) and self.get_child(0).get_child_count() == 2: + if self.get_child(0).operator != "==": + raise OSC2ParsingError( + msg=f'Only relation "==" is currently supported in "keep".', context=self.get_ctx()) + field_exp = self.get_child(0).get_child_with_expected_type(0, FieldAccessExpression) + value = self.get_child(0).get_child(1).get_resolved_value() + + if not field_exp.field_name.startswith('it.'): + raise OSC2ParsingError( + msg=f'FieldAccessExpression only supports "it." prefix, not "{field_exp.field_name}".', context=self.get_ctx()) + field_name = field_exp.field_name.removeprefix("it.") + result = {} + member_path = field_name.split('.') + current_params = result + for current_pos in range(0, len(member_path)): # pylint: disable=consider-using-enumerate + if current_pos != len(member_path) - 1: + current_params[member_path[current_pos]] = {} + current_params = current_params[member_path[current_pos]] + else: + current_params[member_path[current_pos]] = value + else: + raise OSC2ParsingError( + msg=f'Keep uses unsupported expression: allowed "==" only.', context=self.get_ctx()) + + if result is None: + raise OSC2ParsingError( + msg=f'Error in keep constraint declaration.', context=self.get_ctx()) + + return result + + +class RemoveDefaultDeclaration(Declaration): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_remove_default_declaration"): + listener.enter_remove_default_declaration(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_remove_default_declaration"): + listener.exit_remove_default_declaration(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_remove_default_declaration"): + return visitor.visit_remove_default_declaration(self) + else: + return visitor.visit_children(self) + + +class OnDirective(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_on_directive"): + listener.enter_on_directive(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_on_directive"): + listener.exit_on_directive(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_on_directive"): + return visitor.visit_on_directive(self) + else: + return visitor.visit_children(self) + + +class DoDirective(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_do_directive"): + listener.enter_do_directive(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_do_directive"): + listener.exit_do_directive(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_do_directive"): + return visitor.visit_do_directive(self) + else: + return visitor.visit_children(self) + + +class DoMember(ModelElement): + + def __init__(self, label_name, composition_operator): + super().__init__(label_name) + self.label_name = label_name + self.composition_operator = composition_operator + + def enter_node(self, listener): + if hasattr(listener, "enter_do_member"): + listener.enter_do_member(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_do_member"): + listener.exit_do_member(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_do_member"): + return visitor.visit_do_member(self) + else: + return visitor.visit_children(self) + + +class WaitDirective(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_wait_directive"): + listener.enter_wait_directive(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_wait_directive"): + listener.exit_wait_directive(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_wait_directive"): + return visitor.visit_wait_directive(self) + else: + return visitor.visit_children(self) + + +class EmitDirective(ModelElement): + + def __init__(self, event_name): + super().__init__(event_name) + self.event_name = event_name + + def enter_node(self, listener): + if hasattr(listener, "enter_emit_directive"): + listener.enter_emit_directive(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_emit_directive"): + listener.exit_emit_directive(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_emit_directive"): + return visitor.visit_emit_directive(self) + else: + return visitor.visit_children(self) + + +class CallDirective(ModelElement): + + def __init__(self, method_name): + super().__init__() + self.method_name = method_name + + def enter_node(self, listener): + if hasattr(listener, "enter_call_directive"): + listener.enter_call_directive(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_call_directive"): + listener.exit_call_directive(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_call_directive"): + return visitor.visit_call_directive(self) + else: + return visitor.visit_children(self) + + +class UntilDirective(ModelElement): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_until_directive"): + listener.enter_until_directive(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_until_directive"): + listener.exit_until_directive(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_until_directive"): + return visitor.visit_until_directive(self) + else: + return visitor.visit_children(self) + + +class BehaviorInvocation(StructuredDeclaration): + + def __init__(self, name, actor, behavior): + super().__init__(name) + self.actor = actor + self.behavior = behavior + + def enter_node(self, listener): + if hasattr(listener, "enter_behavior_invocation"): + listener.enter_behavior_invocation(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_behavior_invocation"): + listener.exit_behavior_invocation(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_behavior_invocation"): + return visitor.visit_behavior_invocation(self) + else: + return visitor.visit_children(self) + + def get_base_type(self): + return self.behavior + + def get_type(self): + return self.behavior, False + + +class ModifierInvocation(ModelElement): + + def __init__(self, actor, modifier_name): + super().__init__() + self.actor = actor + self.modifier_name = modifier_name + # self.set_children(actor, modifier_name) + + def enter_node(self, listener): + if hasattr(listener, "enter_modifier_invocation"): + listener.enter_modifier_invocation(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_modifier_invocation"): + listener.exit_modifier_invocation(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_modifier_invocation"): + return visitor.visit_modifier_invocation(self) + else: + return visitor.visit_children(self) + + +class RiseExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_rise_expression"): + listener.enter_rise_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_rise_expression"): + listener.exit_rise_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_rise_expression"): + return visitor.visit_rise_expression(self) + else: + return visitor.visit_children(self) + + +class FallExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_fall_expression"): + listener.enter_rise_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_fall_expression"): + listener.exit_fall_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_fall_expression"): + return visitor.visit_fall_expression(self) + else: + return visitor.visit_children(self) + + +class ElapsedExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_elapsed_expression"): + listener.enter_rise_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_elapsed_expression"): + listener.exit_fall_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_elapsed_expression"): + return visitor.visit_fall_expression(self) + else: + return visitor.visit_children(self) + + +class EveryExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_every_expression"): + listener.enter_every_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_every_expression"): + listener.exit_every_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_every_expression"): + return visitor.visit_every_expression(self) + else: + return visitor.visit_children(self) + + +class SampleExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_sample_expression"): + listener.enter_sample_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_sample_expression"): + listener.exit_sample_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_sample_expression"): + return visitor.visit_sample_expression(self) + else: + return visitor.visit_children(self) + + +class CastExpression(Expression): + + def __init__(self, object_def, target_type): + super().__init__() + self.object_def = object_def + self.target_type = target_type + + def enter_node(self, listener): + if hasattr(listener, "enter_cast_expression"): + listener.enter_cast_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_cast_expression"): + listener.exit_cast_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_cast_expression"): + return visitor.visit_cast_expression(self) + else: + return visitor.visit_children(self) + + +class TypeTestExpression(Expression): + + def __init__(self, object_def, target_type): + super().__init__() + self.object_def = object_def + self.target_type = target_type + + def enter_node(self, listener): + if hasattr(listener, "enter_type_test_expression"): + listener.enter_type_test_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_type_test_expression"): + listener.exit_type_test_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_type_test_expression"): + return visitor.visit_type_test_expression(self) + else: + return visitor.visit_children(self) + + +class ElementAccessExpression(Expression): + + def __init__(self, list_name, index): + super().__init__() + self.list_name = list_name + self.index = index + + def enter_node(self, listener): + if hasattr(listener, "enter_element_access_expression"): + listener.enter_element_access_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_element_access_expression"): + listener.exit_element_access_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_element_access_expression"): + return visitor.visit_element_access_expression(self) + else: + return visitor.visit_children(self) + + +class FunctionApplicationExpression(Expression): + + def __init__(self, func_name): + super().__init__() + self.func_name = func_name + + def enter_node(self, listener): + if hasattr(listener, "enter_function_application_expression"): + listener.enter_function_application_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_function_application_expression"): + listener.exit_function_application_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_function_application_expression"): + return visitor.visit_function_application_expression(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + ref = self.find_first_child_of_type(IdentifierReference) + params = ref.get_resolved_value() + + named = False + pos = 0 + param_keys = list(params.keys()) + for child in self.get_children(): + key = None + if isinstance(child, PositionalArgument): + if named: + raise OSC2ParsingError( + msg=f'Positional argument after named argument not allowed.', context=child.get_ctx()) + key = param_keys[pos] + elif isinstance(child, NamedArgument): + named = True + key = child.name + if key: + params[key] = child.get_resolved_value() + return params + + def get_type(self): + ref = self.find_first_child_of_type(IdentifierReference) + return ref.get_type() + + def get_type_string(self): + return self.get_type()[0].name + + +class FieldAccessExpression(Expression): + + def __init__(self, field_name): + super().__init__() + self.field_name = field_name + + def enter_node(self, listener): + if hasattr(listener, "enter_field_access_expression"): + listener.enter_field_access_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_field_access_expression"): + listener.exit_field_access_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_field_access_expression"): + return visitor.visit_field_access_expression(self) + else: + return visitor.visit_children(self) + + +class BinaryExpression(Expression): + + def __init__(self, operator): + super().__init__() + self.operator = operator + + def enter_node(self, listener): + if hasattr(listener, "enter_binary_expression"): + listener.enter_binary_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_binary_expression"): + listener.exit_binary_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_binary_expression"): + return visitor.visit_binary_expression(self) + else: + return visitor.visit_children(self) + + +class UnaryExpression(Expression): + + def __init__(self, operator): + super().__init__() + self.operator = operator + + def enter_node(self, listener): + if hasattr(listener, "enter_unary_expression"): + listener.enter_unary_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_unary_expression"): + listener.exit_unary_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_unary_expression"): + return visitor.visit_unary_expression(self) + else: + return visitor.visit_children(self) + + +class TernaryExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_ternary_expression"): + listener.enter_ternary_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_ternary_expression"): + listener.exit_ternary_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_ternary_expression"): + return visitor.visit_ternary_expression(self) + else: + return visitor.visit_children(self) + + +class LogicalExpression(Expression): + + def __init__(self, operator): + super().__init__() + self.operator = operator + + def enter_node(self, listener): + if hasattr(listener, "enter_logical_expression"): + listener.enter_logical_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_logical_expression"): + listener.exit_logical_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_logical_expression"): + return visitor.visit_logical_expression(self) + else: + return visitor.visit_children(self) + + +class RelationExpression(Expression): + + def __init__(self, operator): + super().__init__() + self.operator = operator + + def enter_node(self, listener): + if hasattr(listener, "enter_relation_expression"): + listener.enter_relation_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_relation_expression"): + listener.exit_relation_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_relation_expression"): + return visitor.visit_relation_expression(self) + else: + return visitor.visit_children(self) + + +class ListExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_list_expression"): + listener.enter_list_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_list_expression"): + listener.exit_list_literal(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_list_expression"): + return visitor.visit_list_expression(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + child = None + if self.get_child_count(): + child = self.get_child(0) + if not child: + raise OSC2ParsingError(msg='At least on child expected.', context=self.get_ctx()) + type_string = child.get_type_string() + return "listof" + type_string + + def get_resolved_value(self): + value = [] + for child in self.get_children(): + value.append(child.get_resolved_value()) + return value + + +class RangeExpression(Expression): + + def __init__(self): + super().__init__() + + def enter_node(self, listener): + if hasattr(listener, "enter_range_expression"): + listener.enter_range_expression(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_range_expression"): + listener.exit_range_expression(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_range_expression"): + return visitor.visit_range_expression(self) + else: + return visitor.visit_children(self) + + +class PhysicalLiteral(ModelElement): + + def __init__(self, unit, value): + super().__init__() + self.value = value + self.unit = unit + + def enter_node(self, listener): + if hasattr(listener, "enter_physical_literal"): + listener.enter_physical_literal(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_physical_literal"): + listener.exit_physical_literal(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_physical_literal"): + return visitor.visit_physical_literal(self) + else: + return visitor.visit_children(self) + + def get_value_child(self): + return self.get_child(0) + + def get_type_string(self): + return self.unit.get_type_string() + + def get_resolved_value(self): + si_unit_specifier = self.unit.find_first_child_of_type(SIUnitSpecifier) + return self.get_value_child().get_resolved_value() * si_unit_specifier.factor + + +class IntegerLiteral(ModelElement): + + def __init__(self, type_def, value): + super().__init__() + self.type_def = type_def # uint, hex, int + self.value = value + + def enter_node(self, listener): + if hasattr(listener, "enter_integer_literal"): + listener.enter_integer_literal(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_integer_literal"): + listener.exit_integer_literal(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_integer_literal"): + return visitor.visit_integer_literal(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + return 'int' + + def get_resolved_value(self): + return int(self.value) + + +class FloatLiteral(ModelElement): + + def __init__(self, value): + super().__init__() + self.value = value + + def enter_node(self, listener): + if hasattr(listener, "enter_float_literal"): + listener.enter_float_literal(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_float_literal"): + listener.exit_float_literal(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_float_literal"): + return visitor.visit_float_literal(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + return 'float' + + def get_resolved_value(self): + return float(self.value) + + +class BoolLiteral(ModelElement): + + def __init__(self, value): + super().__init__() + self.value = value + + def enter_node(self, listener): + if hasattr(listener, "enter_bool_literal"): + listener.enter_bool_literal(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_bool_literal"): + listener.exit_bool_literal(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_bool_literal"): + return visitor.visit_bool_literal(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + return 'bool' + + def get_resolved_value(self): + return self.value == "true" + + +class StringLiteral(ModelElement): + + def __init__(self, value): + super().__init__() + self.value = value + + def get_value_child(self): + return self.value + + def get_resolved_value(self): + return self.value.strip("\'").strip("\"") + + def enter_node(self, listener): + if hasattr(listener, "enter_string_literal"): + listener.enter_string_literal(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_string_literal"): + listener.exit_string_literal(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_string_literal"): + return visitor.visit_string_literal(self) + else: + return visitor.visit_children(self) + + def get_type_string(self): + return 'string' + + +class Type(ModelElement): + + def __init__(self, type_def, is_list): + super().__init__() + self.type_def = type_def + self.is_list = is_list + + def enter_node(self, listener): + if hasattr(listener, "enter_type"): + listener.enter_type(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_type"): + listener.exit_type(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_type"): + return visitor.visit_type(self) + else: + return visitor.visit_children(self) + + def get_resolved_value(self): + return None + + +class Identifier(ModelElement): + + def __init__(self, name): + super().__init__() + self.name = name + + def enter_node(self, listener): + if hasattr(listener, "enter_identifier"): + listener.enter_identifier(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_identifier"): + listener.exit_identifier(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_identifier"): + return visitor.visit_identifier(self) + else: + return visitor.visit_children(self) + + +class IdentifierReference(ModelElement): + + def __init__(self, ref): + super().__init__() + self.ref = ref + + def enter_node(self, listener): + if hasattr(listener, "enter_identifier_reference"): + listener.enter_identifier_reference(self) + + def exit_node(self, listener): + if hasattr(listener, "exit_identifier_reference"): + listener.exit_identifier_reference(self) + + def accept(self, visitor): + if hasattr(visitor, "visit_identifier_reference"): + return visitor.visit_identifier_reference(self) + else: + return visitor.visit_children(self) + + def get_type(self): + return self.ref.get_type() + + def get_type_string(self): + return self.ref.get_type_string() + + def get_resolved_value(self): + return self.ref.get_resolved_value() diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/.gitignore b/scenario_execution_base/scenario_execution_base/osc2_parsing/.gitignore new file mode 100644 index 00000000..91827d60 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/.gitignore @@ -0,0 +1 @@ +.antlr/ \ No newline at end of file diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.g4 b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.g4 new file mode 100644 index 00000000..e0fcd429 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.g4 @@ -0,0 +1,759 @@ +// MIT License + +// Copyright (c) 2018 CARLA + +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: + +// The above copyright notice and this permission notice shall be included in all +// copies or substantial portions of the Software. + +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. + +// Copyright (C) 2024 Intel Corporation + +// 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. + +// SPDX-License-Identifier: Apache-2.0 + +grammar OpenSCENARIO2; + +tokens { INDENT, DEDENT} + + +@lexer::header{ +from antlr4.Token import CommonToken +import re +import importlib +# Allow languages to extend the lexer and parser, by loading the parser dynamically +module_path = __name__[:-5] +language_name = __name__.split('.')[-1] +language_name = language_name[:-5] # Remove Lexer from name +LanguageParser = getattr(importlib.import_module('{}Parser'.format(module_path)), '{}Parser'.format(language_name)) +} + +@lexer::members { + +@property +def tokens(self): + try: + return self._tokens + except AttributeError: + self._tokens = [] + return self._tokens + +@property +def indents(self): + try: + return self._indents + except AttributeError: + self._indents = [] + return self._indents + +@property +def opened(self): + try: + return self._opened + except AttributeError: + self._opened = 0 + return self._opened + +@opened.setter +def opened(self, value): + self._opened = value + +@property +def lastToken(self): + try: + return self._lastToken + except AttributeError: + self._lastToken = None + return self._lastToken + +@lastToken.setter +def lastToken(self, value): + self._lastToken = value + +def reset(self): + super().reset() + self.tokens = [] + self.indents = [] + self.opened = 0 + self.lastToken = None + +def emitToken(self, t): + super().emitToken(t) + self.tokens.append(t) + +def nextToken(self): + if self._input.LA(1) == Token.EOF and self.indents: + for i in range(len(self.tokens)-1,-1,-1): + if self.tokens[i].type == Token.EOF: + self.tokens.pop(i) + self.emitToken(self.commonToken(LanguageParser.NEWLINE, '\n')) + while self.indents: + self.emitToken(self.createDedent()) + self.indents.pop() + self.emitToken(self.commonToken(LanguageParser.EOF, "")) + next = super().nextToken() + if next.channel == Token.DEFAULT_CHANNEL: + self.lastToken = next + return next if not self.tokens else self.tokens.pop(0) + +def createDedent(self): + dedent = self.commonToken(LanguageParser.DEDENT, "") + dedent.line = self.lastToken.line + return dedent + +def commonToken(self, type, text, indent=0): + stop = self.getCharIndex()-1-indent + start = (stop - len(text) + 1) if text else stop + return CommonToken(self._tokenFactorySourcePair, type, super().DEFAULT_TOKEN_CHANNEL, start, stop) + +@staticmethod +def getIndentationCount(spaces): + count = 0 + for ch in spaces: + if ch == '\t': + count += 8 - (count % 8) + else: + count += 1 + return count + +def atStartOfInput(self): + return Lexer.column.fget(self) == 0 and Lexer.line.fget(self) == 1 + +} + + +//---------------------------------------- +// Parser rules +/*Top-Level structure*/ +osc_file : preludeStatement* oscDeclaration* EOF; + +preludeStatement : importStatement ; + +importStatement + : 'import' importReference NEWLINE + | NEWLINE; + +importReference + : StringLiteral + | structuredIdentifier + ; + +structuredIdentifier + : Identifier + | structuredIdentifier'.'Identifier + ; + +oscDeclaration + : physicalTypeDeclaration + | unitDeclaration + | enumDeclaration + | structDeclaration + | actorDeclaration + | actionDeclaration + | scenarioDeclaration + | modifierDeclaration + | typeExtension + | globalParameterDeclaration + | NEWLINE + ; + +//---------------------------------------- +// physicalTypeDeclaration +physicalTypeDeclaration : 'type' physicalTypeName 'is' baseUnitSpecifier NEWLINE; + +physicalTypeName : Identifier; + +baseUnitSpecifier : sIBaseUnitSpecifier; + +sIBaseUnitSpecifier : 'SI' OPEN_PAREN siBaseExponentList CLOSE_PAREN; + +//---------------------------------------- +// unitDeclaration +unitDeclaration : 'unit' unitName 'of' physicalTypeName 'is' unitSpecifier NEWLINE; + +unitSpecifier : siUnitSpecifier ; +unitName : Identifier | siBaseUnitName ; + +siBaseExponentList : siBaseExponent (',' siBaseExponent)* ; +siBaseExponent : siBaseUnitName ':' integerLiteral ; + +siUnitSpecifier : 'SI' '(' siBaseExponentList (',' siFactor)? (',' siOffset)? ')' ; +siFactor : 'factor' ':' ( FloatLiteral | integerLiteral ) ; +siOffset : 'offset' ':' ( FloatLiteral | integerLiteral ) ; +siBaseUnitName : 'kg' | 'm' | 's' | 'A' | 'K' | 'mol' | 'cd' | 'rad' ; + +//---------------------------------------- +// enumDeclaration +enumDeclaration : 'enum' enumName ':' OPEN_BRACK enumMemberDecl (',' enumMemberDecl)* CLOSE_BRACK NEWLINE; + +enumMemberDecl : enumMemberName ('=' enumMemberValue )?; + +enumMemberValue: UintLiteral | HexUintLiteral; + +enumName : Identifier; + +enumMemberName : Identifier; + +enumValueReference : enumName '!' enumMemberName; + +//---------------------------------------- +inheritsCondition : OPEN_PAREN fieldName '==' (enumValueReference | BoolLiteral) CLOSE_PAREN ; + +//---------------------------------------- +// structDeclaration +structDeclaration : + 'struct' structName (structInherits)? + ((':' NEWLINE INDENT structMemberDecl+ DEDENT) | NEWLINE); + +structInherits : 'inherits' structName (inheritsCondition)? ; + +structMemberDecl + : eventDeclaration + | fieldDeclaration + | constraintDeclaration + | methodDeclaration + | coverageDeclaration; + +fieldName : Identifier; + +structName : Identifier; + +//---------------------------------------- +// actorDeclaration +actorDeclaration : + 'actor' actorName (actorInherits)? + ((':' NEWLINE INDENT actorMemberDecl+ DEDENT) | NEWLINE); + +actorInherits : 'inherits' actorName (inheritsCondition)? ; + +actorMemberDecl + : eventDeclaration + | fieldDeclaration + | constraintDeclaration + | methodDeclaration + | coverageDeclaration; + +actorName : Identifier; + +//---------------------------------------- +// scenarioDeclaration +scenarioDeclaration + : 'scenario' qualifiedBehaviorName (scenarioInherits)? + ((':' NEWLINE INDENT + (scenarioMemberDecl | behaviorSpecification )+ + DEDENT) | NEWLINE); + +scenarioInherits : 'inherits' qualifiedBehaviorName (inheritsCondition)? ; + +scenarioMemberDecl + : eventDeclaration + | fieldDeclaration + | constraintDeclaration + | methodDeclaration + | coverageDeclaration + | modifierInvocation; + +qualifiedBehaviorName : (actorName '.')? behaviorName; + +behaviorName : Identifier; + +//---------------------------------------- +// actionDeclaration +actionDeclaration + : 'action' qualifiedBehaviorName (actionInherits)? + ((':' NEWLINE INDENT (scenarioMemberDecl | behaviorSpecification)+ DEDENT) | NEWLINE); + +actionInherits : 'inherits' qualifiedBehaviorName (inheritsCondition)? ; + +//---------------------------------------- +// modifierDeclaration +modifierDeclaration + : 'modifier' (actorName '.')? modifierName ('of' qualifiedBehaviorName)? + ((':' NEWLINE INDENT scenarioMemberDecl+ DEDENT) | NEWLINE); + +modifierName : Identifier; + +//---------------------------------------- +// typeExtension +typeExtension : enumTypeExtension | structuredTypeExtension; + +/* +enumTypeExtension : 'extend' enumName ':' NEWLINE INDENT + (enumMemberDecl NEWLINE)+ DEDENT; +*/ +enumTypeExtension : 'extend' enumName ':' OPEN_BRACK enumMemberDecl (',' enumMemberDecl)* CLOSE_BRACK NEWLINE; + + +structuredTypeExtension : 'extend' extendableTypeName + ':' NEWLINE INDENT extensionMemberDecl+ DEDENT; + + +extendableTypeName + : typeName + | qualifiedBehaviorName; + +extensionMemberDecl + : structMemberDecl + | actorMemberDecl + | scenarioMemberDecl + | behaviorSpecification; + +//---------------------------------------- +// globalParameterDeclaration +globalParameterDeclaration : 'global' fieldName (',' fieldName)* ':' typeDeclarator ('=' defaultValue)? (parameterWithDeclaration | NEWLINE); + +//Type declarations +typeDeclarator : nonAggregateTypeDeclarator | aggregateTypeDeclarator; + +nonAggregateTypeDeclarator : primitiveType | typeName | qualifiedBehaviorName; + +aggregateTypeDeclarator : listTypeDeclarator; + +listTypeDeclarator : 'list' 'of' nonAggregateTypeDeclarator; + +primitiveType : 'int' | 'uint' | 'float' | 'bool' | 'string'; + +typeName : Identifier; + +// Structured type members + +// eventDeclaration +eventDeclaration + : 'event' eventName + (OPEN_PAREN argumentListSpecification CLOSE_PAREN)? + ('is' eventSpecification)? NEWLINE; + +eventSpecification + : eventReference (( eventFieldDecl )? 'if' eventCondition) ? + | eventCondition ; + +eventReference : '@' eventPath; +eventFieldDecl : 'as' eventFieldName; +eventFieldName : Identifier; +eventName : Identifier; +eventPath : (expression '.')? eventName; + +eventCondition + : boolExpression + | riseExpression + | fallExpression + | elapsedExpression + | everyExpression; + +riseExpression : 'rise' OPEN_PAREN boolExpression CLOSE_PAREN; +fallExpression :'fall' OPEN_PAREN boolExpression CLOSE_PAREN; +elapsedExpression : 'elapsed' OPEN_PAREN durationExpression CLOSE_PAREN; + +//everyExpression : 'every' OPEN_PAREN durationExpression (',' 'offset' ':' durationExpression)? CLOSE_PAREN; +everyExpression : 'every' OPEN_PAREN durationExpression (',' Identifier{ +offsetName = $Identifier.text +if( not (offsetName == "offset") ): + print("%s must be offset" %offsetName) + raise NoViableAltException(self) +} ':' durationExpression)? CLOSE_PAREN; + +boolExpression : expression; +durationExpression : expression; + +// fieldDeclaration +fieldDeclaration + : parameterDeclaration + | variableDeclaration; + +//parameter-declaration ::= field-name (',' field-name)* ':' type-declarator ['=' default-value] [parameter-with-declaration] NEWLINE +//[improvement:] parameterWithDeclaration? NEWLINE -> (parameterWithDeclaration | NEWLINE) +parameterDeclaration + : fieldName (',' fieldName)* ':' typeDeclarator ('=' defaultValue)? (parameterWithDeclaration | NEWLINE); + +variableDeclaration + : 'var' fieldName (',' fieldName)* ':' typeDeclarator ('=' (sampleExpression | valueExp) )? NEWLINE; + +sampleExpression + : 'sample' OPEN_PAREN expression ',' eventSpecification (',' defaultValue)? CLOSE_PAREN; + +defaultValue : expression; + +parameterWithDeclaration : 'with' ':' NEWLINE INDENT + parameterWithMember+ DEDENT; + +// add coverageDeclaration +parameterWithMember : constraintDeclaration | coverageDeclaration; + +// constraintDeclaration +constraintDeclaration + : keepConstraintDeclaration | removeDefaultDeclaration; + +keepConstraintDeclaration + : 'keep' OPEN_PAREN (constraintQualifier)? constraintExpression CLOSE_PAREN NEWLINE; + +constraintQualifier + : 'default' | 'hard'; + +constraintExpression : expression; + +removeDefaultDeclaration : 'remove_default' OPEN_PAREN parameterReference CLOSE_PAREN NEWLINE; + +parameterReference : fieldName | fieldAccess ; + +modifierInvocation : ((behaviorExpression | actorExpression) '.')? modifierName OPEN_PAREN (argumentList)? CLOSE_PAREN NEWLINE; + +behaviorExpression : (actorExpression '.') behaviorName; + +// behaviorSpecification +behaviorSpecification : onDirective | doDirective; + +onDirective : 'on' eventSpecification ':' NEWLINE INDENT + onMember+ DEDENT; + +onMember : callDirective | emitDirective; + +doDirective : 'do' doMember; + +doMember + : (labelName ':')?(composition + | behaviorInvocation + | waitDirective + | emitDirective + | callDirective); + +// composition +composition : compositionOperator (OPEN_PAREN argumentList? CLOSE_PAREN)?':' NEWLINE INDENT + doMember+ DEDENT (behaviorWithDeclaration)?; + +compositionOperator + : 'serial' | 'one_of' | 'parallel'; + +behaviorInvocation + : (actorExpression '.')? behaviorName OPEN_PAREN (argumentList)? CLOSE_PAREN (behaviorWithDeclaration | NEWLINE); + +behaviorWithDeclaration : 'with' ':' NEWLINE INDENT + behaviorWithMember+ DEDENT; + +behaviorWithMember : constraintDeclaration + | modifierInvocation + | untilDirective; + +labelName : Identifier; + +actorExpression + : actorName; + +waitDirective + : 'wait' eventSpecification NEWLINE; + +emitDirective : 'emit' eventName (OPEN_PAREN argumentList CLOSE_PAREN)? NEWLINE; + +callDirective : 'call' methodInvocation NEWLINE; + +untilDirective : 'until' eventSpecification NEWLINE; + +methodInvocation : postfixExp OPEN_PAREN (argumentList)? CLOSE_PAREN; + +methodDeclaration : 'def' methodName OPEN_PAREN (argumentListSpecification)? CLOSE_PAREN ('->' returnType)? methodImplementation NEWLINE; + +returnType : typeDeclarator; + +methodImplementation + : 'is' (methodQualifier)? ('expression' expression + | 'undefined' + | 'external' structuredIdentifier OPEN_PAREN (argumentList)? CLOSE_PAREN); + +methodQualifier : 'only'; + +methodName : Identifier; + +coverageDeclaration: coverDeclaration | recordDeclaration ; + +coverDeclaration : 'cover' OPEN_PAREN targetName? coverageArgumentList* CLOSE_PAREN NEWLINE; + +recordDeclaration : 'record' OPEN_PAREN targetName? coverageArgumentList* CLOSE_PAREN NEWLINE; + +coverageArgumentList : (',' 'expression' ':' expression) #coverageExpression + | (',' 'unit' ':' unitName) #coverageUnit + | (',' 'range' ':' rangeConstructor) #coverageRange + | (',' 'every' ':' valueExp) #coverageEvery + | (',' 'event' ':' eventName) #coverageEvent + | (',' namedArgument) #coverageNameArgument + ; + +targetName : Identifier ; + +//Expressions +expression + : implication + | ternaryOpExp; + +ternaryOpExp + : implication '?' expression ':' expression; + +implication : disjunction ('=>' disjunction)*; +disjunction : conjunction ('or' conjunction)*; +conjunction : inversion ('and' inversion)*; +inversion + : 'not' inversion + | relation; + +relation + : sumExpression #sumExp + | relation relationalOp sumExpression #relationExp; + +relationalOp : '==' | '!=' | '<' | '<=' | '>' | '>=' | 'in'; + +sumExpression + : term #termExp + | sumExpression additiveOp term #additiveExp; + +additiveOp + : '+' + | '-'; + +term + : factor #factorExp + | term multiplicativeOp factor #multiplicativeExp; + +multiplicativeOp + : '*' + | '/' + | '%'; + +factor + : postfixExp + | '-' factor; + +postfixExp + : primaryExp #primaryExpression + | postfixExp '.' 'as' OPEN_PAREN typeDeclarator CLOSE_PAREN #castExpression + | postfixExp '.' 'is' OPEN_PAREN typeDeclarator CLOSE_PAREN #typeTestExpression + | postfixExp OPEN_BRACK expression CLOSE_BRACK #elementAccessExpression + | postfixExp OPEN_PAREN (argumentList)? CLOSE_PAREN #functionApplicationExpression + | postfixExp '.' fieldName #fieldAccessExpression ; + +fieldAccess : postfixExp '.' fieldName ; + +primaryExp + : valueExp + | 'it' + | Identifier + | OPEN_PAREN expression CLOSE_PAREN; + +valueExp + : physicalLiteral + | FloatLiteral + | integerLiteral + | BoolLiteral + | StringLiteral + | identifierReference + | enumValueReference + | listConstructor + | rangeConstructor; + +listConstructor : OPEN_BRACK expression (',' expression)* CLOSE_BRACK; +rangeConstructor + : 'range' OPEN_PAREN expression ',' expression CLOSE_PAREN + | OPEN_BRACK expression '..' expression CLOSE_BRACK; + +identifierReference : (fieldName '.')* fieldName ; +//Common productions +argumentListSpecification : argumentSpecification (',' argumentSpecification)*; + +argumentSpecification : argumentName ':' typeDeclarator ('=' defaultValue)?; + +argumentName : Identifier; + +argumentList + : positionalArgument (',' positionalArgument)* (',' namedArgument)* + | namedArgument (',' namedArgument)*; + +positionalArgument : expression; +namedArgument : argumentName ':' expression; + +physicalLiteral : (FloatLiteral | integerLiteral) unitName; + +integerLiteral : UintLiteral | HexUintLiteral | IntLiteral; + +//---------------------------------------- +// Lexer rules + +NEWLINE + : ( {self.atStartOfInput()}? SPACES + | ( '\r'? '\n' | '\r' | '\f' ) SPACES? + ) + { +tempt = Lexer.text.fget(self) +newLine = re.sub("[^\r\n\f]+", "", tempt) +spaces = re.sub("[\r\n\f]+", "", tempt) +la_char = "" +try: + la = self._input.LA(1) + la_char = chr(la) # Python does not compare char to ints directly +except ValueError: # End of file + pass +# Strip newlines inside open clauses except if we are near EOF. We keep NEWLINEs near EOF to +# satisfy the final newline needed by the single_put rule used by the REPL. +try: + nextnext_la = self._input.LA(2) + nextnext_la_char = chr(nextnext_la) +except ValueError: + nextnext_eof = True +else: + nextnext_eof = False +if self.opened > 0 or nextnext_eof is False and (la_char == '\r' or la_char == '\n' or la_char == '\f' or la_char == '#'): + self.skip() +else: + indent = self.getIndentationCount(spaces) + previous = self.indents[-1] if self.indents else 0 + self.emitToken(self.commonToken(self.NEWLINE, newLine, indent=indent)) # NEWLINE is actually the '\n' char + if indent == previous: + self.skip() + elif indent > previous: + self.indents.append(indent) + self.emitToken(self.commonToken(LanguageParser.INDENT, spaces)) + else: + while self.indents and self.indents[-1] > indent: + self.emitToken(self.createDedent()) + self.indents.pop() + } + ; + +OPEN_BRACK : '[' {self.opened += 1} ; +CLOSE_BRACK : ']' {self.opened -= 1} ; +OPEN_PAREN : '(' {self.opened += 1} ; +CLOSE_PAREN : ')' {self.opened -= 1} ; + + +SKIP_ + : (SPACES | LINE_JOINING) + ->skip + ; + + fragment + SPACES + : [ \t]+ + ; + +fragment LINE_JOINING + : '\\' SPACES? '\r'? '\n' + ; + +fragment +RN + : '\r'? '\n' + ; + +BLOCK_COMMENT + : '/*' .*? '*/' + -> skip + ; + +LINE_COMMENT + : '#' ~[\r\n\f]* + -> skip + ; + +StringLiteral + : Shortstring + | Longstring + ; + +fragment +Shortstring + : ('"' ShortstringElem* '"') | ('\'' ShortstringElem* '\''); + + +fragment +ShortstringElem + : ShortstringChar | StringEscapeSeq; + +fragment +ShortstringChar + : ~[\\'"\r\n]; + + +fragment +Longstring + : ('"""' LongstringElem* '"""') | ('\'\'\'' LongstringElem* '\'\'\''); + +fragment +LongstringElem : LongstringChar | StringEscapeSeq; + +fragment +LongstringChar : ~'\\'; + +fragment +StringEscapeSeq + : '\\'. + | '\\' RN // [improvement:] consider: '\r'? '\n' + ; + + +FloatLiteral : [+-]? Digit* '.' Digit+ ([eE] [+-]? Digit+)?; + +UintLiteral : Digit+; + +HexUintLiteral : '0x' HexDigit+; + +IntLiteral : '-' Digit+; + +BoolLiteral : + 'true' | 'false'; + + +/* +where `id-start-char` matches all characters of the following Unicode character categories: + +* Ll -- Lowercase Letter +* Lm -- Modifier Letter +* Lo -- Other Letter +* Lt -- Titlecase Letter +* Lu -- Uppercase Letter +* Nl -- Letter Number + +It also matches the underscore character `_` (U+005F). + +`id-char` matches all characters that `id-start-char` matches, and additionally all characters of the following Unicode character categories: + +* Mc -- Spacing Combining Mark +* Mn -- Nonspacing Mark +* Nd -- Decimal Number +* Pc -- Connector Punctuations + +`non-vertical-line-char` matches all Unicode characters, except the vertical line `|` (U+007C) character. +*/ +Identifier : ( [A-Za-z] [A-Za-z0-9_]* ) | ( '|' (~[|])+ '|' ) ; + +fragment +NonVerticalLineChar : ~[\u007C]; + +fragment +Digit + : [0-9] + ; + +fragment +HexDigit + : [0-9A-Fa-f] + ; diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.interp b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.interp new file mode 100644 index 00000000..fb540c0f --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.interp @@ -0,0 +1,361 @@ +token literal names: +null +'import' +'.' +'type' +'is' +'SI' +'unit' +'of' +',' +':' +'factor' +'offset' +'kg' +'m' +'s' +'A' +'K' +'mol' +'cd' +'rad' +'enum' +'=' +'!' +'==' +'struct' +'inherits' +'actor' +'scenario' +'action' +'modifier' +'extend' +'global' +'list' +'int' +'uint' +'float' +'bool' +'string' +'event' +'if' +'@' +'as' +'rise' +'fall' +'elapsed' +'every' +'var' +'sample' +'with' +'keep' +'default' +'hard' +'remove_default' +'on' +'do' +'serial' +'one_of' +'parallel' +'wait' +'emit' +'call' +'until' +'def' +'->' +'expression' +'undefined' +'external' +'only' +'cover' +'record' +'range' +'?' +'=>' +'or' +'and' +'not' +'!=' +'<' +'<=' +'>' +'>=' +'in' +'+' +'-' +'*' +'/' +'%' +'it' +'..' +null +'[' +']' +'(' +')' +null +null +null +null +null +null +null +null +null +null +null +null + +token symbolic names: +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +NEWLINE +OPEN_BRACK +CLOSE_BRACK +OPEN_PAREN +CLOSE_PAREN +SKIP_ +BLOCK_COMMENT +LINE_COMMENT +StringLiteral +FloatLiteral +UintLiteral +HexUintLiteral +IntLiteral +BoolLiteral +Identifier +INDENT +DEDENT + +rule names: +osc_file +preludeStatement +importStatement +importReference +structuredIdentifier +oscDeclaration +physicalTypeDeclaration +physicalTypeName +baseUnitSpecifier +sIBaseUnitSpecifier +unitDeclaration +unitSpecifier +unitName +siBaseExponentList +siBaseExponent +siUnitSpecifier +siFactor +siOffset +siBaseUnitName +enumDeclaration +enumMemberDecl +enumMemberValue +enumName +enumMemberName +enumValueReference +inheritsCondition +structDeclaration +structInherits +structMemberDecl +fieldName +structName +actorDeclaration +actorInherits +actorMemberDecl +actorName +scenarioDeclaration +scenarioInherits +scenarioMemberDecl +qualifiedBehaviorName +behaviorName +actionDeclaration +actionInherits +modifierDeclaration +modifierName +typeExtension +enumTypeExtension +structuredTypeExtension +extendableTypeName +extensionMemberDecl +globalParameterDeclaration +typeDeclarator +nonAggregateTypeDeclarator +aggregateTypeDeclarator +listTypeDeclarator +primitiveType +typeName +eventDeclaration +eventSpecification +eventReference +eventFieldDecl +eventFieldName +eventName +eventPath +eventCondition +riseExpression +fallExpression +elapsedExpression +everyExpression +boolExpression +durationExpression +fieldDeclaration +parameterDeclaration +variableDeclaration +sampleExpression +defaultValue +parameterWithDeclaration +parameterWithMember +constraintDeclaration +keepConstraintDeclaration +constraintQualifier +constraintExpression +removeDefaultDeclaration +parameterReference +modifierInvocation +behaviorExpression +behaviorSpecification +onDirective +onMember +doDirective +doMember +composition +compositionOperator +behaviorInvocation +behaviorWithDeclaration +behaviorWithMember +labelName +actorExpression +waitDirective +emitDirective +callDirective +untilDirective +methodInvocation +methodDeclaration +returnType +methodImplementation +methodQualifier +methodName +coverageDeclaration +coverDeclaration +recordDeclaration +coverageArgumentList +targetName +expression +ternaryOpExp +implication +disjunction +conjunction +inversion +relation +relationalOp +sumExpression +additiveOp +term +multiplicativeOp +factor +postfixExp +fieldAccess +primaryExp +valueExp +listConstructor +rangeConstructor +identifierReference +argumentListSpecification +argumentSpecification +argumentName +argumentList +positionalArgument +namedArgument +physicalLiteral +integerLiteral + + +atn: +[3, 24715, 42794, 33075, 47597, 16764, 15335, 30598, 22884, 3, 107, 1329, 4, 2, 9, 2, 4, 3, 9, 3, 4, 4, 9, 4, 4, 5, 9, 5, 4, 6, 9, 6, 4, 7, 9, 7, 4, 8, 9, 8, 4, 9, 9, 9, 4, 10, 9, 10, 4, 11, 9, 11, 4, 12, 9, 12, 4, 13, 9, 13, 4, 14, 9, 14, 4, 15, 9, 15, 4, 16, 9, 16, 4, 17, 9, 17, 4, 18, 9, 18, 4, 19, 9, 19, 4, 20, 9, 20, 4, 21, 9, 21, 4, 22, 9, 22, 4, 23, 9, 23, 4, 24, 9, 24, 4, 25, 9, 25, 4, 26, 9, 26, 4, 27, 9, 27, 4, 28, 9, 28, 4, 29, 9, 29, 4, 30, 9, 30, 4, 31, 9, 31, 4, 32, 9, 32, 4, 33, 9, 33, 4, 34, 9, 34, 4, 35, 9, 35, 4, 36, 9, 36, 4, 37, 9, 37, 4, 38, 9, 38, 4, 39, 9, 39, 4, 40, 9, 40, 4, 41, 9, 41, 4, 42, 9, 42, 4, 43, 9, 43, 4, 44, 9, 44, 4, 45, 9, 45, 4, 46, 9, 46, 4, 47, 9, 47, 4, 48, 9, 48, 4, 49, 9, 49, 4, 50, 9, 50, 4, 51, 9, 51, 4, 52, 9, 52, 4, 53, 9, 53, 4, 54, 9, 54, 4, 55, 9, 55, 4, 56, 9, 56, 4, 57, 9, 57, 4, 58, 9, 58, 4, 59, 9, 59, 4, 60, 9, 60, 4, 61, 9, 61, 4, 62, 9, 62, 4, 63, 9, 63, 4, 64, 9, 64, 4, 65, 9, 65, 4, 66, 9, 66, 4, 67, 9, 67, 4, 68, 9, 68, 4, 69, 9, 69, 4, 70, 9, 70, 4, 71, 9, 71, 4, 72, 9, 72, 4, 73, 9, 73, 4, 74, 9, 74, 4, 75, 9, 75, 4, 76, 9, 76, 4, 77, 9, 77, 4, 78, 9, 78, 4, 79, 9, 79, 4, 80, 9, 80, 4, 81, 9, 81, 4, 82, 9, 82, 4, 83, 9, 83, 4, 84, 9, 84, 4, 85, 9, 85, 4, 86, 9, 86, 4, 87, 9, 87, 4, 88, 9, 88, 4, 89, 9, 89, 4, 90, 9, 90, 4, 91, 9, 91, 4, 92, 9, 92, 4, 93, 9, 93, 4, 94, 9, 94, 4, 95, 9, 95, 4, 96, 9, 96, 4, 97, 9, 97, 4, 98, 9, 98, 4, 99, 9, 99, 4, 100, 9, 100, 4, 101, 9, 101, 4, 102, 9, 102, 4, 103, 9, 103, 4, 104, 9, 104, 4, 105, 9, 105, 4, 106, 9, 106, 4, 107, 9, 107, 4, 108, 9, 108, 4, 109, 9, 109, 4, 110, 9, 110, 4, 111, 9, 111, 4, 112, 9, 112, 4, 113, 9, 113, 4, 114, 9, 114, 4, 115, 9, 115, 4, 116, 9, 116, 4, 117, 9, 117, 4, 118, 9, 118, 4, 119, 9, 119, 4, 120, 9, 120, 4, 121, 9, 121, 4, 122, 9, 122, 4, 123, 9, 123, 4, 124, 9, 124, 4, 125, 9, 125, 4, 126, 9, 126, 4, 127, 9, 127, 4, 128, 9, 128, 4, 129, 9, 129, 4, 130, 9, 130, 4, 131, 9, 131, 4, 132, 9, 132, 4, 133, 9, 133, 4, 134, 9, 134, 4, 135, 9, 135, 4, 136, 9, 136, 4, 137, 9, 137, 4, 138, 9, 138, 4, 139, 9, 139, 4, 140, 9, 140, 4, 141, 9, 141, 3, 2, 7, 2, 284, 10, 2, 12, 2, 14, 2, 287, 11, 2, 3, 2, 7, 2, 290, 10, 2, 12, 2, 14, 2, 293, 11, 2, 3, 2, 3, 2, 3, 3, 3, 3, 3, 4, 3, 4, 3, 4, 3, 4, 3, 4, 5, 4, 304, 10, 4, 3, 5, 3, 5, 5, 5, 308, 10, 5, 3, 6, 3, 6, 3, 6, 3, 6, 3, 6, 3, 6, 7, 6, 316, 10, 6, 12, 6, 14, 6, 319, 11, 6, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 5, 7, 332, 10, 7, 3, 8, 3, 8, 3, 8, 3, 8, 3, 8, 3, 8, 3, 9, 3, 9, 3, 10, 3, 10, 3, 11, 3, 11, 3, 11, 3, 11, 3, 11, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 13, 3, 13, 3, 14, 3, 14, 5, 14, 361, 10, 14, 3, 15, 3, 15, 3, 15, 7, 15, 366, 10, 15, 12, 15, 14, 15, 369, 11, 15, 3, 16, 3, 16, 3, 16, 3, 16, 3, 17, 3, 17, 3, 17, 3, 17, 3, 17, 5, 17, 380, 10, 17, 3, 17, 3, 17, 5, 17, 384, 10, 17, 3, 17, 3, 17, 3, 18, 3, 18, 3, 18, 3, 18, 5, 18, 392, 10, 18, 3, 19, 3, 19, 3, 19, 3, 19, 5, 19, 398, 10, 19, 3, 20, 3, 20, 3, 21, 3, 21, 3, 21, 3, 21, 3, 21, 3, 21, 3, 21, 7, 21, 409, 10, 21, 12, 21, 14, 21, 412, 11, 21, 3, 21, 3, 21, 3, 21, 3, 22, 3, 22, 3, 22, 5, 22, 420, 10, 22, 3, 23, 3, 23, 3, 24, 3, 24, 3, 25, 3, 25, 3, 26, 3, 26, 3, 26, 3, 26, 3, 27, 3, 27, 3, 27, 3, 27, 3, 27, 5, 27, 437, 10, 27, 3, 27, 3, 27, 3, 28, 3, 28, 3, 28, 5, 28, 444, 10, 28, 3, 28, 3, 28, 3, 28, 3, 28, 6, 28, 450, 10, 28, 13, 28, 14, 28, 451, 3, 28, 3, 28, 3, 28, 5, 28, 457, 10, 28, 3, 29, 3, 29, 3, 29, 5, 29, 462, 10, 29, 3, 30, 3, 30, 3, 30, 3, 30, 3, 30, 5, 30, 469, 10, 30, 3, 31, 3, 31, 3, 32, 3, 32, 3, 33, 3, 33, 3, 33, 5, 33, 478, 10, 33, 3, 33, 3, 33, 3, 33, 3, 33, 6, 33, 484, 10, 33, 13, 33, 14, 33, 485, 3, 33, 3, 33, 3, 33, 5, 33, 491, 10, 33, 3, 34, 3, 34, 3, 34, 5, 34, 496, 10, 34, 3, 35, 3, 35, 3, 35, 3, 35, 3, 35, 5, 35, 503, 10, 35, 3, 36, 3, 36, 3, 37, 3, 37, 3, 37, 5, 37, 510, 10, 37, 3, 37, 3, 37, 3, 37, 3, 37, 3, 37, 6, 37, 517, 10, 37, 13, 37, 14, 37, 518, 3, 37, 3, 37, 3, 37, 5, 37, 524, 10, 37, 3, 38, 3, 38, 3, 38, 5, 38, 529, 10, 38, 3, 39, 3, 39, 3, 39, 3, 39, 3, 39, 3, 39, 5, 39, 537, 10, 39, 3, 40, 3, 40, 3, 40, 5, 40, 542, 10, 40, 3, 40, 3, 40, 3, 41, 3, 41, 3, 42, 3, 42, 3, 42, 5, 42, 551, 10, 42, 3, 42, 3, 42, 3, 42, 3, 42, 3, 42, 6, 42, 558, 10, 42, 13, 42, 14, 42, 559, 3, 42, 3, 42, 3, 42, 5, 42, 565, 10, 42, 3, 43, 3, 43, 3, 43, 5, 43, 570, 10, 43, 3, 44, 3, 44, 3, 44, 3, 44, 5, 44, 576, 10, 44, 3, 44, 3, 44, 3, 44, 5, 44, 581, 10, 44, 3, 44, 3, 44, 3, 44, 3, 44, 6, 44, 587, 10, 44, 13, 44, 14, 44, 588, 3, 44, 3, 44, 3, 44, 5, 44, 594, 10, 44, 3, 45, 3, 45, 3, 46, 3, 46, 5, 46, 600, 10, 46, 3, 47, 3, 47, 3, 47, 3, 47, 3, 47, 3, 47, 3, 47, 7, 47, 609, 10, 47, 12, 47, 14, 47, 612, 11, 47, 3, 47, 3, 47, 3, 47, 3, 48, 3, 48, 3, 48, 3, 48, 3, 48, 3, 48, 6, 48, 623, 10, 48, 13, 48, 14, 48, 624, 3, 48, 3, 48, 3, 49, 3, 49, 5, 49, 631, 10, 49, 3, 50, 3, 50, 3, 50, 3, 50, 5, 50, 637, 10, 50, 3, 51, 3, 51, 3, 51, 3, 51, 7, 51, 643, 10, 51, 12, 51, 14, 51, 646, 11, 51, 3, 51, 3, 51, 3, 51, 3, 51, 5, 51, 652, 10, 51, 3, 51, 3, 51, 5, 51, 656, 10, 51, 3, 52, 3, 52, 5, 52, 660, 10, 52, 3, 53, 3, 53, 3, 53, 5, 53, 665, 10, 53, 3, 54, 3, 54, 3, 55, 3, 55, 3, 55, 3, 55, 3, 56, 3, 56, 3, 57, 3, 57, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 5, 58, 683, 10, 58, 3, 58, 3, 58, 5, 58, 687, 10, 58, 3, 58, 3, 58, 3, 59, 3, 59, 5, 59, 693, 10, 59, 3, 59, 3, 59, 5, 59, 697, 10, 59, 3, 59, 5, 59, 700, 10, 59, 3, 60, 3, 60, 3, 60, 3, 61, 3, 61, 3, 61, 3, 62, 3, 62, 3, 63, 3, 63, 3, 64, 3, 64, 3, 64, 5, 64, 715, 10, 64, 3, 64, 3, 64, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 5, 65, 724, 10, 65, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 67, 3, 67, 3, 67, 3, 67, 3, 67, 3, 68, 3, 68, 3, 68, 3, 68, 3, 68, 3, 69, 3, 69, 3, 69, 3, 69, 3, 69, 3, 69, 3, 69, 3, 69, 5, 69, 749, 10, 69, 3, 69, 3, 69, 3, 70, 3, 70, 3, 71, 3, 71, 3, 72, 3, 72, 5, 72, 759, 10, 72, 3, 73, 3, 73, 3, 73, 7, 73, 764, 10, 73, 12, 73, 14, 73, 767, 11, 73, 3, 73, 3, 73, 3, 73, 3, 73, 5, 73, 773, 10, 73, 3, 73, 3, 73, 5, 73, 777, 10, 73, 3, 74, 3, 74, 3, 74, 3, 74, 7, 74, 783, 10, 74, 12, 74, 14, 74, 786, 11, 74, 3, 74, 3, 74, 3, 74, 3, 74, 3, 74, 5, 74, 793, 10, 74, 5, 74, 795, 10, 74, 3, 74, 3, 74, 3, 75, 3, 75, 3, 75, 3, 75, 3, 75, 3, 75, 3, 75, 5, 75, 806, 10, 75, 3, 75, 3, 75, 3, 76, 3, 76, 3, 77, 3, 77, 3, 77, 3, 77, 3, 77, 6, 77, 817, 10, 77, 13, 77, 14, 77, 818, 3, 77, 3, 77, 3, 78, 3, 78, 5, 78, 825, 10, 78, 3, 79, 3, 79, 5, 79, 829, 10, 79, 3, 80, 3, 80, 3, 80, 5, 80, 834, 10, 80, 3, 80, 3, 80, 3, 80, 3, 80, 3, 81, 3, 81, 3, 82, 3, 82, 3, 83, 3, 83, 3, 83, 3, 83, 3, 83, 3, 83, 3, 84, 3, 84, 5, 84, 852, 10, 84, 3, 85, 3, 85, 5, 85, 856, 10, 85, 3, 85, 3, 85, 5, 85, 860, 10, 85, 3, 85, 3, 85, 3, 85, 5, 85, 865, 10, 85, 3, 85, 3, 85, 3, 85, 3, 86, 3, 86, 3, 86, 3, 86, 3, 86, 3, 87, 3, 87, 5, 87, 877, 10, 87, 3, 88, 3, 88, 3, 88, 3, 88, 3, 88, 3, 88, 6, 88, 885, 10, 88, 13, 88, 14, 88, 886, 3, 88, 3, 88, 3, 89, 3, 89, 5, 89, 893, 10, 89, 3, 90, 3, 90, 3, 90, 3, 91, 3, 91, 3, 91, 5, 91, 901, 10, 91, 3, 91, 3, 91, 3, 91, 3, 91, 3, 91, 5, 91, 908, 10, 91, 3, 92, 3, 92, 3, 92, 5, 92, 913, 10, 92, 3, 92, 5, 92, 916, 10, 92, 3, 92, 3, 92, 3, 92, 3, 92, 6, 92, 922, 10, 92, 13, 92, 14, 92, 923, 3, 92, 3, 92, 5, 92, 928, 10, 92, 3, 93, 3, 93, 3, 94, 3, 94, 3, 94, 5, 94, 935, 10, 94, 3, 94, 3, 94, 3, 94, 5, 94, 940, 10, 94, 3, 94, 3, 94, 3, 94, 5, 94, 945, 10, 94, 3, 95, 3, 95, 3, 95, 3, 95, 3, 95, 6, 95, 952, 10, 95, 13, 95, 14, 95, 953, 3, 95, 3, 95, 3, 96, 3, 96, 3, 96, 5, 96, 961, 10, 96, 3, 97, 3, 97, 3, 98, 3, 98, 3, 99, 3, 99, 3, 99, 3, 99, 3, 100, 3, 100, 3, 100, 3, 100, 3, 100, 3, 100, 5, 100, 977, 10, 100, 3, 100, 3, 100, 3, 101, 3, 101, 3, 101, 3, 101, 3, 102, 3, 102, 3, 102, 3, 102, 3, 103, 3, 103, 3, 103, 5, 103, 992, 10, 103, 3, 103, 3, 103, 3, 104, 3, 104, 3, 104, 3, 104, 5, 104, 1000, 10, 104, 3, 104, 3, 104, 3, 104, 5, 104, 1005, 10, 104, 3, 104, 3, 104, 3, 104, 3, 105, 3, 105, 3, 106, 3, 106, 5, 106, 1014, 10, 106, 3, 106, 3, 106, 3, 106, 3, 106, 3, 106, 3, 106, 3, 106, 5, 106, 1023, 10, 106, 3, 106, 3, 106, 5, 106, 1027, 10, 106, 3, 107, 3, 107, 3, 108, 3, 108, 3, 109, 3, 109, 5, 109, 1035, 10, 109, 3, 110, 3, 110, 3, 110, 5, 110, 1040, 10, 110, 3, 110, 7, 110, 1043, 10, 110, 12, 110, 14, 110, 1046, 11, 110, 3, 110, 3, 110, 3, 110, 3, 111, 3, 111, 3, 111, 5, 111, 1054, 10, 111, 3, 111, 7, 111, 1057, 10, 111, 12, 111, 14, 111, 1060, 11, 111, 3, 111, 3, 111, 3, 111, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 3, 112, 5, 112, 1087, 10, 112, 3, 113, 3, 113, 3, 114, 3, 114, 5, 114, 1093, 10, 114, 3, 115, 3, 115, 3, 115, 3, 115, 3, 115, 3, 115, 3, 116, 3, 116, 3, 116, 7, 116, 1104, 10, 116, 12, 116, 14, 116, 1107, 11, 116, 3, 117, 3, 117, 3, 117, 7, 117, 1112, 10, 117, 12, 117, 14, 117, 1115, 11, 117, 3, 118, 3, 118, 3, 118, 7, 118, 1120, 10, 118, 12, 118, 14, 118, 1123, 11, 118, 3, 119, 3, 119, 3, 119, 5, 119, 1128, 10, 119, 3, 120, 3, 120, 3, 120, 3, 120, 3, 120, 3, 120, 3, 120, 7, 120, 1137, 10, 120, 12, 120, 14, 120, 1140, 11, 120, 3, 121, 3, 121, 3, 122, 3, 122, 3, 122, 3, 122, 3, 122, 3, 122, 3, 122, 7, 122, 1151, 10, 122, 12, 122, 14, 122, 1154, 11, 122, 3, 123, 3, 123, 3, 124, 3, 124, 3, 124, 3, 124, 3, 124, 3, 124, 3, 124, 7, 124, 1165, 10, 124, 12, 124, 14, 124, 1168, 11, 124, 3, 125, 3, 125, 3, 126, 3, 126, 3, 126, 5, 126, 1175, 10, 126, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 3, 127, 5, 127, 1202, 10, 127, 3, 127, 3, 127, 3, 127, 3, 127, 7, 127, 1208, 10, 127, 12, 127, 14, 127, 1211, 11, 127, 3, 128, 3, 128, 3, 128, 3, 128, 3, 129, 3, 129, 3, 129, 3, 129, 3, 129, 3, 129, 3, 129, 5, 129, 1224, 10, 129, 3, 130, 3, 130, 3, 130, 3, 130, 3, 130, 3, 130, 3, 130, 3, 130, 3, 130, 5, 130, 1235, 10, 130, 3, 131, 3, 131, 3, 131, 3, 131, 7, 131, 1241, 10, 131, 12, 131, 14, 131, 1244, 11, 131, 3, 131, 3, 131, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 3, 132, 5, 132, 1261, 10, 132, 3, 133, 3, 133, 3, 133, 7, 133, 1266, 10, 133, 12, 133, 14, 133, 1269, 11, 133, 3, 133, 3, 133, 3, 134, 3, 134, 3, 134, 7, 134, 1276, 10, 134, 12, 134, 14, 134, 1279, 11, 134, 3, 135, 3, 135, 3, 135, 3, 135, 3, 135, 5, 135, 1286, 10, 135, 3, 136, 3, 136, 3, 137, 3, 137, 3, 137, 7, 137, 1293, 10, 137, 12, 137, 14, 137, 1296, 11, 137, 3, 137, 3, 137, 7, 137, 1300, 10, 137, 12, 137, 14, 137, 1303, 11, 137, 3, 137, 3, 137, 3, 137, 7, 137, 1308, 10, 137, 12, 137, 14, 137, 1311, 11, 137, 5, 137, 1313, 10, 137, 3, 138, 3, 138, 3, 139, 3, 139, 3, 139, 3, 139, 3, 140, 3, 140, 5, 140, 1323, 10, 140, 3, 140, 3, 140, 3, 141, 3, 141, 3, 141, 2, 7, 10, 238, 242, 246, 252, 142, 2, 4, 6, 8, 10, 12, 14, 16, 18, 20, 22, 24, 26, 28, 30, 32, 34, 36, 38, 40, 42, 44, 46, 48, 50, 52, 54, 56, 58, 60, 62, 64, 66, 68, 70, 72, 74, 76, 78, 80, 82, 84, 86, 88, 90, 92, 94, 96, 98, 100, 102, 104, 106, 108, 110, 112, 114, 116, 118, 120, 122, 124, 126, 128, 130, 132, 134, 136, 138, 140, 142, 144, 146, 148, 150, 152, 154, 156, 158, 160, 162, 164, 166, 168, 170, 172, 174, 176, 178, 180, 182, 184, 186, 188, 190, 192, 194, 196, 198, 200, 202, 204, 206, 208, 210, 212, 214, 216, 218, 220, 222, 224, 226, 228, 230, 232, 234, 236, 238, 240, 242, 244, 246, 248, 250, 252, 254, 256, 258, 260, 262, 264, 266, 268, 270, 272, 274, 276, 278, 280, 2, 11, 3, 2, 14, 21, 3, 2, 101, 102, 3, 2, 35, 39, 3, 2, 52, 53, 3, 2, 57, 59, 4, 2, 25, 25, 78, 83, 3, 2, 84, 85, 3, 2, 86, 88, 3, 2, 101, 103, 2, 1360, 2, 285, 3, 2, 2, 2, 4, 296, 3, 2, 2, 2, 6, 303, 3, 2, 2, 2, 8, 307, 3, 2, 2, 2, 10, 309, 3, 2, 2, 2, 12, 331, 3, 2, 2, 2, 14, 333, 3, 2, 2, 2, 16, 339, 3, 2, 2, 2, 18, 341, 3, 2, 2, 2, 20, 343, 3, 2, 2, 2, 22, 348, 3, 2, 2, 2, 24, 356, 3, 2, 2, 2, 26, 360, 3, 2, 2, 2, 28, 362, 3, 2, 2, 2, 30, 370, 3, 2, 2, 2, 32, 374, 3, 2, 2, 2, 34, 387, 3, 2, 2, 2, 36, 393, 3, 2, 2, 2, 38, 399, 3, 2, 2, 2, 40, 401, 3, 2, 2, 2, 42, 416, 3, 2, 2, 2, 44, 421, 3, 2, 2, 2, 46, 423, 3, 2, 2, 2, 48, 425, 3, 2, 2, 2, 50, 427, 3, 2, 2, 2, 52, 431, 3, 2, 2, 2, 54, 440, 3, 2, 2, 2, 56, 458, 3, 2, 2, 2, 58, 468, 3, 2, 2, 2, 60, 470, 3, 2, 2, 2, 62, 472, 3, 2, 2, 2, 64, 474, 3, 2, 2, 2, 66, 492, 3, 2, 2, 2, 68, 502, 3, 2, 2, 2, 70, 504, 3, 2, 2, 2, 72, 506, 3, 2, 2, 2, 74, 525, 3, 2, 2, 2, 76, 536, 3, 2, 2, 2, 78, 541, 3, 2, 2, 2, 80, 545, 3, 2, 2, 2, 82, 547, 3, 2, 2, 2, 84, 566, 3, 2, 2, 2, 86, 571, 3, 2, 2, 2, 88, 595, 3, 2, 2, 2, 90, 599, 3, 2, 2, 2, 92, 601, 3, 2, 2, 2, 94, 616, 3, 2, 2, 2, 96, 630, 3, 2, 2, 2, 98, 636, 3, 2, 2, 2, 100, 638, 3, 2, 2, 2, 102, 659, 3, 2, 2, 2, 104, 664, 3, 2, 2, 2, 106, 666, 3, 2, 2, 2, 108, 668, 3, 2, 2, 2, 110, 672, 3, 2, 2, 2, 112, 674, 3, 2, 2, 2, 114, 676, 3, 2, 2, 2, 116, 699, 3, 2, 2, 2, 118, 701, 3, 2, 2, 2, 120, 704, 3, 2, 2, 2, 122, 707, 3, 2, 2, 2, 124, 709, 3, 2, 2, 2, 126, 714, 3, 2, 2, 2, 128, 723, 3, 2, 2, 2, 130, 725, 3, 2, 2, 2, 132, 730, 3, 2, 2, 2, 134, 735, 3, 2, 2, 2, 136, 740, 3, 2, 2, 2, 138, 752, 3, 2, 2, 2, 140, 754, 3, 2, 2, 2, 142, 758, 3, 2, 2, 2, 144, 760, 3, 2, 2, 2, 146, 778, 3, 2, 2, 2, 148, 798, 3, 2, 2, 2, 150, 809, 3, 2, 2, 2, 152, 811, 3, 2, 2, 2, 154, 824, 3, 2, 2, 2, 156, 828, 3, 2, 2, 2, 158, 830, 3, 2, 2, 2, 160, 839, 3, 2, 2, 2, 162, 841, 3, 2, 2, 2, 164, 843, 3, 2, 2, 2, 166, 851, 3, 2, 2, 2, 168, 859, 3, 2, 2, 2, 170, 869, 3, 2, 2, 2, 172, 876, 3, 2, 2, 2, 174, 878, 3, 2, 2, 2, 176, 892, 3, 2, 2, 2, 178, 894, 3, 2, 2, 2, 180, 900, 3, 2, 2, 2, 182, 909, 3, 2, 2, 2, 184, 929, 3, 2, 2, 2, 186, 934, 3, 2, 2, 2, 188, 946, 3, 2, 2, 2, 190, 960, 3, 2, 2, 2, 192, 962, 3, 2, 2, 2, 194, 964, 3, 2, 2, 2, 196, 966, 3, 2, 2, 2, 198, 970, 3, 2, 2, 2, 200, 980, 3, 2, 2, 2, 202, 984, 3, 2, 2, 2, 204, 988, 3, 2, 2, 2, 206, 995, 3, 2, 2, 2, 208, 1009, 3, 2, 2, 2, 210, 1011, 3, 2, 2, 2, 212, 1028, 3, 2, 2, 2, 214, 1030, 3, 2, 2, 2, 216, 1034, 3, 2, 2, 2, 218, 1036, 3, 2, 2, 2, 220, 1050, 3, 2, 2, 2, 222, 1086, 3, 2, 2, 2, 224, 1088, 3, 2, 2, 2, 226, 1092, 3, 2, 2, 2, 228, 1094, 3, 2, 2, 2, 230, 1100, 3, 2, 2, 2, 232, 1108, 3, 2, 2, 2, 234, 1116, 3, 2, 2, 2, 236, 1127, 3, 2, 2, 2, 238, 1129, 3, 2, 2, 2, 240, 1141, 3, 2, 2, 2, 242, 1143, 3, 2, 2, 2, 244, 1155, 3, 2, 2, 2, 246, 1157, 3, 2, 2, 2, 248, 1169, 3, 2, 2, 2, 250, 1174, 3, 2, 2, 2, 252, 1176, 3, 2, 2, 2, 254, 1212, 3, 2, 2, 2, 256, 1223, 3, 2, 2, 2, 258, 1234, 3, 2, 2, 2, 260, 1236, 3, 2, 2, 2, 262, 1260, 3, 2, 2, 2, 264, 1267, 3, 2, 2, 2, 266, 1272, 3, 2, 2, 2, 268, 1280, 3, 2, 2, 2, 270, 1287, 3, 2, 2, 2, 272, 1312, 3, 2, 2, 2, 274, 1314, 3, 2, 2, 2, 276, 1316, 3, 2, 2, 2, 278, 1322, 3, 2, 2, 2, 280, 1326, 3, 2, 2, 2, 282, 284, 5, 4, 3, 2, 283, 282, 3, 2, 2, 2, 284, 287, 3, 2, 2, 2, 285, 283, 3, 2, 2, 2, 285, 286, 3, 2, 2, 2, 286, 291, 3, 2, 2, 2, 287, 285, 3, 2, 2, 2, 288, 290, 5, 12, 7, 2, 289, 288, 3, 2, 2, 2, 290, 293, 3, 2, 2, 2, 291, 289, 3, 2, 2, 2, 291, 292, 3, 2, 2, 2, 292, 294, 3, 2, 2, 2, 293, 291, 3, 2, 2, 2, 294, 295, 7, 2, 2, 3, 295, 3, 3, 2, 2, 2, 296, 297, 5, 6, 4, 2, 297, 5, 3, 2, 2, 2, 298, 299, 7, 3, 2, 2, 299, 300, 5, 8, 5, 2, 300, 301, 7, 91, 2, 2, 301, 304, 3, 2, 2, 2, 302, 304, 7, 91, 2, 2, 303, 298, 3, 2, 2, 2, 303, 302, 3, 2, 2, 2, 304, 7, 3, 2, 2, 2, 305, 308, 7, 99, 2, 2, 306, 308, 5, 10, 6, 2, 307, 305, 3, 2, 2, 2, 307, 306, 3, 2, 2, 2, 308, 9, 3, 2, 2, 2, 309, 310, 8, 6, 1, 2, 310, 311, 7, 105, 2, 2, 311, 317, 3, 2, 2, 2, 312, 313, 12, 3, 2, 2, 313, 314, 7, 4, 2, 2, 314, 316, 7, 105, 2, 2, 315, 312, 3, 2, 2, 2, 316, 319, 3, 2, 2, 2, 317, 315, 3, 2, 2, 2, 317, 318, 3, 2, 2, 2, 318, 11, 3, 2, 2, 2, 319, 317, 3, 2, 2, 2, 320, 332, 5, 14, 8, 2, 321, 332, 5, 22, 12, 2, 322, 332, 5, 40, 21, 2, 323, 332, 5, 54, 28, 2, 324, 332, 5, 64, 33, 2, 325, 332, 5, 82, 42, 2, 326, 332, 5, 72, 37, 2, 327, 332, 5, 86, 44, 2, 328, 332, 5, 90, 46, 2, 329, 332, 5, 100, 51, 2, 330, 332, 7, 91, 2, 2, 331, 320, 3, 2, 2, 2, 331, 321, 3, 2, 2, 2, 331, 322, 3, 2, 2, 2, 331, 323, 3, 2, 2, 2, 331, 324, 3, 2, 2, 2, 331, 325, 3, 2, 2, 2, 331, 326, 3, 2, 2, 2, 331, 327, 3, 2, 2, 2, 331, 328, 3, 2, 2, 2, 331, 329, 3, 2, 2, 2, 331, 330, 3, 2, 2, 2, 332, 13, 3, 2, 2, 2, 333, 334, 7, 5, 2, 2, 334, 335, 5, 16, 9, 2, 335, 336, 7, 6, 2, 2, 336, 337, 5, 18, 10, 2, 337, 338, 7, 91, 2, 2, 338, 15, 3, 2, 2, 2, 339, 340, 7, 105, 2, 2, 340, 17, 3, 2, 2, 2, 341, 342, 5, 20, 11, 2, 342, 19, 3, 2, 2, 2, 343, 344, 7, 7, 2, 2, 344, 345, 7, 94, 2, 2, 345, 346, 5, 28, 15, 2, 346, 347, 7, 95, 2, 2, 347, 21, 3, 2, 2, 2, 348, 349, 7, 8, 2, 2, 349, 350, 5, 26, 14, 2, 350, 351, 7, 9, 2, 2, 351, 352, 5, 16, 9, 2, 352, 353, 7, 6, 2, 2, 353, 354, 5, 24, 13, 2, 354, 355, 7, 91, 2, 2, 355, 23, 3, 2, 2, 2, 356, 357, 5, 32, 17, 2, 357, 25, 3, 2, 2, 2, 358, 361, 7, 105, 2, 2, 359, 361, 5, 38, 20, 2, 360, 358, 3, 2, 2, 2, 360, 359, 3, 2, 2, 2, 361, 27, 3, 2, 2, 2, 362, 367, 5, 30, 16, 2, 363, 364, 7, 10, 2, 2, 364, 366, 5, 30, 16, 2, 365, 363, 3, 2, 2, 2, 366, 369, 3, 2, 2, 2, 367, 365, 3, 2, 2, 2, 367, 368, 3, 2, 2, 2, 368, 29, 3, 2, 2, 2, 369, 367, 3, 2, 2, 2, 370, 371, 5, 38, 20, 2, 371, 372, 7, 11, 2, 2, 372, 373, 5, 280, 141, 2, 373, 31, 3, 2, 2, 2, 374, 375, 7, 7, 2, 2, 375, 376, 7, 94, 2, 2, 376, 379, 5, 28, 15, 2, 377, 378, 7, 10, 2, 2, 378, 380, 5, 34, 18, 2, 379, 377, 3, 2, 2, 2, 379, 380, 3, 2, 2, 2, 380, 383, 3, 2, 2, 2, 381, 382, 7, 10, 2, 2, 382, 384, 5, 36, 19, 2, 383, 381, 3, 2, 2, 2, 383, 384, 3, 2, 2, 2, 384, 385, 3, 2, 2, 2, 385, 386, 7, 95, 2, 2, 386, 33, 3, 2, 2, 2, 387, 388, 7, 12, 2, 2, 388, 391, 7, 11, 2, 2, 389, 392, 7, 100, 2, 2, 390, 392, 5, 280, 141, 2, 391, 389, 3, 2, 2, 2, 391, 390, 3, 2, 2, 2, 392, 35, 3, 2, 2, 2, 393, 394, 7, 13, 2, 2, 394, 397, 7, 11, 2, 2, 395, 398, 7, 100, 2, 2, 396, 398, 5, 280, 141, 2, 397, 395, 3, 2, 2, 2, 397, 396, 3, 2, 2, 2, 398, 37, 3, 2, 2, 2, 399, 400, 9, 2, 2, 2, 400, 39, 3, 2, 2, 2, 401, 402, 7, 22, 2, 2, 402, 403, 5, 46, 24, 2, 403, 404, 7, 11, 2, 2, 404, 405, 7, 92, 2, 2, 405, 410, 5, 42, 22, 2, 406, 407, 7, 10, 2, 2, 407, 409, 5, 42, 22, 2, 408, 406, 3, 2, 2, 2, 409, 412, 3, 2, 2, 2, 410, 408, 3, 2, 2, 2, 410, 411, 3, 2, 2, 2, 411, 413, 3, 2, 2, 2, 412, 410, 3, 2, 2, 2, 413, 414, 7, 93, 2, 2, 414, 415, 7, 91, 2, 2, 415, 41, 3, 2, 2, 2, 416, 419, 5, 48, 25, 2, 417, 418, 7, 23, 2, 2, 418, 420, 5, 44, 23, 2, 419, 417, 3, 2, 2, 2, 419, 420, 3, 2, 2, 2, 420, 43, 3, 2, 2, 2, 421, 422, 9, 3, 2, 2, 422, 45, 3, 2, 2, 2, 423, 424, 7, 105, 2, 2, 424, 47, 3, 2, 2, 2, 425, 426, 7, 105, 2, 2, 426, 49, 3, 2, 2, 2, 427, 428, 5, 46, 24, 2, 428, 429, 7, 24, 2, 2, 429, 430, 5, 48, 25, 2, 430, 51, 3, 2, 2, 2, 431, 432, 7, 94, 2, 2, 432, 433, 5, 60, 31, 2, 433, 436, 7, 25, 2, 2, 434, 437, 5, 50, 26, 2, 435, 437, 7, 104, 2, 2, 436, 434, 3, 2, 2, 2, 436, 435, 3, 2, 2, 2, 437, 438, 3, 2, 2, 2, 438, 439, 7, 95, 2, 2, 439, 53, 3, 2, 2, 2, 440, 441, 7, 26, 2, 2, 441, 443, 5, 62, 32, 2, 442, 444, 5, 56, 29, 2, 443, 442, 3, 2, 2, 2, 443, 444, 3, 2, 2, 2, 444, 456, 3, 2, 2, 2, 445, 446, 7, 11, 2, 2, 446, 447, 7, 91, 2, 2, 447, 449, 7, 106, 2, 2, 448, 450, 5, 58, 30, 2, 449, 448, 3, 2, 2, 2, 450, 451, 3, 2, 2, 2, 451, 449, 3, 2, 2, 2, 451, 452, 3, 2, 2, 2, 452, 453, 3, 2, 2, 2, 453, 454, 7, 107, 2, 2, 454, 457, 3, 2, 2, 2, 455, 457, 7, 91, 2, 2, 456, 445, 3, 2, 2, 2, 456, 455, 3, 2, 2, 2, 457, 55, 3, 2, 2, 2, 458, 459, 7, 27, 2, 2, 459, 461, 5, 62, 32, 2, 460, 462, 5, 52, 27, 2, 461, 460, 3, 2, 2, 2, 461, 462, 3, 2, 2, 2, 462, 57, 3, 2, 2, 2, 463, 469, 5, 114, 58, 2, 464, 469, 5, 142, 72, 2, 465, 469, 5, 156, 79, 2, 466, 469, 5, 206, 104, 2, 467, 469, 5, 216, 109, 2, 468, 463, 3, 2, 2, 2, 468, 464, 3, 2, 2, 2, 468, 465, 3, 2, 2, 2, 468, 466, 3, 2, 2, 2, 468, 467, 3, 2, 2, 2, 469, 59, 3, 2, 2, 2, 470, 471, 7, 105, 2, 2, 471, 61, 3, 2, 2, 2, 472, 473, 7, 105, 2, 2, 473, 63, 3, 2, 2, 2, 474, 475, 7, 28, 2, 2, 475, 477, 5, 70, 36, 2, 476, 478, 5, 66, 34, 2, 477, 476, 3, 2, 2, 2, 477, 478, 3, 2, 2, 2, 478, 490, 3, 2, 2, 2, 479, 480, 7, 11, 2, 2, 480, 481, 7, 91, 2, 2, 481, 483, 7, 106, 2, 2, 482, 484, 5, 68, 35, 2, 483, 482, 3, 2, 2, 2, 484, 485, 3, 2, 2, 2, 485, 483, 3, 2, 2, 2, 485, 486, 3, 2, 2, 2, 486, 487, 3, 2, 2, 2, 487, 488, 7, 107, 2, 2, 488, 491, 3, 2, 2, 2, 489, 491, 7, 91, 2, 2, 490, 479, 3, 2, 2, 2, 490, 489, 3, 2, 2, 2, 491, 65, 3, 2, 2, 2, 492, 493, 7, 27, 2, 2, 493, 495, 5, 70, 36, 2, 494, 496, 5, 52, 27, 2, 495, 494, 3, 2, 2, 2, 495, 496, 3, 2, 2, 2, 496, 67, 3, 2, 2, 2, 497, 503, 5, 114, 58, 2, 498, 503, 5, 142, 72, 2, 499, 503, 5, 156, 79, 2, 500, 503, 5, 206, 104, 2, 501, 503, 5, 216, 109, 2, 502, 497, 3, 2, 2, 2, 502, 498, 3, 2, 2, 2, 502, 499, 3, 2, 2, 2, 502, 500, 3, 2, 2, 2, 502, 501, 3, 2, 2, 2, 503, 69, 3, 2, 2, 2, 504, 505, 7, 105, 2, 2, 505, 71, 3, 2, 2, 2, 506, 507, 7, 29, 2, 2, 507, 509, 5, 78, 40, 2, 508, 510, 5, 74, 38, 2, 509, 508, 3, 2, 2, 2, 509, 510, 3, 2, 2, 2, 510, 523, 3, 2, 2, 2, 511, 512, 7, 11, 2, 2, 512, 513, 7, 91, 2, 2, 513, 516, 7, 106, 2, 2, 514, 517, 5, 76, 39, 2, 515, 517, 5, 172, 87, 2, 516, 514, 3, 2, 2, 2, 516, 515, 3, 2, 2, 2, 517, 518, 3, 2, 2, 2, 518, 516, 3, 2, 2, 2, 518, 519, 3, 2, 2, 2, 519, 520, 3, 2, 2, 2, 520, 521, 7, 107, 2, 2, 521, 524, 3, 2, 2, 2, 522, 524, 7, 91, 2, 2, 523, 511, 3, 2, 2, 2, 523, 522, 3, 2, 2, 2, 524, 73, 3, 2, 2, 2, 525, 526, 7, 27, 2, 2, 526, 528, 5, 78, 40, 2, 527, 529, 5, 52, 27, 2, 528, 527, 3, 2, 2, 2, 528, 529, 3, 2, 2, 2, 529, 75, 3, 2, 2, 2, 530, 537, 5, 114, 58, 2, 531, 537, 5, 142, 72, 2, 532, 537, 5, 156, 79, 2, 533, 537, 5, 206, 104, 2, 534, 537, 5, 216, 109, 2, 535, 537, 5, 168, 85, 2, 536, 530, 3, 2, 2, 2, 536, 531, 3, 2, 2, 2, 536, 532, 3, 2, 2, 2, 536, 533, 3, 2, 2, 2, 536, 534, 3, 2, 2, 2, 536, 535, 3, 2, 2, 2, 537, 77, 3, 2, 2, 2, 538, 539, 5, 70, 36, 2, 539, 540, 7, 4, 2, 2, 540, 542, 3, 2, 2, 2, 541, 538, 3, 2, 2, 2, 541, 542, 3, 2, 2, 2, 542, 543, 3, 2, 2, 2, 543, 544, 5, 80, 41, 2, 544, 79, 3, 2, 2, 2, 545, 546, 7, 105, 2, 2, 546, 81, 3, 2, 2, 2, 547, 548, 7, 30, 2, 2, 548, 550, 5, 78, 40, 2, 549, 551, 5, 84, 43, 2, 550, 549, 3, 2, 2, 2, 550, 551, 3, 2, 2, 2, 551, 564, 3, 2, 2, 2, 552, 553, 7, 11, 2, 2, 553, 554, 7, 91, 2, 2, 554, 557, 7, 106, 2, 2, 555, 558, 5, 76, 39, 2, 556, 558, 5, 172, 87, 2, 557, 555, 3, 2, 2, 2, 557, 556, 3, 2, 2, 2, 558, 559, 3, 2, 2, 2, 559, 557, 3, 2, 2, 2, 559, 560, 3, 2, 2, 2, 560, 561, 3, 2, 2, 2, 561, 562, 7, 107, 2, 2, 562, 565, 3, 2, 2, 2, 563, 565, 7, 91, 2, 2, 564, 552, 3, 2, 2, 2, 564, 563, 3, 2, 2, 2, 565, 83, 3, 2, 2, 2, 566, 567, 7, 27, 2, 2, 567, 569, 5, 78, 40, 2, 568, 570, 5, 52, 27, 2, 569, 568, 3, 2, 2, 2, 569, 570, 3, 2, 2, 2, 570, 85, 3, 2, 2, 2, 571, 575, 7, 31, 2, 2, 572, 573, 5, 70, 36, 2, 573, 574, 7, 4, 2, 2, 574, 576, 3, 2, 2, 2, 575, 572, 3, 2, 2, 2, 575, 576, 3, 2, 2, 2, 576, 577, 3, 2, 2, 2, 577, 580, 5, 88, 45, 2, 578, 579, 7, 9, 2, 2, 579, 581, 5, 78, 40, 2, 580, 578, 3, 2, 2, 2, 580, 581, 3, 2, 2, 2, 581, 593, 3, 2, 2, 2, 582, 583, 7, 11, 2, 2, 583, 584, 7, 91, 2, 2, 584, 586, 7, 106, 2, 2, 585, 587, 5, 76, 39, 2, 586, 585, 3, 2, 2, 2, 587, 588, 3, 2, 2, 2, 588, 586, 3, 2, 2, 2, 588, 589, 3, 2, 2, 2, 589, 590, 3, 2, 2, 2, 590, 591, 7, 107, 2, 2, 591, 594, 3, 2, 2, 2, 592, 594, 7, 91, 2, 2, 593, 582, 3, 2, 2, 2, 593, 592, 3, 2, 2, 2, 594, 87, 3, 2, 2, 2, 595, 596, 7, 105, 2, 2, 596, 89, 3, 2, 2, 2, 597, 600, 5, 92, 47, 2, 598, 600, 5, 94, 48, 2, 599, 597, 3, 2, 2, 2, 599, 598, 3, 2, 2, 2, 600, 91, 3, 2, 2, 2, 601, 602, 7, 32, 2, 2, 602, 603, 5, 46, 24, 2, 603, 604, 7, 11, 2, 2, 604, 605, 7, 92, 2, 2, 605, 610, 5, 42, 22, 2, 606, 607, 7, 10, 2, 2, 607, 609, 5, 42, 22, 2, 608, 606, 3, 2, 2, 2, 609, 612, 3, 2, 2, 2, 610, 608, 3, 2, 2, 2, 610, 611, 3, 2, 2, 2, 611, 613, 3, 2, 2, 2, 612, 610, 3, 2, 2, 2, 613, 614, 7, 93, 2, 2, 614, 615, 7, 91, 2, 2, 615, 93, 3, 2, 2, 2, 616, 617, 7, 32, 2, 2, 617, 618, 5, 96, 49, 2, 618, 619, 7, 11, 2, 2, 619, 620, 7, 91, 2, 2, 620, 622, 7, 106, 2, 2, 621, 623, 5, 98, 50, 2, 622, 621, 3, 2, 2, 2, 623, 624, 3, 2, 2, 2, 624, 622, 3, 2, 2, 2, 624, 625, 3, 2, 2, 2, 625, 626, 3, 2, 2, 2, 626, 627, 7, 107, 2, 2, 627, 95, 3, 2, 2, 2, 628, 631, 5, 112, 57, 2, 629, 631, 5, 78, 40, 2, 630, 628, 3, 2, 2, 2, 630, 629, 3, 2, 2, 2, 631, 97, 3, 2, 2, 2, 632, 637, 5, 58, 30, 2, 633, 637, 5, 68, 35, 2, 634, 637, 5, 76, 39, 2, 635, 637, 5, 172, 87, 2, 636, 632, 3, 2, 2, 2, 636, 633, 3, 2, 2, 2, 636, 634, 3, 2, 2, 2, 636, 635, 3, 2, 2, 2, 637, 99, 3, 2, 2, 2, 638, 639, 7, 33, 2, 2, 639, 644, 5, 60, 31, 2, 640, 641, 7, 10, 2, 2, 641, 643, 5, 60, 31, 2, 642, 640, 3, 2, 2, 2, 643, 646, 3, 2, 2, 2, 644, 642, 3, 2, 2, 2, 644, 645, 3, 2, 2, 2, 645, 647, 3, 2, 2, 2, 646, 644, 3, 2, 2, 2, 647, 648, 7, 11, 2, 2, 648, 651, 5, 102, 52, 2, 649, 650, 7, 23, 2, 2, 650, 652, 5, 150, 76, 2, 651, 649, 3, 2, 2, 2, 651, 652, 3, 2, 2, 2, 652, 655, 3, 2, 2, 2, 653, 656, 5, 152, 77, 2, 654, 656, 7, 91, 2, 2, 655, 653, 3, 2, 2, 2, 655, 654, 3, 2, 2, 2, 656, 101, 3, 2, 2, 2, 657, 660, 5, 104, 53, 2, 658, 660, 5, 106, 54, 2, 659, 657, 3, 2, 2, 2, 659, 658, 3, 2, 2, 2, 660, 103, 3, 2, 2, 2, 661, 665, 5, 110, 56, 2, 662, 665, 5, 112, 57, 2, 663, 665, 5, 78, 40, 2, 664, 661, 3, 2, 2, 2, 664, 662, 3, 2, 2, 2, 664, 663, 3, 2, 2, 2, 665, 105, 3, 2, 2, 2, 666, 667, 5, 108, 55, 2, 667, 107, 3, 2, 2, 2, 668, 669, 7, 34, 2, 2, 669, 670, 7, 9, 2, 2, 670, 671, 5, 104, 53, 2, 671, 109, 3, 2, 2, 2, 672, 673, 9, 4, 2, 2, 673, 111, 3, 2, 2, 2, 674, 675, 7, 105, 2, 2, 675, 113, 3, 2, 2, 2, 676, 677, 7, 40, 2, 2, 677, 682, 5, 124, 63, 2, 678, 679, 7, 94, 2, 2, 679, 680, 5, 266, 134, 2, 680, 681, 7, 95, 2, 2, 681, 683, 3, 2, 2, 2, 682, 678, 3, 2, 2, 2, 682, 683, 3, 2, 2, 2, 683, 686, 3, 2, 2, 2, 684, 685, 7, 6, 2, 2, 685, 687, 5, 116, 59, 2, 686, 684, 3, 2, 2, 2, 686, 687, 3, 2, 2, 2, 687, 688, 3, 2, 2, 2, 688, 689, 7, 91, 2, 2, 689, 115, 3, 2, 2, 2, 690, 696, 5, 118, 60, 2, 691, 693, 5, 120, 61, 2, 692, 691, 3, 2, 2, 2, 692, 693, 3, 2, 2, 2, 693, 694, 3, 2, 2, 2, 694, 695, 7, 41, 2, 2, 695, 697, 5, 128, 65, 2, 696, 692, 3, 2, 2, 2, 696, 697, 3, 2, 2, 2, 697, 700, 3, 2, 2, 2, 698, 700, 5, 128, 65, 2, 699, 690, 3, 2, 2, 2, 699, 698, 3, 2, 2, 2, 700, 117, 3, 2, 2, 2, 701, 702, 7, 42, 2, 2, 702, 703, 5, 126, 64, 2, 703, 119, 3, 2, 2, 2, 704, 705, 7, 43, 2, 2, 705, 706, 5, 122, 62, 2, 706, 121, 3, 2, 2, 2, 707, 708, 7, 105, 2, 2, 708, 123, 3, 2, 2, 2, 709, 710, 7, 105, 2, 2, 710, 125, 3, 2, 2, 2, 711, 712, 5, 226, 114, 2, 712, 713, 7, 4, 2, 2, 713, 715, 3, 2, 2, 2, 714, 711, 3, 2, 2, 2, 714, 715, 3, 2, 2, 2, 715, 716, 3, 2, 2, 2, 716, 717, 5, 124, 63, 2, 717, 127, 3, 2, 2, 2, 718, 724, 5, 138, 70, 2, 719, 724, 5, 130, 66, 2, 720, 724, 5, 132, 67, 2, 721, 724, 5, 134, 68, 2, 722, 724, 5, 136, 69, 2, 723, 718, 3, 2, 2, 2, 723, 719, 3, 2, 2, 2, 723, 720, 3, 2, 2, 2, 723, 721, 3, 2, 2, 2, 723, 722, 3, 2, 2, 2, 724, 129, 3, 2, 2, 2, 725, 726, 7, 44, 2, 2, 726, 727, 7, 94, 2, 2, 727, 728, 5, 138, 70, 2, 728, 729, 7, 95, 2, 2, 729, 131, 3, 2, 2, 2, 730, 731, 7, 45, 2, 2, 731, 732, 7, 94, 2, 2, 732, 733, 5, 138, 70, 2, 733, 734, 7, 95, 2, 2, 734, 133, 3, 2, 2, 2, 735, 736, 7, 46, 2, 2, 736, 737, 7, 94, 2, 2, 737, 738, 5, 140, 71, 2, 738, 739, 7, 95, 2, 2, 739, 135, 3, 2, 2, 2, 740, 741, 7, 47, 2, 2, 741, 742, 7, 94, 2, 2, 742, 748, 5, 140, 71, 2, 743, 744, 7, 10, 2, 2, 744, 745, 7, 105, 2, 2, 745, 746, 8, 69, 1, 2, 746, 747, 7, 11, 2, 2, 747, 749, 5, 140, 71, 2, 748, 743, 3, 2, 2, 2, 748, 749, 3, 2, 2, 2, 749, 750, 3, 2, 2, 2, 750, 751, 7, 95, 2, 2, 751, 137, 3, 2, 2, 2, 752, 753, 5, 226, 114, 2, 753, 139, 3, 2, 2, 2, 754, 755, 5, 226, 114, 2, 755, 141, 3, 2, 2, 2, 756, 759, 5, 144, 73, 2, 757, 759, 5, 146, 74, 2, 758, 756, 3, 2, 2, 2, 758, 757, 3, 2, 2, 2, 759, 143, 3, 2, 2, 2, 760, 765, 5, 60, 31, 2, 761, 762, 7, 10, 2, 2, 762, 764, 5, 60, 31, 2, 763, 761, 3, 2, 2, 2, 764, 767, 3, 2, 2, 2, 765, 763, 3, 2, 2, 2, 765, 766, 3, 2, 2, 2, 766, 768, 3, 2, 2, 2, 767, 765, 3, 2, 2, 2, 768, 769, 7, 11, 2, 2, 769, 772, 5, 102, 52, 2, 770, 771, 7, 23, 2, 2, 771, 773, 5, 150, 76, 2, 772, 770, 3, 2, 2, 2, 772, 773, 3, 2, 2, 2, 773, 776, 3, 2, 2, 2, 774, 777, 5, 152, 77, 2, 775, 777, 7, 91, 2, 2, 776, 774, 3, 2, 2, 2, 776, 775, 3, 2, 2, 2, 777, 145, 3, 2, 2, 2, 778, 779, 7, 48, 2, 2, 779, 784, 5, 60, 31, 2, 780, 781, 7, 10, 2, 2, 781, 783, 5, 60, 31, 2, 782, 780, 3, 2, 2, 2, 783, 786, 3, 2, 2, 2, 784, 782, 3, 2, 2, 2, 784, 785, 3, 2, 2, 2, 785, 787, 3, 2, 2, 2, 786, 784, 3, 2, 2, 2, 787, 788, 7, 11, 2, 2, 788, 794, 5, 102, 52, 2, 789, 792, 7, 23, 2, 2, 790, 793, 5, 148, 75, 2, 791, 793, 5, 258, 130, 2, 792, 790, 3, 2, 2, 2, 792, 791, 3, 2, 2, 2, 793, 795, 3, 2, 2, 2, 794, 789, 3, 2, 2, 2, 794, 795, 3, 2, 2, 2, 795, 796, 3, 2, 2, 2, 796, 797, 7, 91, 2, 2, 797, 147, 3, 2, 2, 2, 798, 799, 7, 49, 2, 2, 799, 800, 7, 94, 2, 2, 800, 801, 5, 226, 114, 2, 801, 802, 7, 10, 2, 2, 802, 805, 5, 116, 59, 2, 803, 804, 7, 10, 2, 2, 804, 806, 5, 150, 76, 2, 805, 803, 3, 2, 2, 2, 805, 806, 3, 2, 2, 2, 806, 807, 3, 2, 2, 2, 807, 808, 7, 95, 2, 2, 808, 149, 3, 2, 2, 2, 809, 810, 5, 226, 114, 2, 810, 151, 3, 2, 2, 2, 811, 812, 7, 50, 2, 2, 812, 813, 7, 11, 2, 2, 813, 814, 7, 91, 2, 2, 814, 816, 7, 106, 2, 2, 815, 817, 5, 154, 78, 2, 816, 815, 3, 2, 2, 2, 817, 818, 3, 2, 2, 2, 818, 816, 3, 2, 2, 2, 818, 819, 3, 2, 2, 2, 819, 820, 3, 2, 2, 2, 820, 821, 7, 107, 2, 2, 821, 153, 3, 2, 2, 2, 822, 825, 5, 156, 79, 2, 823, 825, 5, 216, 109, 2, 824, 822, 3, 2, 2, 2, 824, 823, 3, 2, 2, 2, 825, 155, 3, 2, 2, 2, 826, 829, 5, 158, 80, 2, 827, 829, 5, 164, 83, 2, 828, 826, 3, 2, 2, 2, 828, 827, 3, 2, 2, 2, 829, 157, 3, 2, 2, 2, 830, 831, 7, 51, 2, 2, 831, 833, 7, 94, 2, 2, 832, 834, 5, 160, 81, 2, 833, 832, 3, 2, 2, 2, 833, 834, 3, 2, 2, 2, 834, 835, 3, 2, 2, 2, 835, 836, 5, 162, 82, 2, 836, 837, 7, 95, 2, 2, 837, 838, 7, 91, 2, 2, 838, 159, 3, 2, 2, 2, 839, 840, 9, 5, 2, 2, 840, 161, 3, 2, 2, 2, 841, 842, 5, 226, 114, 2, 842, 163, 3, 2, 2, 2, 843, 844, 7, 54, 2, 2, 844, 845, 7, 94, 2, 2, 845, 846, 5, 166, 84, 2, 846, 847, 7, 95, 2, 2, 847, 848, 7, 91, 2, 2, 848, 165, 3, 2, 2, 2, 849, 852, 5, 60, 31, 2, 850, 852, 5, 254, 128, 2, 851, 849, 3, 2, 2, 2, 851, 850, 3, 2, 2, 2, 852, 167, 3, 2, 2, 2, 853, 856, 5, 170, 86, 2, 854, 856, 5, 194, 98, 2, 855, 853, 3, 2, 2, 2, 855, 854, 3, 2, 2, 2, 856, 857, 3, 2, 2, 2, 857, 858, 7, 4, 2, 2, 858, 860, 3, 2, 2, 2, 859, 855, 3, 2, 2, 2, 859, 860, 3, 2, 2, 2, 860, 861, 3, 2, 2, 2, 861, 862, 5, 88, 45, 2, 862, 864, 7, 94, 2, 2, 863, 865, 5, 272, 137, 2, 864, 863, 3, 2, 2, 2, 864, 865, 3, 2, 2, 2, 865, 866, 3, 2, 2, 2, 866, 867, 7, 95, 2, 2, 867, 868, 7, 91, 2, 2, 868, 169, 3, 2, 2, 2, 869, 870, 5, 194, 98, 2, 870, 871, 7, 4, 2, 2, 871, 872, 3, 2, 2, 2, 872, 873, 5, 80, 41, 2, 873, 171, 3, 2, 2, 2, 874, 877, 5, 174, 88, 2, 875, 877, 5, 178, 90, 2, 876, 874, 3, 2, 2, 2, 876, 875, 3, 2, 2, 2, 877, 173, 3, 2, 2, 2, 878, 879, 7, 55, 2, 2, 879, 880, 5, 116, 59, 2, 880, 881, 7, 11, 2, 2, 881, 882, 7, 91, 2, 2, 882, 884, 7, 106, 2, 2, 883, 885, 5, 176, 89, 2, 884, 883, 3, 2, 2, 2, 885, 886, 3, 2, 2, 2, 886, 884, 3, 2, 2, 2, 886, 887, 3, 2, 2, 2, 887, 888, 3, 2, 2, 2, 888, 889, 7, 107, 2, 2, 889, 175, 3, 2, 2, 2, 890, 893, 5, 200, 101, 2, 891, 893, 5, 198, 100, 2, 892, 890, 3, 2, 2, 2, 892, 891, 3, 2, 2, 2, 893, 177, 3, 2, 2, 2, 894, 895, 7, 56, 2, 2, 895, 896, 5, 180, 91, 2, 896, 179, 3, 2, 2, 2, 897, 898, 5, 192, 97, 2, 898, 899, 7, 11, 2, 2, 899, 901, 3, 2, 2, 2, 900, 897, 3, 2, 2, 2, 900, 901, 3, 2, 2, 2, 901, 907, 3, 2, 2, 2, 902, 908, 5, 182, 92, 2, 903, 908, 5, 186, 94, 2, 904, 908, 5, 196, 99, 2, 905, 908, 5, 198, 100, 2, 906, 908, 5, 200, 101, 2, 907, 902, 3, 2, 2, 2, 907, 903, 3, 2, 2, 2, 907, 904, 3, 2, 2, 2, 907, 905, 3, 2, 2, 2, 907, 906, 3, 2, 2, 2, 908, 181, 3, 2, 2, 2, 909, 915, 5, 184, 93, 2, 910, 912, 7, 94, 2, 2, 911, 913, 5, 272, 137, 2, 912, 911, 3, 2, 2, 2, 912, 913, 3, 2, 2, 2, 913, 914, 3, 2, 2, 2, 914, 916, 7, 95, 2, 2, 915, 910, 3, 2, 2, 2, 915, 916, 3, 2, 2, 2, 916, 917, 3, 2, 2, 2, 917, 918, 7, 11, 2, 2, 918, 919, 7, 91, 2, 2, 919, 921, 7, 106, 2, 2, 920, 922, 5, 180, 91, 2, 921, 920, 3, 2, 2, 2, 922, 923, 3, 2, 2, 2, 923, 921, 3, 2, 2, 2, 923, 924, 3, 2, 2, 2, 924, 925, 3, 2, 2, 2, 925, 927, 7, 107, 2, 2, 926, 928, 5, 188, 95, 2, 927, 926, 3, 2, 2, 2, 927, 928, 3, 2, 2, 2, 928, 183, 3, 2, 2, 2, 929, 930, 9, 6, 2, 2, 930, 185, 3, 2, 2, 2, 931, 932, 5, 194, 98, 2, 932, 933, 7, 4, 2, 2, 933, 935, 3, 2, 2, 2, 934, 931, 3, 2, 2, 2, 934, 935, 3, 2, 2, 2, 935, 936, 3, 2, 2, 2, 936, 937, 5, 80, 41, 2, 937, 939, 7, 94, 2, 2, 938, 940, 5, 272, 137, 2, 939, 938, 3, 2, 2, 2, 939, 940, 3, 2, 2, 2, 940, 941, 3, 2, 2, 2, 941, 944, 7, 95, 2, 2, 942, 945, 5, 188, 95, 2, 943, 945, 7, 91, 2, 2, 944, 942, 3, 2, 2, 2, 944, 943, 3, 2, 2, 2, 945, 187, 3, 2, 2, 2, 946, 947, 7, 50, 2, 2, 947, 948, 7, 11, 2, 2, 948, 949, 7, 91, 2, 2, 949, 951, 7, 106, 2, 2, 950, 952, 5, 190, 96, 2, 951, 950, 3, 2, 2, 2, 952, 953, 3, 2, 2, 2, 953, 951, 3, 2, 2, 2, 953, 954, 3, 2, 2, 2, 954, 955, 3, 2, 2, 2, 955, 956, 7, 107, 2, 2, 956, 189, 3, 2, 2, 2, 957, 961, 5, 156, 79, 2, 958, 961, 5, 168, 85, 2, 959, 961, 5, 202, 102, 2, 960, 957, 3, 2, 2, 2, 960, 958, 3, 2, 2, 2, 960, 959, 3, 2, 2, 2, 961, 191, 3, 2, 2, 2, 962, 963, 7, 105, 2, 2, 963, 193, 3, 2, 2, 2, 964, 965, 5, 70, 36, 2, 965, 195, 3, 2, 2, 2, 966, 967, 7, 60, 2, 2, 967, 968, 5, 116, 59, 2, 968, 969, 7, 91, 2, 2, 969, 197, 3, 2, 2, 2, 970, 971, 7, 61, 2, 2, 971, 976, 5, 124, 63, 2, 972, 973, 7, 94, 2, 2, 973, 974, 5, 272, 137, 2, 974, 975, 7, 95, 2, 2, 975, 977, 3, 2, 2, 2, 976, 972, 3, 2, 2, 2, 976, 977, 3, 2, 2, 2, 977, 978, 3, 2, 2, 2, 978, 979, 7, 91, 2, 2, 979, 199, 3, 2, 2, 2, 980, 981, 7, 62, 2, 2, 981, 982, 5, 204, 103, 2, 982, 983, 7, 91, 2, 2, 983, 201, 3, 2, 2, 2, 984, 985, 7, 63, 2, 2, 985, 986, 5, 116, 59, 2, 986, 987, 7, 91, 2, 2, 987, 203, 3, 2, 2, 2, 988, 989, 5, 252, 127, 2, 989, 991, 7, 94, 2, 2, 990, 992, 5, 272, 137, 2, 991, 990, 3, 2, 2, 2, 991, 992, 3, 2, 2, 2, 992, 993, 3, 2, 2, 2, 993, 994, 7, 95, 2, 2, 994, 205, 3, 2, 2, 2, 995, 996, 7, 64, 2, 2, 996, 997, 5, 214, 108, 2, 997, 999, 7, 94, 2, 2, 998, 1000, 5, 266, 134, 2, 999, 998, 3, 2, 2, 2, 999, 1000, 3, 2, 2, 2, 1000, 1001, 3, 2, 2, 2, 1001, 1004, 7, 95, 2, 2, 1002, 1003, 7, 65, 2, 2, 1003, 1005, 5, 208, 105, 2, 1004, 1002, 3, 2, 2, 2, 1004, 1005, 3, 2, 2, 2, 1005, 1006, 3, 2, 2, 2, 1006, 1007, 5, 210, 106, 2, 1007, 1008, 7, 91, 2, 2, 1008, 207, 3, 2, 2, 2, 1009, 1010, 5, 102, 52, 2, 1010, 209, 3, 2, 2, 2, 1011, 1013, 7, 6, 2, 2, 1012, 1014, 5, 212, 107, 2, 1013, 1012, 3, 2, 2, 2, 1013, 1014, 3, 2, 2, 2, 1014, 1026, 3, 2, 2, 2, 1015, 1016, 7, 66, 2, 2, 1016, 1027, 5, 226, 114, 2, 1017, 1027, 7, 67, 2, 2, 1018, 1019, 7, 68, 2, 2, 1019, 1020, 5, 10, 6, 2, 1020, 1022, 7, 94, 2, 2, 1021, 1023, 5, 272, 137, 2, 1022, 1021, 3, 2, 2, 2, 1022, 1023, 3, 2, 2, 2, 1023, 1024, 3, 2, 2, 2, 1024, 1025, 7, 95, 2, 2, 1025, 1027, 3, 2, 2, 2, 1026, 1015, 3, 2, 2, 2, 1026, 1017, 3, 2, 2, 2, 1026, 1018, 3, 2, 2, 2, 1027, 211, 3, 2, 2, 2, 1028, 1029, 7, 69, 2, 2, 1029, 213, 3, 2, 2, 2, 1030, 1031, 7, 105, 2, 2, 1031, 215, 3, 2, 2, 2, 1032, 1035, 5, 218, 110, 2, 1033, 1035, 5, 220, 111, 2, 1034, 1032, 3, 2, 2, 2, 1034, 1033, 3, 2, 2, 2, 1035, 217, 3, 2, 2, 2, 1036, 1037, 7, 70, 2, 2, 1037, 1039, 7, 94, 2, 2, 1038, 1040, 5, 224, 113, 2, 1039, 1038, 3, 2, 2, 2, 1039, 1040, 3, 2, 2, 2, 1040, 1044, 3, 2, 2, 2, 1041, 1043, 5, 222, 112, 2, 1042, 1041, 3, 2, 2, 2, 1043, 1046, 3, 2, 2, 2, 1044, 1042, 3, 2, 2, 2, 1044, 1045, 3, 2, 2, 2, 1045, 1047, 3, 2, 2, 2, 1046, 1044, 3, 2, 2, 2, 1047, 1048, 7, 95, 2, 2, 1048, 1049, 7, 91, 2, 2, 1049, 219, 3, 2, 2, 2, 1050, 1051, 7, 71, 2, 2, 1051, 1053, 7, 94, 2, 2, 1052, 1054, 5, 224, 113, 2, 1053, 1052, 3, 2, 2, 2, 1053, 1054, 3, 2, 2, 2, 1054, 1058, 3, 2, 2, 2, 1055, 1057, 5, 222, 112, 2, 1056, 1055, 3, 2, 2, 2, 1057, 1060, 3, 2, 2, 2, 1058, 1056, 3, 2, 2, 2, 1058, 1059, 3, 2, 2, 2, 1059, 1061, 3, 2, 2, 2, 1060, 1058, 3, 2, 2, 2, 1061, 1062, 7, 95, 2, 2, 1062, 1063, 7, 91, 2, 2, 1063, 221, 3, 2, 2, 2, 1064, 1065, 7, 10, 2, 2, 1065, 1066, 7, 66, 2, 2, 1066, 1067, 7, 11, 2, 2, 1067, 1087, 5, 226, 114, 2, 1068, 1069, 7, 10, 2, 2, 1069, 1070, 7, 8, 2, 2, 1070, 1071, 7, 11, 2, 2, 1071, 1087, 5, 26, 14, 2, 1072, 1073, 7, 10, 2, 2, 1073, 1074, 7, 72, 2, 2, 1074, 1075, 7, 11, 2, 2, 1075, 1087, 5, 262, 132, 2, 1076, 1077, 7, 10, 2, 2, 1077, 1078, 7, 47, 2, 2, 1078, 1079, 7, 11, 2, 2, 1079, 1087, 5, 258, 130, 2, 1080, 1081, 7, 10, 2, 2, 1081, 1082, 7, 40, 2, 2, 1082, 1083, 7, 11, 2, 2, 1083, 1087, 5, 124, 63, 2, 1084, 1085, 7, 10, 2, 2, 1085, 1087, 5, 276, 139, 2, 1086, 1064, 3, 2, 2, 2, 1086, 1068, 3, 2, 2, 2, 1086, 1072, 3, 2, 2, 2, 1086, 1076, 3, 2, 2, 2, 1086, 1080, 3, 2, 2, 2, 1086, 1084, 3, 2, 2, 2, 1087, 223, 3, 2, 2, 2, 1088, 1089, 7, 105, 2, 2, 1089, 225, 3, 2, 2, 2, 1090, 1093, 5, 230, 116, 2, 1091, 1093, 5, 228, 115, 2, 1092, 1090, 3, 2, 2, 2, 1092, 1091, 3, 2, 2, 2, 1093, 227, 3, 2, 2, 2, 1094, 1095, 5, 230, 116, 2, 1095, 1096, 7, 73, 2, 2, 1096, 1097, 5, 226, 114, 2, 1097, 1098, 7, 11, 2, 2, 1098, 1099, 5, 226, 114, 2, 1099, 229, 3, 2, 2, 2, 1100, 1105, 5, 232, 117, 2, 1101, 1102, 7, 74, 2, 2, 1102, 1104, 5, 232, 117, 2, 1103, 1101, 3, 2, 2, 2, 1104, 1107, 3, 2, 2, 2, 1105, 1103, 3, 2, 2, 2, 1105, 1106, 3, 2, 2, 2, 1106, 231, 3, 2, 2, 2, 1107, 1105, 3, 2, 2, 2, 1108, 1113, 5, 234, 118, 2, 1109, 1110, 7, 75, 2, 2, 1110, 1112, 5, 234, 118, 2, 1111, 1109, 3, 2, 2, 2, 1112, 1115, 3, 2, 2, 2, 1113, 1111, 3, 2, 2, 2, 1113, 1114, 3, 2, 2, 2, 1114, 233, 3, 2, 2, 2, 1115, 1113, 3, 2, 2, 2, 1116, 1121, 5, 236, 119, 2, 1117, 1118, 7, 76, 2, 2, 1118, 1120, 5, 236, 119, 2, 1119, 1117, 3, 2, 2, 2, 1120, 1123, 3, 2, 2, 2, 1121, 1119, 3, 2, 2, 2, 1121, 1122, 3, 2, 2, 2, 1122, 235, 3, 2, 2, 2, 1123, 1121, 3, 2, 2, 2, 1124, 1125, 7, 77, 2, 2, 1125, 1128, 5, 236, 119, 2, 1126, 1128, 5, 238, 120, 2, 1127, 1124, 3, 2, 2, 2, 1127, 1126, 3, 2, 2, 2, 1128, 237, 3, 2, 2, 2, 1129, 1130, 8, 120, 1, 2, 1130, 1131, 5, 242, 122, 2, 1131, 1138, 3, 2, 2, 2, 1132, 1133, 12, 3, 2, 2, 1133, 1134, 5, 240, 121, 2, 1134, 1135, 5, 242, 122, 2, 1135, 1137, 3, 2, 2, 2, 1136, 1132, 3, 2, 2, 2, 1137, 1140, 3, 2, 2, 2, 1138, 1136, 3, 2, 2, 2, 1138, 1139, 3, 2, 2, 2, 1139, 239, 3, 2, 2, 2, 1140, 1138, 3, 2, 2, 2, 1141, 1142, 9, 7, 2, 2, 1142, 241, 3, 2, 2, 2, 1143, 1144, 8, 122, 1, 2, 1144, 1145, 5, 246, 124, 2, 1145, 1152, 3, 2, 2, 2, 1146, 1147, 12, 3, 2, 2, 1147, 1148, 5, 244, 123, 2, 1148, 1149, 5, 246, 124, 2, 1149, 1151, 3, 2, 2, 2, 1150, 1146, 3, 2, 2, 2, 1151, 1154, 3, 2, 2, 2, 1152, 1150, 3, 2, 2, 2, 1152, 1153, 3, 2, 2, 2, 1153, 243, 3, 2, 2, 2, 1154, 1152, 3, 2, 2, 2, 1155, 1156, 9, 8, 2, 2, 1156, 245, 3, 2, 2, 2, 1157, 1158, 8, 124, 1, 2, 1158, 1159, 5, 250, 126, 2, 1159, 1166, 3, 2, 2, 2, 1160, 1161, 12, 3, 2, 2, 1161, 1162, 5, 248, 125, 2, 1162, 1163, 5, 250, 126, 2, 1163, 1165, 3, 2, 2, 2, 1164, 1160, 3, 2, 2, 2, 1165, 1168, 3, 2, 2, 2, 1166, 1164, 3, 2, 2, 2, 1166, 1167, 3, 2, 2, 2, 1167, 247, 3, 2, 2, 2, 1168, 1166, 3, 2, 2, 2, 1169, 1170, 9, 9, 2, 2, 1170, 249, 3, 2, 2, 2, 1171, 1175, 5, 252, 127, 2, 1172, 1173, 7, 85, 2, 2, 1173, 1175, 5, 250, 126, 2, 1174, 1171, 3, 2, 2, 2, 1174, 1172, 3, 2, 2, 2, 1175, 251, 3, 2, 2, 2, 1176, 1177, 8, 127, 1, 2, 1177, 1178, 5, 256, 129, 2, 1178, 1209, 3, 2, 2, 2, 1179, 1180, 12, 7, 2, 2, 1180, 1181, 7, 4, 2, 2, 1181, 1182, 7, 43, 2, 2, 1182, 1183, 7, 94, 2, 2, 1183, 1184, 5, 102, 52, 2, 1184, 1185, 7, 95, 2, 2, 1185, 1208, 3, 2, 2, 2, 1186, 1187, 12, 6, 2, 2, 1187, 1188, 7, 4, 2, 2, 1188, 1189, 7, 6, 2, 2, 1189, 1190, 7, 94, 2, 2, 1190, 1191, 5, 102, 52, 2, 1191, 1192, 7, 95, 2, 2, 1192, 1208, 3, 2, 2, 2, 1193, 1194, 12, 5, 2, 2, 1194, 1195, 7, 92, 2, 2, 1195, 1196, 5, 226, 114, 2, 1196, 1197, 7, 93, 2, 2, 1197, 1208, 3, 2, 2, 2, 1198, 1199, 12, 4, 2, 2, 1199, 1201, 7, 94, 2, 2, 1200, 1202, 5, 272, 137, 2, 1201, 1200, 3, 2, 2, 2, 1201, 1202, 3, 2, 2, 2, 1202, 1203, 3, 2, 2, 2, 1203, 1208, 7, 95, 2, 2, 1204, 1205, 12, 3, 2, 2, 1205, 1206, 7, 4, 2, 2, 1206, 1208, 5, 60, 31, 2, 1207, 1179, 3, 2, 2, 2, 1207, 1186, 3, 2, 2, 2, 1207, 1193, 3, 2, 2, 2, 1207, 1198, 3, 2, 2, 2, 1207, 1204, 3, 2, 2, 2, 1208, 1211, 3, 2, 2, 2, 1209, 1207, 3, 2, 2, 2, 1209, 1210, 3, 2, 2, 2, 1210, 253, 3, 2, 2, 2, 1211, 1209, 3, 2, 2, 2, 1212, 1213, 5, 252, 127, 2, 1213, 1214, 7, 4, 2, 2, 1214, 1215, 5, 60, 31, 2, 1215, 255, 3, 2, 2, 2, 1216, 1224, 5, 258, 130, 2, 1217, 1224, 7, 89, 2, 2, 1218, 1224, 7, 105, 2, 2, 1219, 1220, 7, 94, 2, 2, 1220, 1221, 5, 226, 114, 2, 1221, 1222, 7, 95, 2, 2, 1222, 1224, 3, 2, 2, 2, 1223, 1216, 3, 2, 2, 2, 1223, 1217, 3, 2, 2, 2, 1223, 1218, 3, 2, 2, 2, 1223, 1219, 3, 2, 2, 2, 1224, 257, 3, 2, 2, 2, 1225, 1235, 5, 278, 140, 2, 1226, 1235, 7, 100, 2, 2, 1227, 1235, 5, 280, 141, 2, 1228, 1235, 7, 104, 2, 2, 1229, 1235, 7, 99, 2, 2, 1230, 1235, 5, 264, 133, 2, 1231, 1235, 5, 50, 26, 2, 1232, 1235, 5, 260, 131, 2, 1233, 1235, 5, 262, 132, 2, 1234, 1225, 3, 2, 2, 2, 1234, 1226, 3, 2, 2, 2, 1234, 1227, 3, 2, 2, 2, 1234, 1228, 3, 2, 2, 2, 1234, 1229, 3, 2, 2, 2, 1234, 1230, 3, 2, 2, 2, 1234, 1231, 3, 2, 2, 2, 1234, 1232, 3, 2, 2, 2, 1234, 1233, 3, 2, 2, 2, 1235, 259, 3, 2, 2, 2, 1236, 1237, 7, 92, 2, 2, 1237, 1242, 5, 226, 114, 2, 1238, 1239, 7, 10, 2, 2, 1239, 1241, 5, 226, 114, 2, 1240, 1238, 3, 2, 2, 2, 1241, 1244, 3, 2, 2, 2, 1242, 1240, 3, 2, 2, 2, 1242, 1243, 3, 2, 2, 2, 1243, 1245, 3, 2, 2, 2, 1244, 1242, 3, 2, 2, 2, 1245, 1246, 7, 93, 2, 2, 1246, 261, 3, 2, 2, 2, 1247, 1248, 7, 72, 2, 2, 1248, 1249, 7, 94, 2, 2, 1249, 1250, 5, 226, 114, 2, 1250, 1251, 7, 10, 2, 2, 1251, 1252, 5, 226, 114, 2, 1252, 1253, 7, 95, 2, 2, 1253, 1261, 3, 2, 2, 2, 1254, 1255, 7, 92, 2, 2, 1255, 1256, 5, 226, 114, 2, 1256, 1257, 7, 90, 2, 2, 1257, 1258, 5, 226, 114, 2, 1258, 1259, 7, 93, 2, 2, 1259, 1261, 3, 2, 2, 2, 1260, 1247, 3, 2, 2, 2, 1260, 1254, 3, 2, 2, 2, 1261, 263, 3, 2, 2, 2, 1262, 1263, 5, 60, 31, 2, 1263, 1264, 7, 4, 2, 2, 1264, 1266, 3, 2, 2, 2, 1265, 1262, 3, 2, 2, 2, 1266, 1269, 3, 2, 2, 2, 1267, 1265, 3, 2, 2, 2, 1267, 1268, 3, 2, 2, 2, 1268, 1270, 3, 2, 2, 2, 1269, 1267, 3, 2, 2, 2, 1270, 1271, 5, 60, 31, 2, 1271, 265, 3, 2, 2, 2, 1272, 1277, 5, 268, 135, 2, 1273, 1274, 7, 10, 2, 2, 1274, 1276, 5, 268, 135, 2, 1275, 1273, 3, 2, 2, 2, 1276, 1279, 3, 2, 2, 2, 1277, 1275, 3, 2, 2, 2, 1277, 1278, 3, 2, 2, 2, 1278, 267, 3, 2, 2, 2, 1279, 1277, 3, 2, 2, 2, 1280, 1281, 5, 270, 136, 2, 1281, 1282, 7, 11, 2, 2, 1282, 1285, 5, 102, 52, 2, 1283, 1284, 7, 23, 2, 2, 1284, 1286, 5, 150, 76, 2, 1285, 1283, 3, 2, 2, 2, 1285, 1286, 3, 2, 2, 2, 1286, 269, 3, 2, 2, 2, 1287, 1288, 7, 105, 2, 2, 1288, 271, 3, 2, 2, 2, 1289, 1294, 5, 274, 138, 2, 1290, 1291, 7, 10, 2, 2, 1291, 1293, 5, 274, 138, 2, 1292, 1290, 3, 2, 2, 2, 1293, 1296, 3, 2, 2, 2, 1294, 1292, 3, 2, 2, 2, 1294, 1295, 3, 2, 2, 2, 1295, 1301, 3, 2, 2, 2, 1296, 1294, 3, 2, 2, 2, 1297, 1298, 7, 10, 2, 2, 1298, 1300, 5, 276, 139, 2, 1299, 1297, 3, 2, 2, 2, 1300, 1303, 3, 2, 2, 2, 1301, 1299, 3, 2, 2, 2, 1301, 1302, 3, 2, 2, 2, 1302, 1313, 3, 2, 2, 2, 1303, 1301, 3, 2, 2, 2, 1304, 1309, 5, 276, 139, 2, 1305, 1306, 7, 10, 2, 2, 1306, 1308, 5, 276, 139, 2, 1307, 1305, 3, 2, 2, 2, 1308, 1311, 3, 2, 2, 2, 1309, 1307, 3, 2, 2, 2, 1309, 1310, 3, 2, 2, 2, 1310, 1313, 3, 2, 2, 2, 1311, 1309, 3, 2, 2, 2, 1312, 1289, 3, 2, 2, 2, 1312, 1304, 3, 2, 2, 2, 1313, 273, 3, 2, 2, 2, 1314, 1315, 5, 226, 114, 2, 1315, 275, 3, 2, 2, 2, 1316, 1317, 5, 270, 136, 2, 1317, 1318, 7, 11, 2, 2, 1318, 1319, 5, 226, 114, 2, 1319, 277, 3, 2, 2, 2, 1320, 1323, 7, 100, 2, 2, 1321, 1323, 5, 280, 141, 2, 1322, 1320, 3, 2, 2, 2, 1322, 1321, 3, 2, 2, 2, 1323, 1324, 3, 2, 2, 2, 1324, 1325, 5, 26, 14, 2, 1325, 279, 3, 2, 2, 2, 1326, 1327, 9, 10, 2, 2, 1327, 281, 3, 2, 2, 2, 128, 285, 291, 303, 307, 317, 331, 360, 367, 379, 383, 391, 397, 410, 419, 436, 443, 451, 456, 461, 468, 477, 485, 490, 495, 502, 509, 516, 518, 523, 528, 536, 541, 550, 557, 559, 564, 569, 575, 580, 588, 593, 599, 610, 624, 630, 636, 644, 651, 655, 659, 664, 682, 686, 692, 696, 699, 714, 723, 748, 758, 765, 772, 776, 784, 792, 794, 805, 818, 824, 828, 833, 851, 855, 859, 864, 876, 886, 892, 900, 907, 912, 915, 923, 927, 934, 939, 944, 953, 960, 976, 991, 999, 1004, 1013, 1022, 1026, 1034, 1039, 1044, 1053, 1058, 1086, 1092, 1105, 1113, 1121, 1127, 1138, 1152, 1166, 1174, 1201, 1207, 1209, 1223, 1234, 1242, 1260, 1267, 1277, 1285, 1294, 1301, 1309, 1312, 1322] \ No newline at end of file diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.tokens b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.tokens new file mode 100644 index 00000000..df6dffc4 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2.tokens @@ -0,0 +1,197 @@ +T__0=1 +T__1=2 +T__2=3 +T__3=4 +T__4=5 +T__5=6 +T__6=7 +T__7=8 +T__8=9 +T__9=10 +T__10=11 +T__11=12 +T__12=13 +T__13=14 +T__14=15 +T__15=16 +T__16=17 +T__17=18 +T__18=19 +T__19=20 +T__20=21 +T__21=22 +T__22=23 +T__23=24 +T__24=25 +T__25=26 +T__26=27 +T__27=28 +T__28=29 +T__29=30 +T__30=31 +T__31=32 +T__32=33 +T__33=34 +T__34=35 +T__35=36 +T__36=37 +T__37=38 +T__38=39 +T__39=40 +T__40=41 +T__41=42 +T__42=43 +T__43=44 +T__44=45 +T__45=46 +T__46=47 +T__47=48 +T__48=49 +T__49=50 +T__50=51 +T__51=52 +T__52=53 +T__53=54 +T__54=55 +T__55=56 +T__56=57 +T__57=58 +T__58=59 +T__59=60 +T__60=61 +T__61=62 +T__62=63 +T__63=64 +T__64=65 +T__65=66 +T__66=67 +T__67=68 +T__68=69 +T__69=70 +T__70=71 +T__71=72 +T__72=73 +T__73=74 +T__74=75 +T__75=76 +T__76=77 +T__77=78 +T__78=79 +T__79=80 +T__80=81 +T__81=82 +T__82=83 +T__83=84 +T__84=85 +T__85=86 +T__86=87 +T__87=88 +NEWLINE=89 +OPEN_BRACK=90 +CLOSE_BRACK=91 +OPEN_PAREN=92 +CLOSE_PAREN=93 +SKIP_=94 +BLOCK_COMMENT=95 +LINE_COMMENT=96 +StringLiteral=97 +FloatLiteral=98 +UintLiteral=99 +HexUintLiteral=100 +IntLiteral=101 +BoolLiteral=102 +Identifier=103 +INDENT=104 +DEDENT=105 +'import'=1 +'.'=2 +'type'=3 +'is'=4 +'SI'=5 +'unit'=6 +'of'=7 +','=8 +':'=9 +'factor'=10 +'offset'=11 +'kg'=12 +'m'=13 +'s'=14 +'A'=15 +'K'=16 +'mol'=17 +'cd'=18 +'rad'=19 +'enum'=20 +'='=21 +'!'=22 +'=='=23 +'struct'=24 +'inherits'=25 +'actor'=26 +'scenario'=27 +'action'=28 +'modifier'=29 +'extend'=30 +'global'=31 +'list'=32 +'int'=33 +'uint'=34 +'float'=35 +'bool'=36 +'string'=37 +'event'=38 +'if'=39 +'@'=40 +'as'=41 +'rise'=42 +'fall'=43 +'elapsed'=44 +'every'=45 +'var'=46 +'sample'=47 +'with'=48 +'keep'=49 +'default'=50 +'hard'=51 +'remove_default'=52 +'on'=53 +'do'=54 +'serial'=55 +'one_of'=56 +'parallel'=57 +'wait'=58 +'emit'=59 +'call'=60 +'until'=61 +'def'=62 +'->'=63 +'expression'=64 +'undefined'=65 +'external'=66 +'only'=67 +'cover'=68 +'record'=69 +'range'=70 +'?'=71 +'=>'=72 +'or'=73 +'and'=74 +'not'=75 +'!='=76 +'<'=77 +'<='=78 +'>'=79 +'>='=80 +'in'=81 +'+'=82 +'-'=83 +'*'=84 +'/'=85 +'%'=86 +'it'=87 +'..'=88 +'['=90 +']'=91 +'('=92 +')'=93 diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.interp b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.interp new file mode 100644 index 00000000..d91df2d0 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.interp @@ -0,0 +1,339 @@ +token literal names: +null +'import' +'.' +'type' +'is' +'SI' +'unit' +'of' +',' +':' +'factor' +'offset' +'kg' +'m' +'s' +'A' +'K' +'mol' +'cd' +'rad' +'enum' +'=' +'!' +'==' +'struct' +'inherits' +'actor' +'scenario' +'action' +'modifier' +'extend' +'global' +'list' +'int' +'uint' +'float' +'bool' +'string' +'event' +'if' +'@' +'as' +'rise' +'fall' +'elapsed' +'every' +'var' +'sample' +'with' +'keep' +'default' +'hard' +'remove_default' +'on' +'do' +'serial' +'one_of' +'parallel' +'wait' +'emit' +'call' +'until' +'def' +'->' +'expression' +'undefined' +'external' +'only' +'cover' +'record' +'range' +'?' +'=>' +'or' +'and' +'not' +'!=' +'<' +'<=' +'>' +'>=' +'in' +'+' +'-' +'*' +'/' +'%' +'it' +'..' +null +'[' +']' +'(' +')' +null +null +null +null +null +null +null +null +null +null + +token symbolic names: +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +null +NEWLINE +OPEN_BRACK +CLOSE_BRACK +OPEN_PAREN +CLOSE_PAREN +SKIP_ +BLOCK_COMMENT +LINE_COMMENT +StringLiteral +FloatLiteral +UintLiteral +HexUintLiteral +IntLiteral +BoolLiteral +Identifier + +rule names: +T__0 +T__1 +T__2 +T__3 +T__4 +T__5 +T__6 +T__7 +T__8 +T__9 +T__10 +T__11 +T__12 +T__13 +T__14 +T__15 +T__16 +T__17 +T__18 +T__19 +T__20 +T__21 +T__22 +T__23 +T__24 +T__25 +T__26 +T__27 +T__28 +T__29 +T__30 +T__31 +T__32 +T__33 +T__34 +T__35 +T__36 +T__37 +T__38 +T__39 +T__40 +T__41 +T__42 +T__43 +T__44 +T__45 +T__46 +T__47 +T__48 +T__49 +T__50 +T__51 +T__52 +T__53 +T__54 +T__55 +T__56 +T__57 +T__58 +T__59 +T__60 +T__61 +T__62 +T__63 +T__64 +T__65 +T__66 +T__67 +T__68 +T__69 +T__70 +T__71 +T__72 +T__73 +T__74 +T__75 +T__76 +T__77 +T__78 +T__79 +T__80 +T__81 +T__82 +T__83 +T__84 +T__85 +T__86 +T__87 +NEWLINE +OPEN_BRACK +CLOSE_BRACK +OPEN_PAREN +CLOSE_PAREN +SKIP_ +SPACES +LINE_JOINING +RN +BLOCK_COMMENT +LINE_COMMENT +StringLiteral +Shortstring +ShortstringElem +ShortstringChar +Longstring +LongstringElem +LongstringChar +StringEscapeSeq +FloatLiteral +UintLiteral +HexUintLiteral +IntLiteral +BoolLiteral +Identifier +NonVerticalLineChar +Digit +HexDigit + +channel names: +DEFAULT_TOKEN_CHANNEL +HIDDEN + +mode names: +DEFAULT_MODE + +atn: +[3, 24715, 42794, 33075, 47597, 16764, 15335, 30598, 22884, 2, 105, 876, 8, 1, 4, 2, 9, 2, 4, 3, 9, 3, 4, 4, 9, 4, 4, 5, 9, 5, 4, 6, 9, 6, 4, 7, 9, 7, 4, 8, 9, 8, 4, 9, 9, 9, 4, 10, 9, 10, 4, 11, 9, 11, 4, 12, 9, 12, 4, 13, 9, 13, 4, 14, 9, 14, 4, 15, 9, 15, 4, 16, 9, 16, 4, 17, 9, 17, 4, 18, 9, 18, 4, 19, 9, 19, 4, 20, 9, 20, 4, 21, 9, 21, 4, 22, 9, 22, 4, 23, 9, 23, 4, 24, 9, 24, 4, 25, 9, 25, 4, 26, 9, 26, 4, 27, 9, 27, 4, 28, 9, 28, 4, 29, 9, 29, 4, 30, 9, 30, 4, 31, 9, 31, 4, 32, 9, 32, 4, 33, 9, 33, 4, 34, 9, 34, 4, 35, 9, 35, 4, 36, 9, 36, 4, 37, 9, 37, 4, 38, 9, 38, 4, 39, 9, 39, 4, 40, 9, 40, 4, 41, 9, 41, 4, 42, 9, 42, 4, 43, 9, 43, 4, 44, 9, 44, 4, 45, 9, 45, 4, 46, 9, 46, 4, 47, 9, 47, 4, 48, 9, 48, 4, 49, 9, 49, 4, 50, 9, 50, 4, 51, 9, 51, 4, 52, 9, 52, 4, 53, 9, 53, 4, 54, 9, 54, 4, 55, 9, 55, 4, 56, 9, 56, 4, 57, 9, 57, 4, 58, 9, 58, 4, 59, 9, 59, 4, 60, 9, 60, 4, 61, 9, 61, 4, 62, 9, 62, 4, 63, 9, 63, 4, 64, 9, 64, 4, 65, 9, 65, 4, 66, 9, 66, 4, 67, 9, 67, 4, 68, 9, 68, 4, 69, 9, 69, 4, 70, 9, 70, 4, 71, 9, 71, 4, 72, 9, 72, 4, 73, 9, 73, 4, 74, 9, 74, 4, 75, 9, 75, 4, 76, 9, 76, 4, 77, 9, 77, 4, 78, 9, 78, 4, 79, 9, 79, 4, 80, 9, 80, 4, 81, 9, 81, 4, 82, 9, 82, 4, 83, 9, 83, 4, 84, 9, 84, 4, 85, 9, 85, 4, 86, 9, 86, 4, 87, 9, 87, 4, 88, 9, 88, 4, 89, 9, 89, 4, 90, 9, 90, 4, 91, 9, 91, 4, 92, 9, 92, 4, 93, 9, 93, 4, 94, 9, 94, 4, 95, 9, 95, 4, 96, 9, 96, 4, 97, 9, 97, 4, 98, 9, 98, 4, 99, 9, 99, 4, 100, 9, 100, 4, 101, 9, 101, 4, 102, 9, 102, 4, 103, 9, 103, 4, 104, 9, 104, 4, 105, 9, 105, 4, 106, 9, 106, 4, 107, 9, 107, 4, 108, 9, 108, 4, 109, 9, 109, 4, 110, 9, 110, 4, 111, 9, 111, 4, 112, 9, 112, 4, 113, 9, 113, 4, 114, 9, 114, 4, 115, 9, 115, 4, 116, 9, 116, 4, 117, 9, 117, 3, 2, 3, 2, 3, 2, 3, 2, 3, 2, 3, 2, 3, 2, 3, 3, 3, 3, 3, 4, 3, 4, 3, 4, 3, 4, 3, 4, 3, 5, 3, 5, 3, 5, 3, 6, 3, 6, 3, 6, 3, 7, 3, 7, 3, 7, 3, 7, 3, 7, 3, 8, 3, 8, 3, 8, 3, 9, 3, 9, 3, 10, 3, 10, 3, 11, 3, 11, 3, 11, 3, 11, 3, 11, 3, 11, 3, 11, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 12, 3, 13, 3, 13, 3, 13, 3, 14, 3, 14, 3, 15, 3, 15, 3, 16, 3, 16, 3, 17, 3, 17, 3, 18, 3, 18, 3, 18, 3, 18, 3, 19, 3, 19, 3, 19, 3, 20, 3, 20, 3, 20, 3, 20, 3, 21, 3, 21, 3, 21, 3, 21, 3, 21, 3, 22, 3, 22, 3, 23, 3, 23, 3, 24, 3, 24, 3, 24, 3, 25, 3, 25, 3, 25, 3, 25, 3, 25, 3, 25, 3, 25, 3, 26, 3, 26, 3, 26, 3, 26, 3, 26, 3, 26, 3, 26, 3, 26, 3, 26, 3, 27, 3, 27, 3, 27, 3, 27, 3, 27, 3, 27, 3, 28, 3, 28, 3, 28, 3, 28, 3, 28, 3, 28, 3, 28, 3, 28, 3, 28, 3, 29, 3, 29, 3, 29, 3, 29, 3, 29, 3, 29, 3, 29, 3, 30, 3, 30, 3, 30, 3, 30, 3, 30, 3, 30, 3, 30, 3, 30, 3, 30, 3, 31, 3, 31, 3, 31, 3, 31, 3, 31, 3, 31, 3, 31, 3, 32, 3, 32, 3, 32, 3, 32, 3, 32, 3, 32, 3, 32, 3, 33, 3, 33, 3, 33, 3, 33, 3, 33, 3, 34, 3, 34, 3, 34, 3, 34, 3, 35, 3, 35, 3, 35, 3, 35, 3, 35, 3, 36, 3, 36, 3, 36, 3, 36, 3, 36, 3, 36, 3, 37, 3, 37, 3, 37, 3, 37, 3, 37, 3, 38, 3, 38, 3, 38, 3, 38, 3, 38, 3, 38, 3, 38, 3, 39, 3, 39, 3, 39, 3, 39, 3, 39, 3, 39, 3, 40, 3, 40, 3, 40, 3, 41, 3, 41, 3, 42, 3, 42, 3, 42, 3, 43, 3, 43, 3, 43, 3, 43, 3, 43, 3, 44, 3, 44, 3, 44, 3, 44, 3, 44, 3, 45, 3, 45, 3, 45, 3, 45, 3, 45, 3, 45, 3, 45, 3, 45, 3, 46, 3, 46, 3, 46, 3, 46, 3, 46, 3, 46, 3, 47, 3, 47, 3, 47, 3, 47, 3, 48, 3, 48, 3, 48, 3, 48, 3, 48, 3, 48, 3, 48, 3, 49, 3, 49, 3, 49, 3, 49, 3, 49, 3, 50, 3, 50, 3, 50, 3, 50, 3, 50, 3, 51, 3, 51, 3, 51, 3, 51, 3, 51, 3, 51, 3, 51, 3, 51, 3, 52, 3, 52, 3, 52, 3, 52, 3, 52, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 53, 3, 54, 3, 54, 3, 54, 3, 55, 3, 55, 3, 55, 3, 56, 3, 56, 3, 56, 3, 56, 3, 56, 3, 56, 3, 56, 3, 57, 3, 57, 3, 57, 3, 57, 3, 57, 3, 57, 3, 57, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 3, 58, 3, 59, 3, 59, 3, 59, 3, 59, 3, 59, 3, 60, 3, 60, 3, 60, 3, 60, 3, 60, 3, 61, 3, 61, 3, 61, 3, 61, 3, 61, 3, 62, 3, 62, 3, 62, 3, 62, 3, 62, 3, 62, 3, 63, 3, 63, 3, 63, 3, 63, 3, 64, 3, 64, 3, 64, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 65, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 66, 3, 67, 3, 67, 3, 67, 3, 67, 3, 67, 3, 67, 3, 67, 3, 67, 3, 67, 3, 68, 3, 68, 3, 68, 3, 68, 3, 68, 3, 69, 3, 69, 3, 69, 3, 69, 3, 69, 3, 69, 3, 70, 3, 70, 3, 70, 3, 70, 3, 70, 3, 70, 3, 70, 3, 71, 3, 71, 3, 71, 3, 71, 3, 71, 3, 71, 3, 72, 3, 72, 3, 73, 3, 73, 3, 73, 3, 74, 3, 74, 3, 74, 3, 75, 3, 75, 3, 75, 3, 75, 3, 76, 3, 76, 3, 76, 3, 76, 3, 77, 3, 77, 3, 77, 3, 78, 3, 78, 3, 79, 3, 79, 3, 79, 3, 80, 3, 80, 3, 81, 3, 81, 3, 81, 3, 82, 3, 82, 3, 82, 3, 83, 3, 83, 3, 84, 3, 84, 3, 85, 3, 85, 3, 86, 3, 86, 3, 87, 3, 87, 3, 88, 3, 88, 3, 88, 3, 89, 3, 89, 3, 89, 3, 90, 3, 90, 3, 90, 5, 90, 658, 10, 90, 3, 90, 3, 90, 5, 90, 662, 10, 90, 3, 90, 5, 90, 665, 10, 90, 5, 90, 667, 10, 90, 3, 90, 3, 90, 3, 91, 3, 91, 3, 91, 3, 92, 3, 92, 3, 92, 3, 93, 3, 93, 3, 93, 3, 94, 3, 94, 3, 94, 3, 95, 3, 95, 5, 95, 685, 10, 95, 3, 95, 3, 95, 3, 96, 6, 96, 690, 10, 96, 13, 96, 14, 96, 691, 3, 97, 3, 97, 5, 97, 696, 10, 97, 3, 97, 5, 97, 699, 10, 97, 3, 97, 3, 97, 3, 98, 5, 98, 704, 10, 98, 3, 98, 3, 98, 3, 99, 3, 99, 3, 99, 3, 99, 7, 99, 712, 10, 99, 12, 99, 14, 99, 715, 11, 99, 3, 99, 3, 99, 3, 99, 3, 99, 3, 99, 3, 100, 3, 100, 7, 100, 724, 10, 100, 12, 100, 14, 100, 727, 11, 100, 3, 100, 3, 100, 3, 101, 3, 101, 5, 101, 733, 10, 101, 3, 102, 3, 102, 7, 102, 737, 10, 102, 12, 102, 14, 102, 740, 11, 102, 3, 102, 3, 102, 3, 102, 7, 102, 745, 10, 102, 12, 102, 14, 102, 748, 11, 102, 3, 102, 5, 102, 751, 10, 102, 3, 103, 3, 103, 5, 103, 755, 10, 103, 3, 104, 3, 104, 3, 105, 3, 105, 3, 105, 3, 105, 3, 105, 7, 105, 764, 10, 105, 12, 105, 14, 105, 767, 11, 105, 3, 105, 3, 105, 3, 105, 3, 105, 3, 105, 3, 105, 3, 105, 3, 105, 7, 105, 777, 10, 105, 12, 105, 14, 105, 780, 11, 105, 3, 105, 3, 105, 3, 105, 5, 105, 785, 10, 105, 3, 106, 3, 106, 5, 106, 789, 10, 106, 3, 107, 3, 107, 3, 108, 3, 108, 3, 108, 3, 108, 5, 108, 797, 10, 108, 3, 109, 5, 109, 800, 10, 109, 3, 109, 7, 109, 803, 10, 109, 12, 109, 14, 109, 806, 11, 109, 3, 109, 3, 109, 6, 109, 810, 10, 109, 13, 109, 14, 109, 811, 3, 109, 3, 109, 5, 109, 816, 10, 109, 3, 109, 6, 109, 819, 10, 109, 13, 109, 14, 109, 820, 5, 109, 823, 10, 109, 3, 110, 6, 110, 826, 10, 110, 13, 110, 14, 110, 827, 3, 111, 3, 111, 3, 111, 3, 111, 6, 111, 834, 10, 111, 13, 111, 14, 111, 835, 3, 112, 3, 112, 6, 112, 840, 10, 112, 13, 112, 14, 112, 841, 3, 113, 3, 113, 3, 113, 3, 113, 3, 113, 3, 113, 3, 113, 3, 113, 3, 113, 5, 113, 853, 10, 113, 3, 114, 3, 114, 7, 114, 857, 10, 114, 12, 114, 14, 114, 860, 11, 114, 3, 114, 3, 114, 6, 114, 864, 10, 114, 13, 114, 14, 114, 865, 3, 114, 5, 114, 869, 10, 114, 3, 115, 3, 115, 3, 116, 3, 116, 3, 117, 3, 117, 3, 713, 2, 118, 3, 3, 5, 4, 7, 5, 9, 6, 11, 7, 13, 8, 15, 9, 17, 10, 19, 11, 21, 12, 23, 13, 25, 14, 27, 15, 29, 16, 31, 17, 33, 18, 35, 19, 37, 20, 39, 21, 41, 22, 43, 23, 45, 24, 47, 25, 49, 26, 51, 27, 53, 28, 55, 29, 57, 30, 59, 31, 61, 32, 63, 33, 65, 34, 67, 35, 69, 36, 71, 37, 73, 38, 75, 39, 77, 40, 79, 41, 81, 42, 83, 43, 85, 44, 87, 45, 89, 46, 91, 47, 93, 48, 95, 49, 97, 50, 99, 51, 101, 52, 103, 53, 105, 54, 107, 55, 109, 56, 111, 57, 113, 58, 115, 59, 117, 60, 119, 61, 121, 62, 123, 63, 125, 64, 127, 65, 129, 66, 131, 67, 133, 68, 135, 69, 137, 70, 139, 71, 141, 72, 143, 73, 145, 74, 147, 75, 149, 76, 151, 77, 153, 78, 155, 79, 157, 80, 159, 81, 161, 82, 163, 83, 165, 84, 167, 85, 169, 86, 171, 87, 173, 88, 175, 89, 177, 90, 179, 91, 181, 92, 183, 93, 185, 94, 187, 95, 189, 96, 191, 2, 193, 2, 195, 2, 197, 97, 199, 98, 201, 99, 203, 2, 205, 2, 207, 2, 209, 2, 211, 2, 213, 2, 215, 2, 217, 100, 219, 101, 221, 102, 223, 103, 225, 104, 227, 105, 229, 2, 231, 2, 233, 2, 3, 2, 13, 4, 2, 11, 11, 34, 34, 4, 2, 12, 12, 14, 15, 7, 2, 12, 12, 15, 15, 36, 36, 41, 41, 94, 94, 3, 2, 94, 94, 4, 2, 45, 45, 47, 47, 4, 2, 71, 71, 103, 103, 4, 2, 67, 92, 99, 124, 6, 2, 50, 59, 67, 92, 97, 97, 99, 124, 3, 2, 126, 126, 3, 2, 50, 59, 5, 2, 50, 59, 67, 72, 99, 104, 2, 896, 2, 3, 3, 2, 2, 2, 2, 5, 3, 2, 2, 2, 2, 7, 3, 2, 2, 2, 2, 9, 3, 2, 2, 2, 2, 11, 3, 2, 2, 2, 2, 13, 3, 2, 2, 2, 2, 15, 3, 2, 2, 2, 2, 17, 3, 2, 2, 2, 2, 19, 3, 2, 2, 2, 2, 21, 3, 2, 2, 2, 2, 23, 3, 2, 2, 2, 2, 25, 3, 2, 2, 2, 2, 27, 3, 2, 2, 2, 2, 29, 3, 2, 2, 2, 2, 31, 3, 2, 2, 2, 2, 33, 3, 2, 2, 2, 2, 35, 3, 2, 2, 2, 2, 37, 3, 2, 2, 2, 2, 39, 3, 2, 2, 2, 2, 41, 3, 2, 2, 2, 2, 43, 3, 2, 2, 2, 2, 45, 3, 2, 2, 2, 2, 47, 3, 2, 2, 2, 2, 49, 3, 2, 2, 2, 2, 51, 3, 2, 2, 2, 2, 53, 3, 2, 2, 2, 2, 55, 3, 2, 2, 2, 2, 57, 3, 2, 2, 2, 2, 59, 3, 2, 2, 2, 2, 61, 3, 2, 2, 2, 2, 63, 3, 2, 2, 2, 2, 65, 3, 2, 2, 2, 2, 67, 3, 2, 2, 2, 2, 69, 3, 2, 2, 2, 2, 71, 3, 2, 2, 2, 2, 73, 3, 2, 2, 2, 2, 75, 3, 2, 2, 2, 2, 77, 3, 2, 2, 2, 2, 79, 3, 2, 2, 2, 2, 81, 3, 2, 2, 2, 2, 83, 3, 2, 2, 2, 2, 85, 3, 2, 2, 2, 2, 87, 3, 2, 2, 2, 2, 89, 3, 2, 2, 2, 2, 91, 3, 2, 2, 2, 2, 93, 3, 2, 2, 2, 2, 95, 3, 2, 2, 2, 2, 97, 3, 2, 2, 2, 2, 99, 3, 2, 2, 2, 2, 101, 3, 2, 2, 2, 2, 103, 3, 2, 2, 2, 2, 105, 3, 2, 2, 2, 2, 107, 3, 2, 2, 2, 2, 109, 3, 2, 2, 2, 2, 111, 3, 2, 2, 2, 2, 113, 3, 2, 2, 2, 2, 115, 3, 2, 2, 2, 2, 117, 3, 2, 2, 2, 2, 119, 3, 2, 2, 2, 2, 121, 3, 2, 2, 2, 2, 123, 3, 2, 2, 2, 2, 125, 3, 2, 2, 2, 2, 127, 3, 2, 2, 2, 2, 129, 3, 2, 2, 2, 2, 131, 3, 2, 2, 2, 2, 133, 3, 2, 2, 2, 2, 135, 3, 2, 2, 2, 2, 137, 3, 2, 2, 2, 2, 139, 3, 2, 2, 2, 2, 141, 3, 2, 2, 2, 2, 143, 3, 2, 2, 2, 2, 145, 3, 2, 2, 2, 2, 147, 3, 2, 2, 2, 2, 149, 3, 2, 2, 2, 2, 151, 3, 2, 2, 2, 2, 153, 3, 2, 2, 2, 2, 155, 3, 2, 2, 2, 2, 157, 3, 2, 2, 2, 2, 159, 3, 2, 2, 2, 2, 161, 3, 2, 2, 2, 2, 163, 3, 2, 2, 2, 2, 165, 3, 2, 2, 2, 2, 167, 3, 2, 2, 2, 2, 169, 3, 2, 2, 2, 2, 171, 3, 2, 2, 2, 2, 173, 3, 2, 2, 2, 2, 175, 3, 2, 2, 2, 2, 177, 3, 2, 2, 2, 2, 179, 3, 2, 2, 2, 2, 181, 3, 2, 2, 2, 2, 183, 3, 2, 2, 2, 2, 185, 3, 2, 2, 2, 2, 187, 3, 2, 2, 2, 2, 189, 3, 2, 2, 2, 2, 197, 3, 2, 2, 2, 2, 199, 3, 2, 2, 2, 2, 201, 3, 2, 2, 2, 2, 217, 3, 2, 2, 2, 2, 219, 3, 2, 2, 2, 2, 221, 3, 2, 2, 2, 2, 223, 3, 2, 2, 2, 2, 225, 3, 2, 2, 2, 2, 227, 3, 2, 2, 2, 3, 235, 3, 2, 2, 2, 5, 242, 3, 2, 2, 2, 7, 244, 3, 2, 2, 2, 9, 249, 3, 2, 2, 2, 11, 252, 3, 2, 2, 2, 13, 255, 3, 2, 2, 2, 15, 260, 3, 2, 2, 2, 17, 263, 3, 2, 2, 2, 19, 265, 3, 2, 2, 2, 21, 267, 3, 2, 2, 2, 23, 274, 3, 2, 2, 2, 25, 281, 3, 2, 2, 2, 27, 284, 3, 2, 2, 2, 29, 286, 3, 2, 2, 2, 31, 288, 3, 2, 2, 2, 33, 290, 3, 2, 2, 2, 35, 292, 3, 2, 2, 2, 37, 296, 3, 2, 2, 2, 39, 299, 3, 2, 2, 2, 41, 303, 3, 2, 2, 2, 43, 308, 3, 2, 2, 2, 45, 310, 3, 2, 2, 2, 47, 312, 3, 2, 2, 2, 49, 315, 3, 2, 2, 2, 51, 322, 3, 2, 2, 2, 53, 331, 3, 2, 2, 2, 55, 337, 3, 2, 2, 2, 57, 346, 3, 2, 2, 2, 59, 353, 3, 2, 2, 2, 61, 362, 3, 2, 2, 2, 63, 369, 3, 2, 2, 2, 65, 376, 3, 2, 2, 2, 67, 381, 3, 2, 2, 2, 69, 385, 3, 2, 2, 2, 71, 390, 3, 2, 2, 2, 73, 396, 3, 2, 2, 2, 75, 401, 3, 2, 2, 2, 77, 408, 3, 2, 2, 2, 79, 414, 3, 2, 2, 2, 81, 417, 3, 2, 2, 2, 83, 419, 3, 2, 2, 2, 85, 422, 3, 2, 2, 2, 87, 427, 3, 2, 2, 2, 89, 432, 3, 2, 2, 2, 91, 440, 3, 2, 2, 2, 93, 446, 3, 2, 2, 2, 95, 450, 3, 2, 2, 2, 97, 457, 3, 2, 2, 2, 99, 462, 3, 2, 2, 2, 101, 467, 3, 2, 2, 2, 103, 475, 3, 2, 2, 2, 105, 480, 3, 2, 2, 2, 107, 495, 3, 2, 2, 2, 109, 498, 3, 2, 2, 2, 111, 501, 3, 2, 2, 2, 113, 508, 3, 2, 2, 2, 115, 515, 3, 2, 2, 2, 117, 524, 3, 2, 2, 2, 119, 529, 3, 2, 2, 2, 121, 534, 3, 2, 2, 2, 123, 539, 3, 2, 2, 2, 125, 545, 3, 2, 2, 2, 127, 549, 3, 2, 2, 2, 129, 552, 3, 2, 2, 2, 131, 563, 3, 2, 2, 2, 133, 573, 3, 2, 2, 2, 135, 582, 3, 2, 2, 2, 137, 587, 3, 2, 2, 2, 139, 593, 3, 2, 2, 2, 141, 600, 3, 2, 2, 2, 143, 606, 3, 2, 2, 2, 145, 608, 3, 2, 2, 2, 147, 611, 3, 2, 2, 2, 149, 614, 3, 2, 2, 2, 151, 618, 3, 2, 2, 2, 153, 622, 3, 2, 2, 2, 155, 625, 3, 2, 2, 2, 157, 627, 3, 2, 2, 2, 159, 630, 3, 2, 2, 2, 161, 632, 3, 2, 2, 2, 163, 635, 3, 2, 2, 2, 165, 638, 3, 2, 2, 2, 167, 640, 3, 2, 2, 2, 169, 642, 3, 2, 2, 2, 171, 644, 3, 2, 2, 2, 173, 646, 3, 2, 2, 2, 175, 648, 3, 2, 2, 2, 177, 651, 3, 2, 2, 2, 179, 666, 3, 2, 2, 2, 181, 670, 3, 2, 2, 2, 183, 673, 3, 2, 2, 2, 185, 676, 3, 2, 2, 2, 187, 679, 3, 2, 2, 2, 189, 684, 3, 2, 2, 2, 191, 689, 3, 2, 2, 2, 193, 693, 3, 2, 2, 2, 195, 703, 3, 2, 2, 2, 197, 707, 3, 2, 2, 2, 199, 721, 3, 2, 2, 2, 201, 732, 3, 2, 2, 2, 203, 750, 3, 2, 2, 2, 205, 754, 3, 2, 2, 2, 207, 756, 3, 2, 2, 2, 209, 784, 3, 2, 2, 2, 211, 788, 3, 2, 2, 2, 213, 790, 3, 2, 2, 2, 215, 796, 3, 2, 2, 2, 217, 799, 3, 2, 2, 2, 219, 825, 3, 2, 2, 2, 221, 829, 3, 2, 2, 2, 223, 837, 3, 2, 2, 2, 225, 852, 3, 2, 2, 2, 227, 868, 3, 2, 2, 2, 229, 870, 3, 2, 2, 2, 231, 872, 3, 2, 2, 2, 233, 874, 3, 2, 2, 2, 235, 236, 7, 107, 2, 2, 236, 237, 7, 111, 2, 2, 237, 238, 7, 114, 2, 2, 238, 239, 7, 113, 2, 2, 239, 240, 7, 116, 2, 2, 240, 241, 7, 118, 2, 2, 241, 4, 3, 2, 2, 2, 242, 243, 7, 48, 2, 2, 243, 6, 3, 2, 2, 2, 244, 245, 7, 118, 2, 2, 245, 246, 7, 123, 2, 2, 246, 247, 7, 114, 2, 2, 247, 248, 7, 103, 2, 2, 248, 8, 3, 2, 2, 2, 249, 250, 7, 107, 2, 2, 250, 251, 7, 117, 2, 2, 251, 10, 3, 2, 2, 2, 252, 253, 7, 85, 2, 2, 253, 254, 7, 75, 2, 2, 254, 12, 3, 2, 2, 2, 255, 256, 7, 119, 2, 2, 256, 257, 7, 112, 2, 2, 257, 258, 7, 107, 2, 2, 258, 259, 7, 118, 2, 2, 259, 14, 3, 2, 2, 2, 260, 261, 7, 113, 2, 2, 261, 262, 7, 104, 2, 2, 262, 16, 3, 2, 2, 2, 263, 264, 7, 46, 2, 2, 264, 18, 3, 2, 2, 2, 265, 266, 7, 60, 2, 2, 266, 20, 3, 2, 2, 2, 267, 268, 7, 104, 2, 2, 268, 269, 7, 99, 2, 2, 269, 270, 7, 101, 2, 2, 270, 271, 7, 118, 2, 2, 271, 272, 7, 113, 2, 2, 272, 273, 7, 116, 2, 2, 273, 22, 3, 2, 2, 2, 274, 275, 7, 113, 2, 2, 275, 276, 7, 104, 2, 2, 276, 277, 7, 104, 2, 2, 277, 278, 7, 117, 2, 2, 278, 279, 7, 103, 2, 2, 279, 280, 7, 118, 2, 2, 280, 24, 3, 2, 2, 2, 281, 282, 7, 109, 2, 2, 282, 283, 7, 105, 2, 2, 283, 26, 3, 2, 2, 2, 284, 285, 7, 111, 2, 2, 285, 28, 3, 2, 2, 2, 286, 287, 7, 117, 2, 2, 287, 30, 3, 2, 2, 2, 288, 289, 7, 67, 2, 2, 289, 32, 3, 2, 2, 2, 290, 291, 7, 77, 2, 2, 291, 34, 3, 2, 2, 2, 292, 293, 7, 111, 2, 2, 293, 294, 7, 113, 2, 2, 294, 295, 7, 110, 2, 2, 295, 36, 3, 2, 2, 2, 296, 297, 7, 101, 2, 2, 297, 298, 7, 102, 2, 2, 298, 38, 3, 2, 2, 2, 299, 300, 7, 116, 2, 2, 300, 301, 7, 99, 2, 2, 301, 302, 7, 102, 2, 2, 302, 40, 3, 2, 2, 2, 303, 304, 7, 103, 2, 2, 304, 305, 7, 112, 2, 2, 305, 306, 7, 119, 2, 2, 306, 307, 7, 111, 2, 2, 307, 42, 3, 2, 2, 2, 308, 309, 7, 63, 2, 2, 309, 44, 3, 2, 2, 2, 310, 311, 7, 35, 2, 2, 311, 46, 3, 2, 2, 2, 312, 313, 7, 63, 2, 2, 313, 314, 7, 63, 2, 2, 314, 48, 3, 2, 2, 2, 315, 316, 7, 117, 2, 2, 316, 317, 7, 118, 2, 2, 317, 318, 7, 116, 2, 2, 318, 319, 7, 119, 2, 2, 319, 320, 7, 101, 2, 2, 320, 321, 7, 118, 2, 2, 321, 50, 3, 2, 2, 2, 322, 323, 7, 107, 2, 2, 323, 324, 7, 112, 2, 2, 324, 325, 7, 106, 2, 2, 325, 326, 7, 103, 2, 2, 326, 327, 7, 116, 2, 2, 327, 328, 7, 107, 2, 2, 328, 329, 7, 118, 2, 2, 329, 330, 7, 117, 2, 2, 330, 52, 3, 2, 2, 2, 331, 332, 7, 99, 2, 2, 332, 333, 7, 101, 2, 2, 333, 334, 7, 118, 2, 2, 334, 335, 7, 113, 2, 2, 335, 336, 7, 116, 2, 2, 336, 54, 3, 2, 2, 2, 337, 338, 7, 117, 2, 2, 338, 339, 7, 101, 2, 2, 339, 340, 7, 103, 2, 2, 340, 341, 7, 112, 2, 2, 341, 342, 7, 99, 2, 2, 342, 343, 7, 116, 2, 2, 343, 344, 7, 107, 2, 2, 344, 345, 7, 113, 2, 2, 345, 56, 3, 2, 2, 2, 346, 347, 7, 99, 2, 2, 347, 348, 7, 101, 2, 2, 348, 349, 7, 118, 2, 2, 349, 350, 7, 107, 2, 2, 350, 351, 7, 113, 2, 2, 351, 352, 7, 112, 2, 2, 352, 58, 3, 2, 2, 2, 353, 354, 7, 111, 2, 2, 354, 355, 7, 113, 2, 2, 355, 356, 7, 102, 2, 2, 356, 357, 7, 107, 2, 2, 357, 358, 7, 104, 2, 2, 358, 359, 7, 107, 2, 2, 359, 360, 7, 103, 2, 2, 360, 361, 7, 116, 2, 2, 361, 60, 3, 2, 2, 2, 362, 363, 7, 103, 2, 2, 363, 364, 7, 122, 2, 2, 364, 365, 7, 118, 2, 2, 365, 366, 7, 103, 2, 2, 366, 367, 7, 112, 2, 2, 367, 368, 7, 102, 2, 2, 368, 62, 3, 2, 2, 2, 369, 370, 7, 105, 2, 2, 370, 371, 7, 110, 2, 2, 371, 372, 7, 113, 2, 2, 372, 373, 7, 100, 2, 2, 373, 374, 7, 99, 2, 2, 374, 375, 7, 110, 2, 2, 375, 64, 3, 2, 2, 2, 376, 377, 7, 110, 2, 2, 377, 378, 7, 107, 2, 2, 378, 379, 7, 117, 2, 2, 379, 380, 7, 118, 2, 2, 380, 66, 3, 2, 2, 2, 381, 382, 7, 107, 2, 2, 382, 383, 7, 112, 2, 2, 383, 384, 7, 118, 2, 2, 384, 68, 3, 2, 2, 2, 385, 386, 7, 119, 2, 2, 386, 387, 7, 107, 2, 2, 387, 388, 7, 112, 2, 2, 388, 389, 7, 118, 2, 2, 389, 70, 3, 2, 2, 2, 390, 391, 7, 104, 2, 2, 391, 392, 7, 110, 2, 2, 392, 393, 7, 113, 2, 2, 393, 394, 7, 99, 2, 2, 394, 395, 7, 118, 2, 2, 395, 72, 3, 2, 2, 2, 396, 397, 7, 100, 2, 2, 397, 398, 7, 113, 2, 2, 398, 399, 7, 113, 2, 2, 399, 400, 7, 110, 2, 2, 400, 74, 3, 2, 2, 2, 401, 402, 7, 117, 2, 2, 402, 403, 7, 118, 2, 2, 403, 404, 7, 116, 2, 2, 404, 405, 7, 107, 2, 2, 405, 406, 7, 112, 2, 2, 406, 407, 7, 105, 2, 2, 407, 76, 3, 2, 2, 2, 408, 409, 7, 103, 2, 2, 409, 410, 7, 120, 2, 2, 410, 411, 7, 103, 2, 2, 411, 412, 7, 112, 2, 2, 412, 413, 7, 118, 2, 2, 413, 78, 3, 2, 2, 2, 414, 415, 7, 107, 2, 2, 415, 416, 7, 104, 2, 2, 416, 80, 3, 2, 2, 2, 417, 418, 7, 66, 2, 2, 418, 82, 3, 2, 2, 2, 419, 420, 7, 99, 2, 2, 420, 421, 7, 117, 2, 2, 421, 84, 3, 2, 2, 2, 422, 423, 7, 116, 2, 2, 423, 424, 7, 107, 2, 2, 424, 425, 7, 117, 2, 2, 425, 426, 7, 103, 2, 2, 426, 86, 3, 2, 2, 2, 427, 428, 7, 104, 2, 2, 428, 429, 7, 99, 2, 2, 429, 430, 7, 110, 2, 2, 430, 431, 7, 110, 2, 2, 431, 88, 3, 2, 2, 2, 432, 433, 7, 103, 2, 2, 433, 434, 7, 110, 2, 2, 434, 435, 7, 99, 2, 2, 435, 436, 7, 114, 2, 2, 436, 437, 7, 117, 2, 2, 437, 438, 7, 103, 2, 2, 438, 439, 7, 102, 2, 2, 439, 90, 3, 2, 2, 2, 440, 441, 7, 103, 2, 2, 441, 442, 7, 120, 2, 2, 442, 443, 7, 103, 2, 2, 443, 444, 7, 116, 2, 2, 444, 445, 7, 123, 2, 2, 445, 92, 3, 2, 2, 2, 446, 447, 7, 120, 2, 2, 447, 448, 7, 99, 2, 2, 448, 449, 7, 116, 2, 2, 449, 94, 3, 2, 2, 2, 450, 451, 7, 117, 2, 2, 451, 452, 7, 99, 2, 2, 452, 453, 7, 111, 2, 2, 453, 454, 7, 114, 2, 2, 454, 455, 7, 110, 2, 2, 455, 456, 7, 103, 2, 2, 456, 96, 3, 2, 2, 2, 457, 458, 7, 121, 2, 2, 458, 459, 7, 107, 2, 2, 459, 460, 7, 118, 2, 2, 460, 461, 7, 106, 2, 2, 461, 98, 3, 2, 2, 2, 462, 463, 7, 109, 2, 2, 463, 464, 7, 103, 2, 2, 464, 465, 7, 103, 2, 2, 465, 466, 7, 114, 2, 2, 466, 100, 3, 2, 2, 2, 467, 468, 7, 102, 2, 2, 468, 469, 7, 103, 2, 2, 469, 470, 7, 104, 2, 2, 470, 471, 7, 99, 2, 2, 471, 472, 7, 119, 2, 2, 472, 473, 7, 110, 2, 2, 473, 474, 7, 118, 2, 2, 474, 102, 3, 2, 2, 2, 475, 476, 7, 106, 2, 2, 476, 477, 7, 99, 2, 2, 477, 478, 7, 116, 2, 2, 478, 479, 7, 102, 2, 2, 479, 104, 3, 2, 2, 2, 480, 481, 7, 116, 2, 2, 481, 482, 7, 103, 2, 2, 482, 483, 7, 111, 2, 2, 483, 484, 7, 113, 2, 2, 484, 485, 7, 120, 2, 2, 485, 486, 7, 103, 2, 2, 486, 487, 7, 97, 2, 2, 487, 488, 7, 102, 2, 2, 488, 489, 7, 103, 2, 2, 489, 490, 7, 104, 2, 2, 490, 491, 7, 99, 2, 2, 491, 492, 7, 119, 2, 2, 492, 493, 7, 110, 2, 2, 493, 494, 7, 118, 2, 2, 494, 106, 3, 2, 2, 2, 495, 496, 7, 113, 2, 2, 496, 497, 7, 112, 2, 2, 497, 108, 3, 2, 2, 2, 498, 499, 7, 102, 2, 2, 499, 500, 7, 113, 2, 2, 500, 110, 3, 2, 2, 2, 501, 502, 7, 117, 2, 2, 502, 503, 7, 103, 2, 2, 503, 504, 7, 116, 2, 2, 504, 505, 7, 107, 2, 2, 505, 506, 7, 99, 2, 2, 506, 507, 7, 110, 2, 2, 507, 112, 3, 2, 2, 2, 508, 509, 7, 113, 2, 2, 509, 510, 7, 112, 2, 2, 510, 511, 7, 103, 2, 2, 511, 512, 7, 97, 2, 2, 512, 513, 7, 113, 2, 2, 513, 514, 7, 104, 2, 2, 514, 114, 3, 2, 2, 2, 515, 516, 7, 114, 2, 2, 516, 517, 7, 99, 2, 2, 517, 518, 7, 116, 2, 2, 518, 519, 7, 99, 2, 2, 519, 520, 7, 110, 2, 2, 520, 521, 7, 110, 2, 2, 521, 522, 7, 103, 2, 2, 522, 523, 7, 110, 2, 2, 523, 116, 3, 2, 2, 2, 524, 525, 7, 121, 2, 2, 525, 526, 7, 99, 2, 2, 526, 527, 7, 107, 2, 2, 527, 528, 7, 118, 2, 2, 528, 118, 3, 2, 2, 2, 529, 530, 7, 103, 2, 2, 530, 531, 7, 111, 2, 2, 531, 532, 7, 107, 2, 2, 532, 533, 7, 118, 2, 2, 533, 120, 3, 2, 2, 2, 534, 535, 7, 101, 2, 2, 535, 536, 7, 99, 2, 2, 536, 537, 7, 110, 2, 2, 537, 538, 7, 110, 2, 2, 538, 122, 3, 2, 2, 2, 539, 540, 7, 119, 2, 2, 540, 541, 7, 112, 2, 2, 541, 542, 7, 118, 2, 2, 542, 543, 7, 107, 2, 2, 543, 544, 7, 110, 2, 2, 544, 124, 3, 2, 2, 2, 545, 546, 7, 102, 2, 2, 546, 547, 7, 103, 2, 2, 547, 548, 7, 104, 2, 2, 548, 126, 3, 2, 2, 2, 549, 550, 7, 47, 2, 2, 550, 551, 7, 64, 2, 2, 551, 128, 3, 2, 2, 2, 552, 553, 7, 103, 2, 2, 553, 554, 7, 122, 2, 2, 554, 555, 7, 114, 2, 2, 555, 556, 7, 116, 2, 2, 556, 557, 7, 103, 2, 2, 557, 558, 7, 117, 2, 2, 558, 559, 7, 117, 2, 2, 559, 560, 7, 107, 2, 2, 560, 561, 7, 113, 2, 2, 561, 562, 7, 112, 2, 2, 562, 130, 3, 2, 2, 2, 563, 564, 7, 119, 2, 2, 564, 565, 7, 112, 2, 2, 565, 566, 7, 102, 2, 2, 566, 567, 7, 103, 2, 2, 567, 568, 7, 104, 2, 2, 568, 569, 7, 107, 2, 2, 569, 570, 7, 112, 2, 2, 570, 571, 7, 103, 2, 2, 571, 572, 7, 102, 2, 2, 572, 132, 3, 2, 2, 2, 573, 574, 7, 103, 2, 2, 574, 575, 7, 122, 2, 2, 575, 576, 7, 118, 2, 2, 576, 577, 7, 103, 2, 2, 577, 578, 7, 116, 2, 2, 578, 579, 7, 112, 2, 2, 579, 580, 7, 99, 2, 2, 580, 581, 7, 110, 2, 2, 581, 134, 3, 2, 2, 2, 582, 583, 7, 113, 2, 2, 583, 584, 7, 112, 2, 2, 584, 585, 7, 110, 2, 2, 585, 586, 7, 123, 2, 2, 586, 136, 3, 2, 2, 2, 587, 588, 7, 101, 2, 2, 588, 589, 7, 113, 2, 2, 589, 590, 7, 120, 2, 2, 590, 591, 7, 103, 2, 2, 591, 592, 7, 116, 2, 2, 592, 138, 3, 2, 2, 2, 593, 594, 7, 116, 2, 2, 594, 595, 7, 103, 2, 2, 595, 596, 7, 101, 2, 2, 596, 597, 7, 113, 2, 2, 597, 598, 7, 116, 2, 2, 598, 599, 7, 102, 2, 2, 599, 140, 3, 2, 2, 2, 600, 601, 7, 116, 2, 2, 601, 602, 7, 99, 2, 2, 602, 603, 7, 112, 2, 2, 603, 604, 7, 105, 2, 2, 604, 605, 7, 103, 2, 2, 605, 142, 3, 2, 2, 2, 606, 607, 7, 65, 2, 2, 607, 144, 3, 2, 2, 2, 608, 609, 7, 63, 2, 2, 609, 610, 7, 64, 2, 2, 610, 146, 3, 2, 2, 2, 611, 612, 7, 113, 2, 2, 612, 613, 7, 116, 2, 2, 613, 148, 3, 2, 2, 2, 614, 615, 7, 99, 2, 2, 615, 616, 7, 112, 2, 2, 616, 617, 7, 102, 2, 2, 617, 150, 3, 2, 2, 2, 618, 619, 7, 112, 2, 2, 619, 620, 7, 113, 2, 2, 620, 621, 7, 118, 2, 2, 621, 152, 3, 2, 2, 2, 622, 623, 7, 35, 2, 2, 623, 624, 7, 63, 2, 2, 624, 154, 3, 2, 2, 2, 625, 626, 7, 62, 2, 2, 626, 156, 3, 2, 2, 2, 627, 628, 7, 62, 2, 2, 628, 629, 7, 63, 2, 2, 629, 158, 3, 2, 2, 2, 630, 631, 7, 64, 2, 2, 631, 160, 3, 2, 2, 2, 632, 633, 7, 64, 2, 2, 633, 634, 7, 63, 2, 2, 634, 162, 3, 2, 2, 2, 635, 636, 7, 107, 2, 2, 636, 637, 7, 112, 2, 2, 637, 164, 3, 2, 2, 2, 638, 639, 7, 45, 2, 2, 639, 166, 3, 2, 2, 2, 640, 641, 7, 47, 2, 2, 641, 168, 3, 2, 2, 2, 642, 643, 7, 44, 2, 2, 643, 170, 3, 2, 2, 2, 644, 645, 7, 49, 2, 2, 645, 172, 3, 2, 2, 2, 646, 647, 7, 39, 2, 2, 647, 174, 3, 2, 2, 2, 648, 649, 7, 107, 2, 2, 649, 650, 7, 118, 2, 2, 650, 176, 3, 2, 2, 2, 651, 652, 7, 48, 2, 2, 652, 653, 7, 48, 2, 2, 653, 178, 3, 2, 2, 2, 654, 655, 6, 90, 2, 2, 655, 667, 5, 191, 96, 2, 656, 658, 7, 15, 2, 2, 657, 656, 3, 2, 2, 2, 657, 658, 3, 2, 2, 2, 658, 659, 3, 2, 2, 2, 659, 662, 7, 12, 2, 2, 660, 662, 4, 14, 15, 2, 661, 657, 3, 2, 2, 2, 661, 660, 3, 2, 2, 2, 662, 664, 3, 2, 2, 2, 663, 665, 5, 191, 96, 2, 664, 663, 3, 2, 2, 2, 664, 665, 3, 2, 2, 2, 665, 667, 3, 2, 2, 2, 666, 654, 3, 2, 2, 2, 666, 661, 3, 2, 2, 2, 667, 668, 3, 2, 2, 2, 668, 669, 8, 90, 2, 2, 669, 180, 3, 2, 2, 2, 670, 671, 7, 93, 2, 2, 671, 672, 8, 91, 3, 2, 672, 182, 3, 2, 2, 2, 673, 674, 7, 95, 2, 2, 674, 675, 8, 92, 4, 2, 675, 184, 3, 2, 2, 2, 676, 677, 7, 42, 2, 2, 677, 678, 8, 93, 5, 2, 678, 186, 3, 2, 2, 2, 679, 680, 7, 43, 2, 2, 680, 681, 8, 94, 6, 2, 681, 188, 3, 2, 2, 2, 682, 685, 5, 191, 96, 2, 683, 685, 5, 193, 97, 2, 684, 682, 3, 2, 2, 2, 684, 683, 3, 2, 2, 2, 685, 686, 3, 2, 2, 2, 686, 687, 8, 95, 7, 2, 687, 190, 3, 2, 2, 2, 688, 690, 9, 2, 2, 2, 689, 688, 3, 2, 2, 2, 690, 691, 3, 2, 2, 2, 691, 689, 3, 2, 2, 2, 691, 692, 3, 2, 2, 2, 692, 192, 3, 2, 2, 2, 693, 695, 7, 94, 2, 2, 694, 696, 5, 191, 96, 2, 695, 694, 3, 2, 2, 2, 695, 696, 3, 2, 2, 2, 696, 698, 3, 2, 2, 2, 697, 699, 7, 15, 2, 2, 698, 697, 3, 2, 2, 2, 698, 699, 3, 2, 2, 2, 699, 700, 3, 2, 2, 2, 700, 701, 7, 12, 2, 2, 701, 194, 3, 2, 2, 2, 702, 704, 7, 15, 2, 2, 703, 702, 3, 2, 2, 2, 703, 704, 3, 2, 2, 2, 704, 705, 3, 2, 2, 2, 705, 706, 7, 12, 2, 2, 706, 196, 3, 2, 2, 2, 707, 708, 7, 49, 2, 2, 708, 709, 7, 44, 2, 2, 709, 713, 3, 2, 2, 2, 710, 712, 11, 2, 2, 2, 711, 710, 3, 2, 2, 2, 712, 715, 3, 2, 2, 2, 713, 714, 3, 2, 2, 2, 713, 711, 3, 2, 2, 2, 714, 716, 3, 2, 2, 2, 715, 713, 3, 2, 2, 2, 716, 717, 7, 44, 2, 2, 717, 718, 7, 49, 2, 2, 718, 719, 3, 2, 2, 2, 719, 720, 8, 99, 7, 2, 720, 198, 3, 2, 2, 2, 721, 725, 7, 37, 2, 2, 722, 724, 10, 3, 2, 2, 723, 722, 3, 2, 2, 2, 724, 727, 3, 2, 2, 2, 725, 723, 3, 2, 2, 2, 725, 726, 3, 2, 2, 2, 726, 728, 3, 2, 2, 2, 727, 725, 3, 2, 2, 2, 728, 729, 8, 100, 7, 2, 729, 200, 3, 2, 2, 2, 730, 733, 5, 203, 102, 2, 731, 733, 5, 209, 105, 2, 732, 730, 3, 2, 2, 2, 732, 731, 3, 2, 2, 2, 733, 202, 3, 2, 2, 2, 734, 738, 7, 36, 2, 2, 735, 737, 5, 205, 103, 2, 736, 735, 3, 2, 2, 2, 737, 740, 3, 2, 2, 2, 738, 736, 3, 2, 2, 2, 738, 739, 3, 2, 2, 2, 739, 741, 3, 2, 2, 2, 740, 738, 3, 2, 2, 2, 741, 751, 7, 36, 2, 2, 742, 746, 7, 41, 2, 2, 743, 745, 5, 205, 103, 2, 744, 743, 3, 2, 2, 2, 745, 748, 3, 2, 2, 2, 746, 744, 3, 2, 2, 2, 746, 747, 3, 2, 2, 2, 747, 749, 3, 2, 2, 2, 748, 746, 3, 2, 2, 2, 749, 751, 7, 41, 2, 2, 750, 734, 3, 2, 2, 2, 750, 742, 3, 2, 2, 2, 751, 204, 3, 2, 2, 2, 752, 755, 5, 207, 104, 2, 753, 755, 5, 215, 108, 2, 754, 752, 3, 2, 2, 2, 754, 753, 3, 2, 2, 2, 755, 206, 3, 2, 2, 2, 756, 757, 10, 4, 2, 2, 757, 208, 3, 2, 2, 2, 758, 759, 7, 36, 2, 2, 759, 760, 7, 36, 2, 2, 760, 761, 7, 36, 2, 2, 761, 765, 3, 2, 2, 2, 762, 764, 5, 211, 106, 2, 763, 762, 3, 2, 2, 2, 764, 767, 3, 2, 2, 2, 765, 763, 3, 2, 2, 2, 765, 766, 3, 2, 2, 2, 766, 768, 3, 2, 2, 2, 767, 765, 3, 2, 2, 2, 768, 769, 7, 36, 2, 2, 769, 770, 7, 36, 2, 2, 770, 785, 7, 36, 2, 2, 771, 772, 7, 41, 2, 2, 772, 773, 7, 41, 2, 2, 773, 774, 7, 41, 2, 2, 774, 778, 3, 2, 2, 2, 775, 777, 5, 211, 106, 2, 776, 775, 3, 2, 2, 2, 777, 780, 3, 2, 2, 2, 778, 776, 3, 2, 2, 2, 778, 779, 3, 2, 2, 2, 779, 781, 3, 2, 2, 2, 780, 778, 3, 2, 2, 2, 781, 782, 7, 41, 2, 2, 782, 783, 7, 41, 2, 2, 783, 785, 7, 41, 2, 2, 784, 758, 3, 2, 2, 2, 784, 771, 3, 2, 2, 2, 785, 210, 3, 2, 2, 2, 786, 789, 5, 213, 107, 2, 787, 789, 5, 215, 108, 2, 788, 786, 3, 2, 2, 2, 788, 787, 3, 2, 2, 2, 789, 212, 3, 2, 2, 2, 790, 791, 10, 5, 2, 2, 791, 214, 3, 2, 2, 2, 792, 793, 7, 94, 2, 2, 793, 797, 11, 2, 2, 2, 794, 795, 7, 94, 2, 2, 795, 797, 5, 195, 98, 2, 796, 792, 3, 2, 2, 2, 796, 794, 3, 2, 2, 2, 797, 216, 3, 2, 2, 2, 798, 800, 9, 6, 2, 2, 799, 798, 3, 2, 2, 2, 799, 800, 3, 2, 2, 2, 800, 804, 3, 2, 2, 2, 801, 803, 5, 231, 116, 2, 802, 801, 3, 2, 2, 2, 803, 806, 3, 2, 2, 2, 804, 802, 3, 2, 2, 2, 804, 805, 3, 2, 2, 2, 805, 807, 3, 2, 2, 2, 806, 804, 3, 2, 2, 2, 807, 809, 7, 48, 2, 2, 808, 810, 5, 231, 116, 2, 809, 808, 3, 2, 2, 2, 810, 811, 3, 2, 2, 2, 811, 809, 3, 2, 2, 2, 811, 812, 3, 2, 2, 2, 812, 822, 3, 2, 2, 2, 813, 815, 9, 7, 2, 2, 814, 816, 9, 6, 2, 2, 815, 814, 3, 2, 2, 2, 815, 816, 3, 2, 2, 2, 816, 818, 3, 2, 2, 2, 817, 819, 5, 231, 116, 2, 818, 817, 3, 2, 2, 2, 819, 820, 3, 2, 2, 2, 820, 818, 3, 2, 2, 2, 820, 821, 3, 2, 2, 2, 821, 823, 3, 2, 2, 2, 822, 813, 3, 2, 2, 2, 822, 823, 3, 2, 2, 2, 823, 218, 3, 2, 2, 2, 824, 826, 5, 231, 116, 2, 825, 824, 3, 2, 2, 2, 826, 827, 3, 2, 2, 2, 827, 825, 3, 2, 2, 2, 827, 828, 3, 2, 2, 2, 828, 220, 3, 2, 2, 2, 829, 830, 7, 50, 2, 2, 830, 831, 7, 122, 2, 2, 831, 833, 3, 2, 2, 2, 832, 834, 5, 233, 117, 2, 833, 832, 3, 2, 2, 2, 834, 835, 3, 2, 2, 2, 835, 833, 3, 2, 2, 2, 835, 836, 3, 2, 2, 2, 836, 222, 3, 2, 2, 2, 837, 839, 7, 47, 2, 2, 838, 840, 5, 231, 116, 2, 839, 838, 3, 2, 2, 2, 840, 841, 3, 2, 2, 2, 841, 839, 3, 2, 2, 2, 841, 842, 3, 2, 2, 2, 842, 224, 3, 2, 2, 2, 843, 844, 7, 118, 2, 2, 844, 845, 7, 116, 2, 2, 845, 846, 7, 119, 2, 2, 846, 853, 7, 103, 2, 2, 847, 848, 7, 104, 2, 2, 848, 849, 7, 99, 2, 2, 849, 850, 7, 110, 2, 2, 850, 851, 7, 117, 2, 2, 851, 853, 7, 103, 2, 2, 852, 843, 3, 2, 2, 2, 852, 847, 3, 2, 2, 2, 853, 226, 3, 2, 2, 2, 854, 858, 9, 8, 2, 2, 855, 857, 9, 9, 2, 2, 856, 855, 3, 2, 2, 2, 857, 860, 3, 2, 2, 2, 858, 856, 3, 2, 2, 2, 858, 859, 3, 2, 2, 2, 859, 869, 3, 2, 2, 2, 860, 858, 3, 2, 2, 2, 861, 863, 7, 126, 2, 2, 862, 864, 10, 10, 2, 2, 863, 862, 3, 2, 2, 2, 864, 865, 3, 2, 2, 2, 865, 863, 3, 2, 2, 2, 865, 866, 3, 2, 2, 2, 866, 867, 3, 2, 2, 2, 867, 869, 7, 126, 2, 2, 868, 854, 3, 2, 2, 2, 868, 861, 3, 2, 2, 2, 869, 228, 3, 2, 2, 2, 870, 871, 10, 10, 2, 2, 871, 230, 3, 2, 2, 2, 872, 873, 9, 11, 2, 2, 873, 232, 3, 2, 2, 2, 874, 875, 9, 12, 2, 2, 875, 234, 3, 2, 2, 2, 37, 2, 657, 661, 664, 666, 684, 691, 695, 698, 703, 713, 725, 732, 738, 746, 750, 754, 765, 778, 784, 788, 796, 799, 804, 811, 815, 820, 822, 827, 835, 841, 852, 858, 865, 868, 8, 3, 90, 2, 3, 91, 3, 3, 92, 4, 3, 93, 5, 3, 94, 6, 8, 2, 2] \ No newline at end of file diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.py b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.py new file mode 100644 index 00000000..68a65706 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.py @@ -0,0 +1,757 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +# Generated from OpenSCENARIO2.g4 by ANTLR 4.7.2 +from antlr4 import * +from io import StringIO +from typing.io import TextIO +import sys + + +from antlr4.Token import CommonToken +import re +import importlib +# Allow languages to extend the lexer and parser, by loading the parser dynamically +module_path = __name__[:-5] +language_name = __name__.split('.')[-1] +language_name = language_name[:-5] # Remove Lexer from name +LanguageParser = getattr(importlib.import_module('{}Parser'.format(module_path)), '{}Parser'.format(language_name)) + + +def serializedATN(): + with StringIO() as buf: + buf.write("\3\u608b\ua72a\u8133\ub9ed\u417c\u3be7\u7786\u5964\2i") + buf.write("\u036c\b\1\4\2\t\2\4\3\t\3\4\4\t\4\4\5\t\5\4\6\t\6\4\7") + buf.write("\t\7\4\b\t\b\4\t\t\t\4\n\t\n\4\13\t\13\4\f\t\f\4\r\t\r") + buf.write("\4\16\t\16\4\17\t\17\4\20\t\20\4\21\t\21\4\22\t\22\4\23") + buf.write("\t\23\4\24\t\24\4\25\t\25\4\26\t\26\4\27\t\27\4\30\t\30") + buf.write("\4\31\t\31\4\32\t\32\4\33\t\33\4\34\t\34\4\35\t\35\4\36") + buf.write("\t\36\4\37\t\37\4 \t \4!\t!\4\"\t\"\4#\t#\4$\t$\4%\t%") + buf.write("\4&\t&\4\'\t\'\4(\t(\4)\t)\4*\t*\4+\t+\4,\t,\4-\t-\4.") + buf.write("\t.\4/\t/\4\60\t\60\4\61\t\61\4\62\t\62\4\63\t\63\4\64") + buf.write("\t\64\4\65\t\65\4\66\t\66\4\67\t\67\48\t8\49\t9\4:\t:") + buf.write("\4;\t;\4<\t<\4=\t=\4>\t>\4?\t?\4@\t@\4A\tA\4B\tB\4C\t") + buf.write("C\4D\tD\4E\tE\4F\tF\4G\tG\4H\tH\4I\tI\4J\tJ\4K\tK\4L\t") + buf.write("L\4M\tM\4N\tN\4O\tO\4P\tP\4Q\tQ\4R\tR\4S\tS\4T\tT\4U\t") + buf.write("U\4V\tV\4W\tW\4X\tX\4Y\tY\4Z\tZ\4[\t[\4\\\t\\\4]\t]\4") + buf.write("^\t^\4_\t_\4`\t`\4a\ta\4b\tb\4c\tc\4d\td\4e\te\4f\tf\4") + buf.write("g\tg\4h\th\4i\ti\4j\tj\4k\tk\4l\tl\4m\tm\4n\tn\4o\to\4") + buf.write("p\tp\4q\tq\4r\tr\4s\ts\4t\tt\4u\tu\3\2\3\2\3\2\3\2\3\2") + buf.write("\3\2\3\2\3\3\3\3\3\4\3\4\3\4\3\4\3\4\3\5\3\5\3\5\3\6\3") + buf.write("\6\3\6\3\7\3\7\3\7\3\7\3\7\3\b\3\b\3\b\3\t\3\t\3\n\3\n") + buf.write("\3\13\3\13\3\13\3\13\3\13\3\13\3\13\3\f\3\f\3\f\3\f\3") + buf.write("\f\3\f\3\f\3\r\3\r\3\r\3\16\3\16\3\17\3\17\3\20\3\20\3") + buf.write("\21\3\21\3\22\3\22\3\22\3\22\3\23\3\23\3\23\3\24\3\24") + buf.write("\3\24\3\24\3\25\3\25\3\25\3\25\3\25\3\26\3\26\3\27\3\27") + buf.write("\3\30\3\30\3\30\3\31\3\31\3\31\3\31\3\31\3\31\3\31\3\32") + buf.write("\3\32\3\32\3\32\3\32\3\32\3\32\3\32\3\32\3\33\3\33\3\33") + buf.write("\3\33\3\33\3\33\3\34\3\34\3\34\3\34\3\34\3\34\3\34\3\34") + buf.write("\3\34\3\35\3\35\3\35\3\35\3\35\3\35\3\35\3\36\3\36\3\36") + buf.write("\3\36\3\36\3\36\3\36\3\36\3\36\3\37\3\37\3\37\3\37\3\37") + buf.write("\3\37\3\37\3 \3 \3 \3 \3 \3 \3 \3!\3!\3!\3!\3!\3\"\3\"") + buf.write("\3\"\3\"\3#\3#\3#\3#\3#\3$\3$\3$\3$\3$\3$\3%\3%\3%\3%") + buf.write("\3%\3&\3&\3&\3&\3&\3&\3&\3\'\3\'\3\'\3\'\3\'\3\'\3(\3") + buf.write("(\3(\3)\3)\3*\3*\3*\3+\3+\3+\3+\3+\3,\3,\3,\3,\3,\3-\3") + buf.write("-\3-\3-\3-\3-\3-\3-\3.\3.\3.\3.\3.\3.\3/\3/\3/\3/\3\60") + buf.write("\3\60\3\60\3\60\3\60\3\60\3\60\3\61\3\61\3\61\3\61\3\61") + buf.write("\3\62\3\62\3\62\3\62\3\62\3\63\3\63\3\63\3\63\3\63\3\63") + buf.write("\3\63\3\63\3\64\3\64\3\64\3\64\3\64\3\65\3\65\3\65\3\65") + buf.write("\3\65\3\65\3\65\3\65\3\65\3\65\3\65\3\65\3\65\3\65\3\65") + buf.write("\3\66\3\66\3\66\3\67\3\67\3\67\38\38\38\38\38\38\38\3") + buf.write("9\39\39\39\39\39\39\3:\3:\3:\3:\3:\3:\3:\3:\3:\3;\3;\3") + buf.write(";\3;\3;\3<\3<\3<\3<\3<\3=\3=\3=\3=\3=\3>\3>\3>\3>\3>\3") + buf.write(">\3?\3?\3?\3?\3@\3@\3@\3A\3A\3A\3A\3A\3A\3A\3A\3A\3A\3") + buf.write("A\3B\3B\3B\3B\3B\3B\3B\3B\3B\3B\3C\3C\3C\3C\3C\3C\3C\3") + buf.write("C\3C\3D\3D\3D\3D\3D\3E\3E\3E\3E\3E\3E\3F\3F\3F\3F\3F\3") + buf.write("F\3F\3G\3G\3G\3G\3G\3G\3H\3H\3I\3I\3I\3J\3J\3J\3K\3K\3") + buf.write("K\3K\3L\3L\3L\3L\3M\3M\3M\3N\3N\3O\3O\3O\3P\3P\3Q\3Q\3") + buf.write("Q\3R\3R\3R\3S\3S\3T\3T\3U\3U\3V\3V\3W\3W\3X\3X\3X\3Y\3") + buf.write("Y\3Y\3Z\3Z\3Z\5Z\u0292\nZ\3Z\3Z\5Z\u0296\nZ\3Z\5Z\u0299") + buf.write("\nZ\5Z\u029b\nZ\3Z\3Z\3[\3[\3[\3\\\3\\\3\\\3]\3]\3]\3") + buf.write("^\3^\3^\3_\3_\5_\u02ad\n_\3_\3_\3`\6`\u02b2\n`\r`\16`") + buf.write("\u02b3\3a\3a\5a\u02b8\na\3a\5a\u02bb\na\3a\3a\3b\5b\u02c0") + buf.write("\nb\3b\3b\3c\3c\3c\3c\7c\u02c8\nc\fc\16c\u02cb\13c\3c") + buf.write("\3c\3c\3c\3c\3d\3d\7d\u02d4\nd\fd\16d\u02d7\13d\3d\3d") + buf.write("\3e\3e\5e\u02dd\ne\3f\3f\7f\u02e1\nf\ff\16f\u02e4\13f") + buf.write("\3f\3f\3f\7f\u02e9\nf\ff\16f\u02ec\13f\3f\5f\u02ef\nf") + buf.write("\3g\3g\5g\u02f3\ng\3h\3h\3i\3i\3i\3i\3i\7i\u02fc\ni\f") + buf.write("i\16i\u02ff\13i\3i\3i\3i\3i\3i\3i\3i\3i\7i\u0309\ni\f") + buf.write("i\16i\u030c\13i\3i\3i\3i\5i\u0311\ni\3j\3j\5j\u0315\n") + buf.write("j\3k\3k\3l\3l\3l\3l\5l\u031d\nl\3m\5m\u0320\nm\3m\7m\u0323") + buf.write("\nm\fm\16m\u0326\13m\3m\3m\6m\u032a\nm\rm\16m\u032b\3") + buf.write("m\3m\5m\u0330\nm\3m\6m\u0333\nm\rm\16m\u0334\5m\u0337") + buf.write("\nm\3n\6n\u033a\nn\rn\16n\u033b\3o\3o\3o\3o\6o\u0342\n") + buf.write("o\ro\16o\u0343\3p\3p\6p\u0348\np\rp\16p\u0349\3q\3q\3") + buf.write("q\3q\3q\3q\3q\3q\3q\5q\u0355\nq\3r\3r\7r\u0359\nr\fr\16") + buf.write("r\u035c\13r\3r\3r\6r\u0360\nr\rr\16r\u0361\3r\5r\u0365") + buf.write("\nr\3s\3s\3t\3t\3u\3u\3\u02c9\2v\3\3\5\4\7\5\t\6\13\7") + buf.write("\r\b\17\t\21\n\23\13\25\f\27\r\31\16\33\17\35\20\37\21") + buf.write("!\22#\23%\24\'\25)\26+\27-\30/\31\61\32\63\33\65\34\67") + buf.write("\359\36;\37= ?!A\"C#E$G%I&K\'M(O)Q*S+U,W-Y.[/]\60_\61") + buf.write("a\62c\63e\64g\65i\66k\67m8o9q:s;u{?}@\177A\u0081") + buf.write("B\u0083C\u0085D\u0087E\u0089F\u008bG\u008dH\u008fI\u0091") + buf.write("J\u0093K\u0095L\u0097M\u0099N\u009bO\u009dP\u009fQ\u00a1") + buf.write("R\u00a3S\u00a5T\u00a7U\u00a9V\u00abW\u00adX\u00afY\u00b1") + buf.write("Z\u00b3[\u00b5\\\u00b7]\u00b9^\u00bb_\u00bd`\u00bf\2\u00c1") + buf.write("\2\u00c3\2\u00c5a\u00c7b\u00c9c\u00cb\2\u00cd\2\u00cf") + buf.write("\2\u00d1\2\u00d3\2\u00d5\2\u00d7\2\u00d9d\u00dbe\u00dd") + buf.write("f\u00dfg\u00e1h\u00e3i\u00e5\2\u00e7\2\u00e9\2\3\2\r\4") + buf.write("\2\13\13\"\"\4\2\f\f\16\17\7\2\f\f\17\17$$))^^\3\2^^\4") + buf.write("\2--//\4\2GGgg\4\2C\\c|\6\2\62;C\\aac|\3\2~~\3\2\62;\5") + buf.write("\2\62;CHch\2\u0380\2\3\3\2\2\2\2\5\3\2\2\2\2\7\3\2\2\2") + buf.write("\2\t\3\2\2\2\2\13\3\2\2\2\2\r\3\2\2\2\2\17\3\2\2\2\2\21") + buf.write("\3\2\2\2\2\23\3\2\2\2\2\25\3\2\2\2\2\27\3\2\2\2\2\31\3") + buf.write("\2\2\2\2\33\3\2\2\2\2\35\3\2\2\2\2\37\3\2\2\2\2!\3\2\2") + buf.write("\2\2#\3\2\2\2\2%\3\2\2\2\2\'\3\2\2\2\2)\3\2\2\2\2+\3\2") + buf.write("\2\2\2-\3\2\2\2\2/\3\2\2\2\2\61\3\2\2\2\2\63\3\2\2\2\2") + buf.write("\65\3\2\2\2\2\67\3\2\2\2\29\3\2\2\2\2;\3\2\2\2\2=\3\2") + buf.write("\2\2\2?\3\2\2\2\2A\3\2\2\2\2C\3\2\2\2\2E\3\2\2\2\2G\3") + buf.write("\2\2\2\2I\3\2\2\2\2K\3\2\2\2\2M\3\2\2\2\2O\3\2\2\2\2Q") + buf.write("\3\2\2\2\2S\3\2\2\2\2U\3\2\2\2\2W\3\2\2\2\2Y\3\2\2\2\2") + buf.write("[\3\2\2\2\2]\3\2\2\2\2_\3\2\2\2\2a\3\2\2\2\2c\3\2\2\2") + buf.write("\2e\3\2\2\2\2g\3\2\2\2\2i\3\2\2\2\2k\3\2\2\2\2m\3\2\2") + buf.write("\2\2o\3\2\2\2\2q\3\2\2\2\2s\3\2\2\2\2u\3\2\2\2\2w\3\2") + buf.write("\2\2\2y\3\2\2\2\2{\3\2\2\2\2}\3\2\2\2\2\177\3\2\2\2\2") + buf.write("\u0081\3\2\2\2\2\u0083\3\2\2\2\2\u0085\3\2\2\2\2\u0087") + buf.write("\3\2\2\2\2\u0089\3\2\2\2\2\u008b\3\2\2\2\2\u008d\3\2\2") + buf.write("\2\2\u008f\3\2\2\2\2\u0091\3\2\2\2\2\u0093\3\2\2\2\2\u0095") + buf.write("\3\2\2\2\2\u0097\3\2\2\2\2\u0099\3\2\2\2\2\u009b\3\2\2") + buf.write("\2\2\u009d\3\2\2\2\2\u009f\3\2\2\2\2\u00a1\3\2\2\2\2\u00a3") + buf.write("\3\2\2\2\2\u00a5\3\2\2\2\2\u00a7\3\2\2\2\2\u00a9\3\2\2") + buf.write("\2\2\u00ab\3\2\2\2\2\u00ad\3\2\2\2\2\u00af\3\2\2\2\2\u00b1") + buf.write("\3\2\2\2\2\u00b3\3\2\2\2\2\u00b5\3\2\2\2\2\u00b7\3\2\2") + buf.write("\2\2\u00b9\3\2\2\2\2\u00bb\3\2\2\2\2\u00bd\3\2\2\2\2\u00c5") + buf.write("\3\2\2\2\2\u00c7\3\2\2\2\2\u00c9\3\2\2\2\2\u00d9\3\2\2") + buf.write("\2\2\u00db\3\2\2\2\2\u00dd\3\2\2\2\2\u00df\3\2\2\2\2\u00e1") + buf.write("\3\2\2\2\2\u00e3\3\2\2\2\3\u00eb\3\2\2\2\5\u00f2\3\2\2") + buf.write("\2\7\u00f4\3\2\2\2\t\u00f9\3\2\2\2\13\u00fc\3\2\2\2\r") + buf.write("\u00ff\3\2\2\2\17\u0104\3\2\2\2\21\u0107\3\2\2\2\23\u0109") + buf.write("\3\2\2\2\25\u010b\3\2\2\2\27\u0112\3\2\2\2\31\u0119\3") + buf.write("\2\2\2\33\u011c\3\2\2\2\35\u011e\3\2\2\2\37\u0120\3\2") + buf.write("\2\2!\u0122\3\2\2\2#\u0124\3\2\2\2%\u0128\3\2\2\2\'\u012b") + buf.write("\3\2\2\2)\u012f\3\2\2\2+\u0134\3\2\2\2-\u0136\3\2\2\2") + buf.write("/\u0138\3\2\2\2\61\u013b\3\2\2\2\63\u0142\3\2\2\2\65\u014b") + buf.write("\3\2\2\2\67\u0151\3\2\2\29\u015a\3\2\2\2;\u0161\3\2\2") + buf.write("\2=\u016a\3\2\2\2?\u0171\3\2\2\2A\u0178\3\2\2\2C\u017d") + buf.write("\3\2\2\2E\u0181\3\2\2\2G\u0186\3\2\2\2I\u018c\3\2\2\2") + buf.write("K\u0191\3\2\2\2M\u0198\3\2\2\2O\u019e\3\2\2\2Q\u01a1\3") + buf.write("\2\2\2S\u01a3\3\2\2\2U\u01a6\3\2\2\2W\u01ab\3\2\2\2Y\u01b0") + buf.write("\3\2\2\2[\u01b8\3\2\2\2]\u01be\3\2\2\2_\u01c2\3\2\2\2") + buf.write("a\u01c9\3\2\2\2c\u01ce\3\2\2\2e\u01d3\3\2\2\2g\u01db\3") + buf.write("\2\2\2i\u01e0\3\2\2\2k\u01ef\3\2\2\2m\u01f2\3\2\2\2o\u01f5") + buf.write("\3\2\2\2q\u01fc\3\2\2\2s\u0203\3\2\2\2u\u020c\3\2\2\2") + buf.write("w\u0211\3\2\2\2y\u0216\3\2\2\2{\u021b\3\2\2\2}\u0221\3") + buf.write("\2\2\2\177\u0225\3\2\2\2\u0081\u0228\3\2\2\2\u0083\u0233") + buf.write("\3\2\2\2\u0085\u023d\3\2\2\2\u0087\u0246\3\2\2\2\u0089") + buf.write("\u024b\3\2\2\2\u008b\u0251\3\2\2\2\u008d\u0258\3\2\2\2") + buf.write("\u008f\u025e\3\2\2\2\u0091\u0260\3\2\2\2\u0093\u0263\3") + buf.write("\2\2\2\u0095\u0266\3\2\2\2\u0097\u026a\3\2\2\2\u0099\u026e") + buf.write("\3\2\2\2\u009b\u0271\3\2\2\2\u009d\u0273\3\2\2\2\u009f") + buf.write("\u0276\3\2\2\2\u00a1\u0278\3\2\2\2\u00a3\u027b\3\2\2\2") + buf.write("\u00a5\u027e\3\2\2\2\u00a7\u0280\3\2\2\2\u00a9\u0282\3") + buf.write("\2\2\2\u00ab\u0284\3\2\2\2\u00ad\u0286\3\2\2\2\u00af\u0288") + buf.write("\3\2\2\2\u00b1\u028b\3\2\2\2\u00b3\u029a\3\2\2\2\u00b5") + buf.write("\u029e\3\2\2\2\u00b7\u02a1\3\2\2\2\u00b9\u02a4\3\2\2\2") + buf.write("\u00bb\u02a7\3\2\2\2\u00bd\u02ac\3\2\2\2\u00bf\u02b1\3") + buf.write("\2\2\2\u00c1\u02b5\3\2\2\2\u00c3\u02bf\3\2\2\2\u00c5\u02c3") + buf.write("\3\2\2\2\u00c7\u02d1\3\2\2\2\u00c9\u02dc\3\2\2\2\u00cb") + buf.write("\u02ee\3\2\2\2\u00cd\u02f2\3\2\2\2\u00cf\u02f4\3\2\2\2") + buf.write("\u00d1\u0310\3\2\2\2\u00d3\u0314\3\2\2\2\u00d5\u0316\3") + buf.write("\2\2\2\u00d7\u031c\3\2\2\2\u00d9\u031f\3\2\2\2\u00db\u0339") + buf.write("\3\2\2\2\u00dd\u033d\3\2\2\2\u00df\u0345\3\2\2\2\u00e1") + buf.write("\u0354\3\2\2\2\u00e3\u0364\3\2\2\2\u00e5\u0366\3\2\2\2") + buf.write("\u00e7\u0368\3\2\2\2\u00e9\u036a\3\2\2\2\u00eb\u00ec\7") + buf.write("k\2\2\u00ec\u00ed\7o\2\2\u00ed\u00ee\7r\2\2\u00ee\u00ef") + buf.write("\7q\2\2\u00ef\u00f0\7t\2\2\u00f0\u00f1\7v\2\2\u00f1\4") + buf.write("\3\2\2\2\u00f2\u00f3\7\60\2\2\u00f3\6\3\2\2\2\u00f4\u00f5") + buf.write("\7v\2\2\u00f5\u00f6\7{\2\2\u00f6\u00f7\7r\2\2\u00f7\u00f8") + buf.write("\7g\2\2\u00f8\b\3\2\2\2\u00f9\u00fa\7k\2\2\u00fa\u00fb") + buf.write("\7u\2\2\u00fb\n\3\2\2\2\u00fc\u00fd\7U\2\2\u00fd\u00fe") + buf.write("\7K\2\2\u00fe\f\3\2\2\2\u00ff\u0100\7w\2\2\u0100\u0101") + buf.write("\7p\2\2\u0101\u0102\7k\2\2\u0102\u0103\7v\2\2\u0103\16") + buf.write("\3\2\2\2\u0104\u0105\7q\2\2\u0105\u0106\7h\2\2\u0106\20") + buf.write("\3\2\2\2\u0107\u0108\7.\2\2\u0108\22\3\2\2\2\u0109\u010a") + buf.write("\7<\2\2\u010a\24\3\2\2\2\u010b\u010c\7h\2\2\u010c\u010d") + buf.write("\7c\2\2\u010d\u010e\7e\2\2\u010e\u010f\7v\2\2\u010f\u0110") + buf.write("\7q\2\2\u0110\u0111\7t\2\2\u0111\26\3\2\2\2\u0112\u0113") + buf.write("\7q\2\2\u0113\u0114\7h\2\2\u0114\u0115\7h\2\2\u0115\u0116") + buf.write("\7u\2\2\u0116\u0117\7g\2\2\u0117\u0118\7v\2\2\u0118\30") + buf.write("\3\2\2\2\u0119\u011a\7m\2\2\u011a\u011b\7i\2\2\u011b\32") + buf.write("\3\2\2\2\u011c\u011d\7o\2\2\u011d\34\3\2\2\2\u011e\u011f") + buf.write("\7u\2\2\u011f\36\3\2\2\2\u0120\u0121\7C\2\2\u0121 \3\2") + buf.write("\2\2\u0122\u0123\7M\2\2\u0123\"\3\2\2\2\u0124\u0125\7") + buf.write("o\2\2\u0125\u0126\7q\2\2\u0126\u0127\7n\2\2\u0127$\3\2") + buf.write("\2\2\u0128\u0129\7e\2\2\u0129\u012a\7f\2\2\u012a&\3\2") + buf.write("\2\2\u012b\u012c\7t\2\2\u012c\u012d\7c\2\2\u012d\u012e") + buf.write("\7f\2\2\u012e(\3\2\2\2\u012f\u0130\7g\2\2\u0130\u0131") + buf.write("\7p\2\2\u0131\u0132\7w\2\2\u0132\u0133\7o\2\2\u0133*\3") + buf.write("\2\2\2\u0134\u0135\7?\2\2\u0135,\3\2\2\2\u0136\u0137\7") + buf.write("#\2\2\u0137.\3\2\2\2\u0138\u0139\7?\2\2\u0139\u013a\7") + buf.write("?\2\2\u013a\60\3\2\2\2\u013b\u013c\7u\2\2\u013c\u013d") + buf.write("\7v\2\2\u013d\u013e\7t\2\2\u013e\u013f\7w\2\2\u013f\u0140") + buf.write("\7e\2\2\u0140\u0141\7v\2\2\u0141\62\3\2\2\2\u0142\u0143") + buf.write("\7k\2\2\u0143\u0144\7p\2\2\u0144\u0145\7j\2\2\u0145\u0146") + buf.write("\7g\2\2\u0146\u0147\7t\2\2\u0147\u0148\7k\2\2\u0148\u0149") + buf.write("\7v\2\2\u0149\u014a\7u\2\2\u014a\64\3\2\2\2\u014b\u014c") + buf.write("\7c\2\2\u014c\u014d\7e\2\2\u014d\u014e\7v\2\2\u014e\u014f") + buf.write("\7q\2\2\u014f\u0150\7t\2\2\u0150\66\3\2\2\2\u0151\u0152") + buf.write("\7u\2\2\u0152\u0153\7e\2\2\u0153\u0154\7g\2\2\u0154\u0155") + buf.write("\7p\2\2\u0155\u0156\7c\2\2\u0156\u0157\7t\2\2\u0157\u0158") + buf.write("\7k\2\2\u0158\u0159\7q\2\2\u01598\3\2\2\2\u015a\u015b") + buf.write("\7c\2\2\u015b\u015c\7e\2\2\u015c\u015d\7v\2\2\u015d\u015e") + buf.write("\7k\2\2\u015e\u015f\7q\2\2\u015f\u0160\7p\2\2\u0160:\3") + buf.write("\2\2\2\u0161\u0162\7o\2\2\u0162\u0163\7q\2\2\u0163\u0164") + buf.write("\7f\2\2\u0164\u0165\7k\2\2\u0165\u0166\7h\2\2\u0166\u0167") + buf.write("\7k\2\2\u0167\u0168\7g\2\2\u0168\u0169\7t\2\2\u0169<\3") + buf.write("\2\2\2\u016a\u016b\7g\2\2\u016b\u016c\7z\2\2\u016c\u016d") + buf.write("\7v\2\2\u016d\u016e\7g\2\2\u016e\u016f\7p\2\2\u016f\u0170") + buf.write("\7f\2\2\u0170>\3\2\2\2\u0171\u0172\7i\2\2\u0172\u0173") + buf.write("\7n\2\2\u0173\u0174\7q\2\2\u0174\u0175\7d\2\2\u0175\u0176") + buf.write("\7c\2\2\u0176\u0177\7n\2\2\u0177@\3\2\2\2\u0178\u0179") + buf.write("\7n\2\2\u0179\u017a\7k\2\2\u017a\u017b\7u\2\2\u017b\u017c") + buf.write("\7v\2\2\u017cB\3\2\2\2\u017d\u017e\7k\2\2\u017e\u017f") + buf.write("\7p\2\2\u017f\u0180\7v\2\2\u0180D\3\2\2\2\u0181\u0182") + buf.write("\7w\2\2\u0182\u0183\7k\2\2\u0183\u0184\7p\2\2\u0184\u0185") + buf.write("\7v\2\2\u0185F\3\2\2\2\u0186\u0187\7h\2\2\u0187\u0188") + buf.write("\7n\2\2\u0188\u0189\7q\2\2\u0189\u018a\7c\2\2\u018a\u018b") + buf.write("\7v\2\2\u018bH\3\2\2\2\u018c\u018d\7d\2\2\u018d\u018e") + buf.write("\7q\2\2\u018e\u018f\7q\2\2\u018f\u0190\7n\2\2\u0190J\3") + buf.write("\2\2\2\u0191\u0192\7u\2\2\u0192\u0193\7v\2\2\u0193\u0194") + buf.write("\7t\2\2\u0194\u0195\7k\2\2\u0195\u0196\7p\2\2\u0196\u0197") + buf.write("\7i\2\2\u0197L\3\2\2\2\u0198\u0199\7g\2\2\u0199\u019a") + buf.write("\7x\2\2\u019a\u019b\7g\2\2\u019b\u019c\7p\2\2\u019c\u019d") + buf.write("\7v\2\2\u019dN\3\2\2\2\u019e\u019f\7k\2\2\u019f\u01a0") + buf.write("\7h\2\2\u01a0P\3\2\2\2\u01a1\u01a2\7B\2\2\u01a2R\3\2\2") + buf.write("\2\u01a3\u01a4\7c\2\2\u01a4\u01a5\7u\2\2\u01a5T\3\2\2") + buf.write("\2\u01a6\u01a7\7t\2\2\u01a7\u01a8\7k\2\2\u01a8\u01a9\7") + buf.write("u\2\2\u01a9\u01aa\7g\2\2\u01aaV\3\2\2\2\u01ab\u01ac\7") + buf.write("h\2\2\u01ac\u01ad\7c\2\2\u01ad\u01ae\7n\2\2\u01ae\u01af") + buf.write("\7n\2\2\u01afX\3\2\2\2\u01b0\u01b1\7g\2\2\u01b1\u01b2") + buf.write("\7n\2\2\u01b2\u01b3\7c\2\2\u01b3\u01b4\7r\2\2\u01b4\u01b5") + buf.write("\7u\2\2\u01b5\u01b6\7g\2\2\u01b6\u01b7\7f\2\2\u01b7Z\3") + buf.write("\2\2\2\u01b8\u01b9\7g\2\2\u01b9\u01ba\7x\2\2\u01ba\u01bb") + buf.write("\7g\2\2\u01bb\u01bc\7t\2\2\u01bc\u01bd\7{\2\2\u01bd\\") + buf.write("\3\2\2\2\u01be\u01bf\7x\2\2\u01bf\u01c0\7c\2\2\u01c0\u01c1") + buf.write("\7t\2\2\u01c1^\3\2\2\2\u01c2\u01c3\7u\2\2\u01c3\u01c4") + buf.write("\7c\2\2\u01c4\u01c5\7o\2\2\u01c5\u01c6\7r\2\2\u01c6\u01c7") + buf.write("\7n\2\2\u01c7\u01c8\7g\2\2\u01c8`\3\2\2\2\u01c9\u01ca") + buf.write("\7y\2\2\u01ca\u01cb\7k\2\2\u01cb\u01cc\7v\2\2\u01cc\u01cd") + buf.write("\7j\2\2\u01cdb\3\2\2\2\u01ce\u01cf\7m\2\2\u01cf\u01d0") + buf.write("\7g\2\2\u01d0\u01d1\7g\2\2\u01d1\u01d2\7r\2\2\u01d2d\3") + buf.write("\2\2\2\u01d3\u01d4\7f\2\2\u01d4\u01d5\7g\2\2\u01d5\u01d6") + buf.write("\7h\2\2\u01d6\u01d7\7c\2\2\u01d7\u01d8\7w\2\2\u01d8\u01d9") + buf.write("\7n\2\2\u01d9\u01da\7v\2\2\u01daf\3\2\2\2\u01db\u01dc") + buf.write("\7j\2\2\u01dc\u01dd\7c\2\2\u01dd\u01de\7t\2\2\u01de\u01df") + buf.write("\7f\2\2\u01dfh\3\2\2\2\u01e0\u01e1\7t\2\2\u01e1\u01e2") + buf.write("\7g\2\2\u01e2\u01e3\7o\2\2\u01e3\u01e4\7q\2\2\u01e4\u01e5") + buf.write("\7x\2\2\u01e5\u01e6\7g\2\2\u01e6\u01e7\7a\2\2\u01e7\u01e8") + buf.write("\7f\2\2\u01e8\u01e9\7g\2\2\u01e9\u01ea\7h\2\2\u01ea\u01eb") + buf.write("\7c\2\2\u01eb\u01ec\7w\2\2\u01ec\u01ed\7n\2\2\u01ed\u01ee") + buf.write("\7v\2\2\u01eej\3\2\2\2\u01ef\u01f0\7q\2\2\u01f0\u01f1") + buf.write("\7p\2\2\u01f1l\3\2\2\2\u01f2\u01f3\7f\2\2\u01f3\u01f4") + buf.write("\7q\2\2\u01f4n\3\2\2\2\u01f5\u01f6\7u\2\2\u01f6\u01f7") + buf.write("\7g\2\2\u01f7\u01f8\7t\2\2\u01f8\u01f9\7k\2\2\u01f9\u01fa") + buf.write("\7c\2\2\u01fa\u01fb\7n\2\2\u01fbp\3\2\2\2\u01fc\u01fd") + buf.write("\7q\2\2\u01fd\u01fe\7p\2\2\u01fe\u01ff\7g\2\2\u01ff\u0200") + buf.write("\7a\2\2\u0200\u0201\7q\2\2\u0201\u0202\7h\2\2\u0202r\3") + buf.write("\2\2\2\u0203\u0204\7r\2\2\u0204\u0205\7c\2\2\u0205\u0206") + buf.write("\7t\2\2\u0206\u0207\7c\2\2\u0207\u0208\7n\2\2\u0208\u0209") + buf.write("\7n\2\2\u0209\u020a\7g\2\2\u020a\u020b\7n\2\2\u020bt\3") + buf.write("\2\2\2\u020c\u020d\7y\2\2\u020d\u020e\7c\2\2\u020e\u020f") + buf.write("\7k\2\2\u020f\u0210\7v\2\2\u0210v\3\2\2\2\u0211\u0212") + buf.write("\7g\2\2\u0212\u0213\7o\2\2\u0213\u0214\7k\2\2\u0214\u0215") + buf.write("\7v\2\2\u0215x\3\2\2\2\u0216\u0217\7e\2\2\u0217\u0218") + buf.write("\7c\2\2\u0218\u0219\7n\2\2\u0219\u021a\7n\2\2\u021az\3") + buf.write("\2\2\2\u021b\u021c\7w\2\2\u021c\u021d\7p\2\2\u021d\u021e") + buf.write("\7v\2\2\u021e\u021f\7k\2\2\u021f\u0220\7n\2\2\u0220|\3") + buf.write("\2\2\2\u0221\u0222\7f\2\2\u0222\u0223\7g\2\2\u0223\u0224") + buf.write("\7h\2\2\u0224~\3\2\2\2\u0225\u0226\7/\2\2\u0226\u0227") + buf.write("\7@\2\2\u0227\u0080\3\2\2\2\u0228\u0229\7g\2\2\u0229\u022a") + buf.write("\7z\2\2\u022a\u022b\7r\2\2\u022b\u022c\7t\2\2\u022c\u022d") + buf.write("\7g\2\2\u022d\u022e\7u\2\2\u022e\u022f\7u\2\2\u022f\u0230") + buf.write("\7k\2\2\u0230\u0231\7q\2\2\u0231\u0232\7p\2\2\u0232\u0082") + buf.write("\3\2\2\2\u0233\u0234\7w\2\2\u0234\u0235\7p\2\2\u0235\u0236") + buf.write("\7f\2\2\u0236\u0237\7g\2\2\u0237\u0238\7h\2\2\u0238\u0239") + buf.write("\7k\2\2\u0239\u023a\7p\2\2\u023a\u023b\7g\2\2\u023b\u023c") + buf.write("\7f\2\2\u023c\u0084\3\2\2\2\u023d\u023e\7g\2\2\u023e\u023f") + buf.write("\7z\2\2\u023f\u0240\7v\2\2\u0240\u0241\7g\2\2\u0241\u0242") + buf.write("\7t\2\2\u0242\u0243\7p\2\2\u0243\u0244\7c\2\2\u0244\u0245") + buf.write("\7n\2\2\u0245\u0086\3\2\2\2\u0246\u0247\7q\2\2\u0247\u0248") + buf.write("\7p\2\2\u0248\u0249\7n\2\2\u0249\u024a\7{\2\2\u024a\u0088") + buf.write("\3\2\2\2\u024b\u024c\7e\2\2\u024c\u024d\7q\2\2\u024d\u024e") + buf.write("\7x\2\2\u024e\u024f\7g\2\2\u024f\u0250\7t\2\2\u0250\u008a") + buf.write("\3\2\2\2\u0251\u0252\7t\2\2\u0252\u0253\7g\2\2\u0253\u0254") + buf.write("\7e\2\2\u0254\u0255\7q\2\2\u0255\u0256\7t\2\2\u0256\u0257") + buf.write("\7f\2\2\u0257\u008c\3\2\2\2\u0258\u0259\7t\2\2\u0259\u025a") + buf.write("\7c\2\2\u025a\u025b\7p\2\2\u025b\u025c\7i\2\2\u025c\u025d") + buf.write("\7g\2\2\u025d\u008e\3\2\2\2\u025e\u025f\7A\2\2\u025f\u0090") + buf.write("\3\2\2\2\u0260\u0261\7?\2\2\u0261\u0262\7@\2\2\u0262\u0092") + buf.write("\3\2\2\2\u0263\u0264\7q\2\2\u0264\u0265\7t\2\2\u0265\u0094") + buf.write("\3\2\2\2\u0266\u0267\7c\2\2\u0267\u0268\7p\2\2\u0268\u0269") + buf.write("\7f\2\2\u0269\u0096\3\2\2\2\u026a\u026b\7p\2\2\u026b\u026c") + buf.write("\7q\2\2\u026c\u026d\7v\2\2\u026d\u0098\3\2\2\2\u026e\u026f") + buf.write("\7#\2\2\u026f\u0270\7?\2\2\u0270\u009a\3\2\2\2\u0271\u0272") + buf.write("\7>\2\2\u0272\u009c\3\2\2\2\u0273\u0274\7>\2\2\u0274\u0275") + buf.write("\7?\2\2\u0275\u009e\3\2\2\2\u0276\u0277\7@\2\2\u0277\u00a0") + buf.write("\3\2\2\2\u0278\u0279\7@\2\2\u0279\u027a\7?\2\2\u027a\u00a2") + buf.write("\3\2\2\2\u027b\u027c\7k\2\2\u027c\u027d\7p\2\2\u027d\u00a4") + buf.write("\3\2\2\2\u027e\u027f\7-\2\2\u027f\u00a6\3\2\2\2\u0280") + buf.write("\u0281\7/\2\2\u0281\u00a8\3\2\2\2\u0282\u0283\7,\2\2\u0283") + buf.write("\u00aa\3\2\2\2\u0284\u0285\7\61\2\2\u0285\u00ac\3\2\2") + buf.write("\2\u0286\u0287\7\'\2\2\u0287\u00ae\3\2\2\2\u0288\u0289") + buf.write("\7k\2\2\u0289\u028a\7v\2\2\u028a\u00b0\3\2\2\2\u028b\u028c") + buf.write("\7\60\2\2\u028c\u028d\7\60\2\2\u028d\u00b2\3\2\2\2\u028e") + buf.write("\u028f\6Z\2\2\u028f\u029b\5\u00bf`\2\u0290\u0292\7\17") + buf.write("\2\2\u0291\u0290\3\2\2\2\u0291\u0292\3\2\2\2\u0292\u0293") + buf.write("\3\2\2\2\u0293\u0296\7\f\2\2\u0294\u0296\4\16\17\2\u0295") + buf.write("\u0291\3\2\2\2\u0295\u0294\3\2\2\2\u0296\u0298\3\2\2\2") + buf.write("\u0297\u0299\5\u00bf`\2\u0298\u0297\3\2\2\2\u0298\u0299") + buf.write("\3\2\2\2\u0299\u029b\3\2\2\2\u029a\u028e\3\2\2\2\u029a") + buf.write("\u0295\3\2\2\2\u029b\u029c\3\2\2\2\u029c\u029d\bZ\2\2") + buf.write("\u029d\u00b4\3\2\2\2\u029e\u029f\7]\2\2\u029f\u02a0\b") + buf.write("[\3\2\u02a0\u00b6\3\2\2\2\u02a1\u02a2\7_\2\2\u02a2\u02a3") + buf.write("\b\\\4\2\u02a3\u00b8\3\2\2\2\u02a4\u02a5\7*\2\2\u02a5") + buf.write("\u02a6\b]\5\2\u02a6\u00ba\3\2\2\2\u02a7\u02a8\7+\2\2\u02a8") + buf.write("\u02a9\b^\6\2\u02a9\u00bc\3\2\2\2\u02aa\u02ad\5\u00bf") + buf.write("`\2\u02ab\u02ad\5\u00c1a\2\u02ac\u02aa\3\2\2\2\u02ac\u02ab") + buf.write("\3\2\2\2\u02ad\u02ae\3\2\2\2\u02ae\u02af\b_\7\2\u02af") + buf.write("\u00be\3\2\2\2\u02b0\u02b2\t\2\2\2\u02b1\u02b0\3\2\2\2") + buf.write("\u02b2\u02b3\3\2\2\2\u02b3\u02b1\3\2\2\2\u02b3\u02b4\3") + buf.write("\2\2\2\u02b4\u00c0\3\2\2\2\u02b5\u02b7\7^\2\2\u02b6\u02b8") + buf.write("\5\u00bf`\2\u02b7\u02b6\3\2\2\2\u02b7\u02b8\3\2\2\2\u02b8") + buf.write("\u02ba\3\2\2\2\u02b9\u02bb\7\17\2\2\u02ba\u02b9\3\2\2") + buf.write("\2\u02ba\u02bb\3\2\2\2\u02bb\u02bc\3\2\2\2\u02bc\u02bd") + buf.write("\7\f\2\2\u02bd\u00c2\3\2\2\2\u02be\u02c0\7\17\2\2\u02bf") + buf.write("\u02be\3\2\2\2\u02bf\u02c0\3\2\2\2\u02c0\u02c1\3\2\2\2") + buf.write("\u02c1\u02c2\7\f\2\2\u02c2\u00c4\3\2\2\2\u02c3\u02c4\7") + buf.write("\61\2\2\u02c4\u02c5\7,\2\2\u02c5\u02c9\3\2\2\2\u02c6\u02c8") + buf.write("\13\2\2\2\u02c7\u02c6\3\2\2\2\u02c8\u02cb\3\2\2\2\u02c9") + buf.write("\u02ca\3\2\2\2\u02c9\u02c7\3\2\2\2\u02ca\u02cc\3\2\2\2") + buf.write("\u02cb\u02c9\3\2\2\2\u02cc\u02cd\7,\2\2\u02cd\u02ce\7") + buf.write("\61\2\2\u02ce\u02cf\3\2\2\2\u02cf\u02d0\bc\7\2\u02d0\u00c6") + buf.write("\3\2\2\2\u02d1\u02d5\7%\2\2\u02d2\u02d4\n\3\2\2\u02d3") + buf.write("\u02d2\3\2\2\2\u02d4\u02d7\3\2\2\2\u02d5\u02d3\3\2\2\2") + buf.write("\u02d5\u02d6\3\2\2\2\u02d6\u02d8\3\2\2\2\u02d7\u02d5\3") + buf.write("\2\2\2\u02d8\u02d9\bd\7\2\u02d9\u00c8\3\2\2\2\u02da\u02dd") + buf.write("\5\u00cbf\2\u02db\u02dd\5\u00d1i\2\u02dc\u02da\3\2\2\2") + buf.write("\u02dc\u02db\3\2\2\2\u02dd\u00ca\3\2\2\2\u02de\u02e2\7") + buf.write("$\2\2\u02df\u02e1\5\u00cdg\2\u02e0\u02df\3\2\2\2\u02e1") + buf.write("\u02e4\3\2\2\2\u02e2\u02e0\3\2\2\2\u02e2\u02e3\3\2\2\2") + buf.write("\u02e3\u02e5\3\2\2\2\u02e4\u02e2\3\2\2\2\u02e5\u02ef\7") + buf.write("$\2\2\u02e6\u02ea\7)\2\2\u02e7\u02e9\5\u00cdg\2\u02e8") + buf.write("\u02e7\3\2\2\2\u02e9\u02ec\3\2\2\2\u02ea\u02e8\3\2\2\2") + buf.write("\u02ea\u02eb\3\2\2\2\u02eb\u02ed\3\2\2\2\u02ec\u02ea\3") + buf.write("\2\2\2\u02ed\u02ef\7)\2\2\u02ee\u02de\3\2\2\2\u02ee\u02e6") + buf.write("\3\2\2\2\u02ef\u00cc\3\2\2\2\u02f0\u02f3\5\u00cfh\2\u02f1") + buf.write("\u02f3\5\u00d7l\2\u02f2\u02f0\3\2\2\2\u02f2\u02f1\3\2") + buf.write("\2\2\u02f3\u00ce\3\2\2\2\u02f4\u02f5\n\4\2\2\u02f5\u00d0") + buf.write("\3\2\2\2\u02f6\u02f7\7$\2\2\u02f7\u02f8\7$\2\2\u02f8\u02f9") + buf.write("\7$\2\2\u02f9\u02fd\3\2\2\2\u02fa\u02fc\5\u00d3j\2\u02fb") + buf.write("\u02fa\3\2\2\2\u02fc\u02ff\3\2\2\2\u02fd\u02fb\3\2\2\2") + buf.write("\u02fd\u02fe\3\2\2\2\u02fe\u0300\3\2\2\2\u02ff\u02fd\3") + buf.write("\2\2\2\u0300\u0301\7$\2\2\u0301\u0302\7$\2\2\u0302\u0311") + buf.write("\7$\2\2\u0303\u0304\7)\2\2\u0304\u0305\7)\2\2\u0305\u0306") + buf.write("\7)\2\2\u0306\u030a\3\2\2\2\u0307\u0309\5\u00d3j\2\u0308") + buf.write("\u0307\3\2\2\2\u0309\u030c\3\2\2\2\u030a\u0308\3\2\2\2") + buf.write("\u030a\u030b\3\2\2\2\u030b\u030d\3\2\2\2\u030c\u030a\3") + buf.write("\2\2\2\u030d\u030e\7)\2\2\u030e\u030f\7)\2\2\u030f\u0311") + buf.write("\7)\2\2\u0310\u02f6\3\2\2\2\u0310\u0303\3\2\2\2\u0311") + buf.write("\u00d2\3\2\2\2\u0312\u0315\5\u00d5k\2\u0313\u0315\5\u00d7") + buf.write("l\2\u0314\u0312\3\2\2\2\u0314\u0313\3\2\2\2\u0315\u00d4") + buf.write("\3\2\2\2\u0316\u0317\n\5\2\2\u0317\u00d6\3\2\2\2\u0318") + buf.write("\u0319\7^\2\2\u0319\u031d\13\2\2\2\u031a\u031b\7^\2\2") + buf.write("\u031b\u031d\5\u00c3b\2\u031c\u0318\3\2\2\2\u031c\u031a") + buf.write("\3\2\2\2\u031d\u00d8\3\2\2\2\u031e\u0320\t\6\2\2\u031f") + buf.write("\u031e\3\2\2\2\u031f\u0320\3\2\2\2\u0320\u0324\3\2\2\2") + buf.write("\u0321\u0323\5\u00e7t\2\u0322\u0321\3\2\2\2\u0323\u0326") + buf.write("\3\2\2\2\u0324\u0322\3\2\2\2\u0324\u0325\3\2\2\2\u0325") + buf.write("\u0327\3\2\2\2\u0326\u0324\3\2\2\2\u0327\u0329\7\60\2") + buf.write("\2\u0328\u032a\5\u00e7t\2\u0329\u0328\3\2\2\2\u032a\u032b") + buf.write("\3\2\2\2\u032b\u0329\3\2\2\2\u032b\u032c\3\2\2\2\u032c") + buf.write("\u0336\3\2\2\2\u032d\u032f\t\7\2\2\u032e\u0330\t\6\2\2") + buf.write("\u032f\u032e\3\2\2\2\u032f\u0330\3\2\2\2\u0330\u0332\3") + buf.write("\2\2\2\u0331\u0333\5\u00e7t\2\u0332\u0331\3\2\2\2\u0333") + buf.write("\u0334\3\2\2\2\u0334\u0332\3\2\2\2\u0334\u0335\3\2\2\2") + buf.write("\u0335\u0337\3\2\2\2\u0336\u032d\3\2\2\2\u0336\u0337\3") + buf.write("\2\2\2\u0337\u00da\3\2\2\2\u0338\u033a\5\u00e7t\2\u0339") + buf.write("\u0338\3\2\2\2\u033a\u033b\3\2\2\2\u033b\u0339\3\2\2\2") + buf.write("\u033b\u033c\3\2\2\2\u033c\u00dc\3\2\2\2\u033d\u033e\7") + buf.write("\62\2\2\u033e\u033f\7z\2\2\u033f\u0341\3\2\2\2\u0340\u0342") + buf.write("\5\u00e9u\2\u0341\u0340\3\2\2\2\u0342\u0343\3\2\2\2\u0343") + buf.write("\u0341\3\2\2\2\u0343\u0344\3\2\2\2\u0344\u00de\3\2\2\2") + buf.write("\u0345\u0347\7/\2\2\u0346\u0348\5\u00e7t\2\u0347\u0346") + buf.write("\3\2\2\2\u0348\u0349\3\2\2\2\u0349\u0347\3\2\2\2\u0349") + buf.write("\u034a\3\2\2\2\u034a\u00e0\3\2\2\2\u034b\u034c\7v\2\2") + buf.write("\u034c\u034d\7t\2\2\u034d\u034e\7w\2\2\u034e\u0355\7g") + buf.write("\2\2\u034f\u0350\7h\2\2\u0350\u0351\7c\2\2\u0351\u0352") + buf.write("\7n\2\2\u0352\u0353\7u\2\2\u0353\u0355\7g\2\2\u0354\u034b") + buf.write("\3\2\2\2\u0354\u034f\3\2\2\2\u0355\u00e2\3\2\2\2\u0356") + buf.write("\u035a\t\b\2\2\u0357\u0359\t\t\2\2\u0358\u0357\3\2\2\2") + buf.write("\u0359\u035c\3\2\2\2\u035a\u0358\3\2\2\2\u035a\u035b\3") + buf.write("\2\2\2\u035b\u0365\3\2\2\2\u035c\u035a\3\2\2\2\u035d\u035f") + buf.write("\7~\2\2\u035e\u0360\n\n\2\2\u035f\u035e\3\2\2\2\u0360") + buf.write("\u0361\3\2\2\2\u0361\u035f\3\2\2\2\u0361\u0362\3\2\2\2") + buf.write("\u0362\u0363\3\2\2\2\u0363\u0365\7~\2\2\u0364\u0356\3") + buf.write("\2\2\2\u0364\u035d\3\2\2\2\u0365\u00e4\3\2\2\2\u0366\u0367") + buf.write("\n\n\2\2\u0367\u00e6\3\2\2\2\u0368\u0369\t\13\2\2\u0369") + buf.write("\u00e8\3\2\2\2\u036a\u036b\t\f\2\2\u036b\u00ea\3\2\2\2") + buf.write("%\2\u0291\u0295\u0298\u029a\u02ac\u02b3\u02b7\u02ba\u02bf") + buf.write("\u02c9\u02d5\u02dc\u02e2\u02ea\u02ee\u02f2\u02fd\u030a") + buf.write("\u0310\u0314\u031c\u031f\u0324\u032b\u032f\u0334\u0336") + buf.write("\u033b\u0343\u0349\u0354\u035a\u0361\u0364\b\3Z\2\3[\3") + buf.write("\3\\\4\3]\5\3^\6\b\2\2") + return buf.getvalue() + + +class OpenSCENARIO2Lexer(Lexer): + + atn = ATNDeserializer().deserialize(serializedATN()) + + decisionsToDFA = [DFA(ds, i) for i, ds in enumerate(atn.decisionToState)] + + T__0 = 1 + T__1 = 2 + T__2 = 3 + T__3 = 4 + T__4 = 5 + T__5 = 6 + T__6 = 7 + T__7 = 8 + T__8 = 9 + T__9 = 10 + T__10 = 11 + T__11 = 12 + T__12 = 13 + T__13 = 14 + T__14 = 15 + T__15 = 16 + T__16 = 17 + T__17 = 18 + T__18 = 19 + T__19 = 20 + T__20 = 21 + T__21 = 22 + T__22 = 23 + T__23 = 24 + T__24 = 25 + T__25 = 26 + T__26 = 27 + T__27 = 28 + T__28 = 29 + T__29 = 30 + T__30 = 31 + T__31 = 32 + T__32 = 33 + T__33 = 34 + T__34 = 35 + T__35 = 36 + T__36 = 37 + T__37 = 38 + T__38 = 39 + T__39 = 40 + T__40 = 41 + T__41 = 42 + T__42 = 43 + T__43 = 44 + T__44 = 45 + T__45 = 46 + T__46 = 47 + T__47 = 48 + T__48 = 49 + T__49 = 50 + T__50 = 51 + T__51 = 52 + T__52 = 53 + T__53 = 54 + T__54 = 55 + T__55 = 56 + T__56 = 57 + T__57 = 58 + T__58 = 59 + T__59 = 60 + T__60 = 61 + T__61 = 62 + T__62 = 63 + T__63 = 64 + T__64 = 65 + T__65 = 66 + T__66 = 67 + T__67 = 68 + T__68 = 69 + T__69 = 70 + T__70 = 71 + T__71 = 72 + T__72 = 73 + T__73 = 74 + T__74 = 75 + T__75 = 76 + T__76 = 77 + T__77 = 78 + T__78 = 79 + T__79 = 80 + T__80 = 81 + T__81 = 82 + T__82 = 83 + T__83 = 84 + T__84 = 85 + T__85 = 86 + T__86 = 87 + T__87 = 88 + NEWLINE = 89 + OPEN_BRACK = 90 + CLOSE_BRACK = 91 + OPEN_PAREN = 92 + CLOSE_PAREN = 93 + SKIP_ = 94 + BLOCK_COMMENT = 95 + LINE_COMMENT = 96 + StringLiteral = 97 + FloatLiteral = 98 + UintLiteral = 99 + HexUintLiteral = 100 + IntLiteral = 101 + BoolLiteral = 102 + Identifier = 103 + + channelNames = [u"DEFAULT_TOKEN_CHANNEL", u"HIDDEN"] + + modeNames = ["DEFAULT_MODE"] + + literalNames = ["", + "'import'", "'.'", "'type'", "'is'", "'SI'", "'unit'", "'of'", + "','", "':'", "'factor'", "'offset'", "'kg'", "'m'", "'s'", + "'A'", "'K'", "'mol'", "'cd'", "'rad'", "'enum'", "'='", "'!'", + "'=='", "'struct'", "'inherits'", "'actor'", "'scenario'", "'action'", + "'modifier'", "'extend'", "'global'", "'list'", "'int'", "'uint'", + "'float'", "'bool'", "'string'", "'event'", "'if'", "'@'", "'as'", + "'rise'", "'fall'", "'elapsed'", "'every'", "'var'", "'sample'", + "'with'", "'keep'", "'default'", "'hard'", "'remove_default'", + "'on'", "'do'", "'serial'", "'one_of'", "'parallel'", "'wait'", + "'emit'", "'call'", "'until'", "'def'", "'->'", "'expression'", + "'undefined'", "'external'", "'only'", "'cover'", "'record'", + "'range'", "'?'", "'=>'", "'or'", "'and'", "'not'", "'!='", + "'<'", "'<='", "'>'", "'>='", "'in'", "'+'", "'-'", "'*'", "'/'", + "'%'", "'it'", "'..'", "'['", "']'", "'('", "')'"] + + symbolicNames = ["", + "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", "OPEN_PAREN", "CLOSE_PAREN", + "SKIP_", "BLOCK_COMMENT", "LINE_COMMENT", "StringLiteral", "FloatLiteral", + "UintLiteral", "HexUintLiteral", "IntLiteral", "BoolLiteral", + "Identifier"] + + ruleNames = ["T__0", "T__1", "T__2", "T__3", "T__4", "T__5", "T__6", + "T__7", "T__8", "T__9", "T__10", "T__11", "T__12", "T__13", + "T__14", "T__15", "T__16", "T__17", "T__18", "T__19", + "T__20", "T__21", "T__22", "T__23", "T__24", "T__25", + "T__26", "T__27", "T__28", "T__29", "T__30", "T__31", + "T__32", "T__33", "T__34", "T__35", "T__36", "T__37", + "T__38", "T__39", "T__40", "T__41", "T__42", "T__43", + "T__44", "T__45", "T__46", "T__47", "T__48", "T__49", + "T__50", "T__51", "T__52", "T__53", "T__54", "T__55", + "T__56", "T__57", "T__58", "T__59", "T__60", "T__61", + "T__62", "T__63", "T__64", "T__65", "T__66", "T__67", + "T__68", "T__69", "T__70", "T__71", "T__72", "T__73", + "T__74", "T__75", "T__76", "T__77", "T__78", "T__79", + "T__80", "T__81", "T__82", "T__83", "T__84", "T__85", + "T__86", "T__87", "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", + "OPEN_PAREN", "CLOSE_PAREN", "SKIP_", "SPACES", "LINE_JOINING", + "RN", "BLOCK_COMMENT", "LINE_COMMENT", "StringLiteral", + "Shortstring", "ShortstringElem", "ShortstringChar", "Longstring", + "LongstringElem", "LongstringChar", "StringEscapeSeq", + "FloatLiteral", "UintLiteral", "HexUintLiteral", "IntLiteral", + "BoolLiteral", "Identifier", "NonVerticalLineChar", "Digit", + "HexDigit"] + + grammarFileName = "OpenSCENARIO2.g4" + + def __init__(self, input=None, output: TextIO = sys.stdout): + super().__init__(input, output) + self.checkVersion("4.7.2") + self._interp = LexerATNSimulator(self, self.atn, self.decisionsToDFA, PredictionContextCache()) + self._actions = None + self._predicates = None + + @property + def tokens(self): + try: + return self._tokens + except AttributeError: + self._tokens = [] + return self._tokens + + @property + def indents(self): + try: + return self._indents + except AttributeError: + self._indents = [] + return self._indents + + @property + def opened(self): + try: + return self._opened + except AttributeError: + self._opened = 0 + return self._opened + + @opened.setter + def opened(self, value): + self._opened = value + + @property + def lastToken(self): + try: + return self._lastToken + except AttributeError: + self._lastToken = None + return self._lastToken + + @lastToken.setter + def lastToken(self, value): + self._lastToken = value + + def reset(self): + super().reset() + self.tokens = [] + self.indents = [] + self.opened = 0 + self.lastToken = None + + def emitToken(self, t): + super().emitToken(t) + self.tokens.append(t) + + def nextToken(self): + if self._input.LA(1) == Token.EOF and self.indents: + for i in range(len(self.tokens)-1, -1, -1): + if self.tokens[i].type == Token.EOF: + self.tokens.pop(i) + self.emitToken(self.commonToken(LanguageParser.NEWLINE, '\n')) + while self.indents: + self.emitToken(self.createDedent()) + self.indents.pop() + self.emitToken(self.commonToken(LanguageParser.EOF, "")) + next = super().nextToken() + if next.channel == Token.DEFAULT_CHANNEL: + self.lastToken = next + return next if not self.tokens else self.tokens.pop(0) + + def createDedent(self): + dedent = self.commonToken(LanguageParser.DEDENT, "") + dedent.line = self.lastToken.line + return dedent + + def commonToken(self, type, text, indent=0): + stop = self.getCharIndex()-1-indent + start = (stop - len(text) + 1) if text else stop + return CommonToken(self._tokenFactorySourcePair, type, super().DEFAULT_TOKEN_CHANNEL, start, stop) + + @staticmethod + def getIndentationCount(spaces): + count = 0 + for ch in spaces: + if ch == '\t': + count += 8 - (count % 8) + else: + count += 1 + return count + + def atStartOfInput(self): + return Lexer.column.fget(self) == 0 and Lexer.line.fget(self) == 1 + + def action(self, localctx: RuleContext, ruleIndex: int, actionIndex: int): + if self._actions is None: + actions = dict() + actions[88] = self.NEWLINE_action + actions[89] = self.OPEN_BRACK_action + actions[90] = self.CLOSE_BRACK_action + actions[91] = self.OPEN_PAREN_action + actions[92] = self.CLOSE_PAREN_action + self._actions = actions + action = self._actions.get(ruleIndex, None) + if action is not None: + action(localctx, actionIndex) + else: + raise Exception("No registered action for:" + str(ruleIndex)) + + def NEWLINE_action(self, localctx: RuleContext, actionIndex: int): + if actionIndex == 0: + + tempt = Lexer.text.fget(self) + newLine = re.sub("[^\r\n\f]+", "", tempt) + spaces = re.sub("[\r\n\f]+", "", tempt) + la_char = "" + try: + la = self._input.LA(1) + la_char = chr(la) # Python does not compare char to ints directly + except ValueError: # End of file + pass + # Strip newlines inside open clauses except if we are near EOF. We keep NEWLINEs near EOF to + # satisfy the final newline needed by the single_put rule used by the REPL. + try: + nextnext_la = self._input.LA(2) + nextnext_la_char = chr(nextnext_la) + except ValueError: + nextnext_eof = True + else: + nextnext_eof = False + if self.opened > 0 or nextnext_eof is False and (la_char == '\r' or la_char == '\n' or la_char == '\f' or la_char == '#'): + self.skip() + else: + indent = self.getIndentationCount(spaces) + previous = self.indents[-1] if self.indents else 0 + self.emitToken(self.commonToken(self.NEWLINE, newLine, indent=indent)) # NEWLINE is actually the '\n' char + if indent == previous: + self.skip() + elif indent > previous: + self.indents.append(indent) + self.emitToken(self.commonToken(LanguageParser.INDENT, spaces)) + else: + while self.indents and self.indents[-1] > indent: + self.emitToken(self.createDedent()) + self.indents.pop() + + def OPEN_BRACK_action(self, localctx: RuleContext, actionIndex: int): + if actionIndex == 1: + self.opened += 1 + + def CLOSE_BRACK_action(self, localctx: RuleContext, actionIndex: int): + if actionIndex == 2: + self.opened -= 1 + + def OPEN_PAREN_action(self, localctx: RuleContext, actionIndex: int): + if actionIndex == 3: + self.opened += 1 + + def CLOSE_PAREN_action(self, localctx: RuleContext, actionIndex: int): + if actionIndex == 4: + self.opened -= 1 + + def sempred(self, localctx: RuleContext, ruleIndex: int, predIndex: int): + if self._predicates is None: + preds = dict() + preds[88] = self.NEWLINE_sempred + self._predicates = preds + pred = self._predicates.get(ruleIndex, None) + if pred is not None: + return pred(localctx, predIndex) + else: + raise Exception("No registered predicate for:" + str(ruleIndex)) + + def NEWLINE_sempred(self, localctx: RuleContext, predIndex: int): + if predIndex == 0: + return self.atStartOfInput() diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.tokens b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.tokens new file mode 100644 index 00000000..402155cd --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Lexer.tokens @@ -0,0 +1,195 @@ +T__0=1 +T__1=2 +T__2=3 +T__3=4 +T__4=5 +T__5=6 +T__6=7 +T__7=8 +T__8=9 +T__9=10 +T__10=11 +T__11=12 +T__12=13 +T__13=14 +T__14=15 +T__15=16 +T__16=17 +T__17=18 +T__18=19 +T__19=20 +T__20=21 +T__21=22 +T__22=23 +T__23=24 +T__24=25 +T__25=26 +T__26=27 +T__27=28 +T__28=29 +T__29=30 +T__30=31 +T__31=32 +T__32=33 +T__33=34 +T__34=35 +T__35=36 +T__36=37 +T__37=38 +T__38=39 +T__39=40 +T__40=41 +T__41=42 +T__42=43 +T__43=44 +T__44=45 +T__45=46 +T__46=47 +T__47=48 +T__48=49 +T__49=50 +T__50=51 +T__51=52 +T__52=53 +T__53=54 +T__54=55 +T__55=56 +T__56=57 +T__57=58 +T__58=59 +T__59=60 +T__60=61 +T__61=62 +T__62=63 +T__63=64 +T__64=65 +T__65=66 +T__66=67 +T__67=68 +T__68=69 +T__69=70 +T__70=71 +T__71=72 +T__72=73 +T__73=74 +T__74=75 +T__75=76 +T__76=77 +T__77=78 +T__78=79 +T__79=80 +T__80=81 +T__81=82 +T__82=83 +T__83=84 +T__84=85 +T__85=86 +T__86=87 +T__87=88 +NEWLINE=89 +OPEN_BRACK=90 +CLOSE_BRACK=91 +OPEN_PAREN=92 +CLOSE_PAREN=93 +SKIP_=94 +BLOCK_COMMENT=95 +LINE_COMMENT=96 +StringLiteral=97 +FloatLiteral=98 +UintLiteral=99 +HexUintLiteral=100 +IntLiteral=101 +BoolLiteral=102 +Identifier=103 +'import'=1 +'.'=2 +'type'=3 +'is'=4 +'SI'=5 +'unit'=6 +'of'=7 +','=8 +':'=9 +'factor'=10 +'offset'=11 +'kg'=12 +'m'=13 +'s'=14 +'A'=15 +'K'=16 +'mol'=17 +'cd'=18 +'rad'=19 +'enum'=20 +'='=21 +'!'=22 +'=='=23 +'struct'=24 +'inherits'=25 +'actor'=26 +'scenario'=27 +'action'=28 +'modifier'=29 +'extend'=30 +'global'=31 +'list'=32 +'int'=33 +'uint'=34 +'float'=35 +'bool'=36 +'string'=37 +'event'=38 +'if'=39 +'@'=40 +'as'=41 +'rise'=42 +'fall'=43 +'elapsed'=44 +'every'=45 +'var'=46 +'sample'=47 +'with'=48 +'keep'=49 +'default'=50 +'hard'=51 +'remove_default'=52 +'on'=53 +'do'=54 +'serial'=55 +'one_of'=56 +'parallel'=57 +'wait'=58 +'emit'=59 +'call'=60 +'until'=61 +'def'=62 +'->'=63 +'expression'=64 +'undefined'=65 +'external'=66 +'only'=67 +'cover'=68 +'record'=69 +'range'=70 +'?'=71 +'=>'=72 +'or'=73 +'and'=74 +'not'=75 +'!='=76 +'<'=77 +'<='=78 +'>'=79 +'>='=80 +'in'=81 +'+'=82 +'-'=83 +'*'=84 +'/'=85 +'%'=86 +'it'=87 +'..'=88 +'['=90 +']'=91 +'('=92 +')'=93 diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Listener.py b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Listener.py new file mode 100644 index 00000000..30e9d44b --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Listener.py @@ -0,0 +1,1251 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +# Generated from OpenSCENARIO2.g4 by ANTLR 4.7.2 +from antlr4 import * +if __name__ is not None and "." in __name__: + from .OpenSCENARIO2Parser import OpenSCENARIO2Parser +else: + from OpenSCENARIO2Parser import OpenSCENARIO2Parser + +# This class defines a complete listener for a parse tree produced by OpenSCENARIO2Parser. + + +class OpenSCENARIO2Listener(ParseTreeListener): + + # Enter a parse tree produced by OpenSCENARIO2Parser#osc_file. + def enterOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#osc_file. + def exitOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#preludeStatement. + def enterPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#preludeStatement. + def exitPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#importStatement. + def enterImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#importStatement. + def exitImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#importReference. + def enterImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#importReference. + def exitImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. + def enterStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. + def exitStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. + def enterOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. + def exitOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. + def enterPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. + def exitPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. + def enterPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. + def exitPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. + def enterBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. + def exitBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. + def enterSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. + def exitSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. + def enterUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. + def exitUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. + def enterUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. + def exitUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#unitName. + def enterUnitName(self, ctx: OpenSCENARIO2Parser.UnitNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#unitName. + def exitUnitName(self, ctx: OpenSCENARIO2Parser.UnitNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#siBaseExponentList. + def enterSiBaseExponentList(self, ctx: OpenSCENARIO2Parser.SiBaseExponentListContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#siBaseExponentList. + def exitSiBaseExponentList(self, ctx: OpenSCENARIO2Parser.SiBaseExponentListContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#siBaseExponent. + def enterSiBaseExponent(self, ctx: OpenSCENARIO2Parser.SiBaseExponentContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#siBaseExponent. + def exitSiBaseExponent(self, ctx: OpenSCENARIO2Parser.SiBaseExponentContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#siUnitSpecifier. + def enterSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#siUnitSpecifier. + def exitSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#siFactor. + def enterSiFactor(self, ctx: OpenSCENARIO2Parser.SiFactorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#siFactor. + def exitSiFactor(self, ctx: OpenSCENARIO2Parser.SiFactorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#siOffset. + def enterSiOffset(self, ctx: OpenSCENARIO2Parser.SiOffsetContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#siOffset. + def exitSiOffset(self, ctx: OpenSCENARIO2Parser.SiOffsetContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#siBaseUnitName. + def enterSiBaseUnitName(self, ctx: OpenSCENARIO2Parser.SiBaseUnitNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#siBaseUnitName. + def exitSiBaseUnitName(self, ctx: OpenSCENARIO2Parser.SiBaseUnitNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. + def enterEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. + def exitEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. + def enterEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. + def exitEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. + def enterEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. + def exitEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumName. + def enterEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumName. + def exitEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumMemberName. + def enterEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumMemberName. + def exitEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumValueReference. + def enterEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumValueReference. + def exitEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. + def enterInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. + def exitInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structDeclaration. + def enterStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structDeclaration. + def exitStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structInherits. + def enterStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structInherits. + def exitStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. + def enterStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. + def exitStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldName. + def enterFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldName. + def exitFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structName. + def enterStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structName. + def exitStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. + def enterActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. + def exitActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorInherits. + def enterActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorInherits. + def exitActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. + def enterActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. + def exitActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorName. + def enterActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorName. + def exitActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. + def enterScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. + def exitScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. + def enterScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. + def exitScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. + def enterScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. + def exitScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. + def enterQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. + def exitQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorName. + def enterBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorName. + def exitBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. + def enterActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. + def exitActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actionInherits. + def enterActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actionInherits. + def exitActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. + def enterModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. + def exitModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#modifierName. + def enterModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#modifierName. + def exitModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeExtension. + def enterTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeExtension. + def exitTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. + def enterEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. + def exitEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. + def enterStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. + def exitStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. + def enterExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. + def exitExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. + def enterExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. + def exitExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. + def enterGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. + def exitGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. + def enterTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. + def exitTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. + def enterNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. + def exitNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. + def enterAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. + def exitAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. + def enterListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. + def exitListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#primitiveType. + def enterPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#primitiveType. + def exitPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeName. + def enterTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeName. + def exitTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. + def enterEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. + def exitEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventSpecification. + def enterEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventSpecification. + def exitEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventReference. + def enterEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventReference. + def exitEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. + def enterEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. + def exitEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventFieldName. + def enterEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventFieldName. + def exitEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventName. + def enterEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventName. + def exitEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventPath. + def enterEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventPath. + def exitEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#eventCondition. + def enterEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#eventCondition. + def exitEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#riseExpression. + def enterRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#riseExpression. + def exitRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fallExpression. + def enterFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fallExpression. + def exitFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. + def enterElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. + def exitElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#everyExpression. + def enterEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#everyExpression. + def exitEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#boolExpression. + def enterBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#boolExpression. + def exitBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#durationExpression. + def enterDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#durationExpression. + def exitDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. + def enterFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. + def exitFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. + def enterParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. + def exitParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. + def enterVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. + def exitVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#sampleExpression. + def enterSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#sampleExpression. + def exitSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#defaultValue. + def enterDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#defaultValue. + def exitDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. + def enterParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. + def exitParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. + def enterParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. + def exitParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. + def enterConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. + def exitConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. + def enterKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. + def exitKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. + def enterConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. + def exitConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#constraintExpression. + def enterConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#constraintExpression. + def exitConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. + def enterRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. + def exitRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#parameterReference. + def enterParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#parameterReference. + def exitParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. + def enterModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. + def exitModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. + def enterBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. + def exitBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. + def enterBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. + def exitBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#onDirective. + def enterOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#onDirective. + def exitOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#onMember. + def enterOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#onMember. + def exitOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#doDirective. + def enterDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#doDirective. + def exitDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#doMember. + def enterDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#doMember. + def exitDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#composition. + def enterComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#composition. + def exitComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#compositionOperator. + def enterCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#compositionOperator. + def exitCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. + def enterBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. + def exitBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. + def enterBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. + def exitBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. + def enterBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. + def exitBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#labelName. + def enterLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#labelName. + def exitLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#actorExpression. + def enterActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#actorExpression. + def exitActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#waitDirective. + def enterWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#waitDirective. + def exitWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#emitDirective. + def enterEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#emitDirective. + def exitEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#callDirective. + def enterCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#callDirective. + def exitCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#untilDirective. + def enterUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#untilDirective. + def exitUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodInvocation. + def enterMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodInvocation. + def exitMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. + def enterMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. + def exitMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#returnType. + def enterReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#returnType. + def exitReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodImplementation. + def enterMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodImplementation. + def exitMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodQualifier. + def enterMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodQualifier. + def exitMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#methodName. + def enterMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#methodName. + def exitMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. + def enterCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. + def exitCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. + def enterCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. + def exitCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. + def enterRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. + def exitRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageExpression. + def enterCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageExpression. + def exitCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageUnit. + def enterCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageUnit. + def exitCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageRange. + def enterCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageRange. + def exitCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageEvery. + def enterCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageEvery. + def exitCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageEvent. + def enterCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageEvent. + def exitCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. + def enterCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. + def exitCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#targetName. + def enterTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#targetName. + def exitTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#expression. + def enterExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#expression. + def exitExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. + def enterTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. + def exitTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#implication. + def enterImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#implication. + def exitImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#disjunction. + def enterDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#disjunction. + def exitDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#conjunction. + def enterConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#conjunction. + def exitConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#inversion. + def enterInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#inversion. + def exitInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#relationExp. + def enterRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#relationExp. + def exitRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#sumExp. + def enterSumExp(self, ctx: OpenSCENARIO2Parser.SumExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#sumExp. + def exitSumExp(self, ctx: OpenSCENARIO2Parser.SumExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#relationalOp. + def enterRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#relationalOp. + def exitRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#termExp. + def enterTermExp(self, ctx: OpenSCENARIO2Parser.TermExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#termExp. + def exitTermExp(self, ctx: OpenSCENARIO2Parser.TermExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#additiveExp. + def enterAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#additiveExp. + def exitAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#additiveOp. + def enterAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#additiveOp. + def exitAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. + def enterMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. + def exitMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#factorExp. + def enterFactorExp(self, ctx: OpenSCENARIO2Parser.FactorExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#factorExp. + def exitFactorExp(self, ctx: OpenSCENARIO2Parser.FactorExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. + def enterMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. + def exitMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#factor. + def enterFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#factor. + def exitFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#primaryExpression. + def enterPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#primaryExpression. + def exitPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#castExpression. + def enterCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#castExpression. + def exitCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. + def enterFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. + def exitFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. + def enterFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. + def exitFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. + def enterElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. + def exitElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. + def enterTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. + def exitTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#fieldAccess. + def enterFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#fieldAccess. + def exitFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#primaryExp. + def enterPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#primaryExp. + def exitPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#valueExp. + def enterValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#valueExp. + def exitValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#listConstructor. + def enterListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#listConstructor. + def exitListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. + def enterRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. + def exitRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#identifierReference. + def enterIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#identifierReference. + def exitIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. + def enterArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. + def exitArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. + def enterArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. + def exitArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentName. + def enterArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentName. + def exitArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#argumentList. + def enterArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#argumentList. + def exitArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#positionalArgument. + def enterPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#positionalArgument. + def exitPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#namedArgument. + def enterNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#namedArgument. + def exitNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. + def enterPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. + def exitPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): + pass + + # Enter a parse tree produced by OpenSCENARIO2Parser#integerLiteral. + def enterIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): + pass + + # Exit a parse tree produced by OpenSCENARIO2Parser#integerLiteral. + def exitIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): + pass diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Parser.py b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Parser.py new file mode 100644 index 00000000..cbc0ce45 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Parser.py @@ -0,0 +1,10461 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +# Generated from OpenSCENARIO2.g4 by ANTLR 4.7.2 +# encoding: utf-8 +from antlr4 import * +from io import StringIO +from typing.io import TextIO +import sys + + +def serializedATN(): + with StringIO() as buf: + buf.write("\3\u608b\ua72a\u8133\ub9ed\u417c\u3be7\u7786\u5964\3k") + buf.write("\u0531\4\2\t\2\4\3\t\3\4\4\t\4\4\5\t\5\4\6\t\6\4\7\t\7") + buf.write("\4\b\t\b\4\t\t\t\4\n\t\n\4\13\t\13\4\f\t\f\4\r\t\r\4\16") + buf.write("\t\16\4\17\t\17\4\20\t\20\4\21\t\21\4\22\t\22\4\23\t\23") + buf.write("\4\24\t\24\4\25\t\25\4\26\t\26\4\27\t\27\4\30\t\30\4\31") + buf.write("\t\31\4\32\t\32\4\33\t\33\4\34\t\34\4\35\t\35\4\36\t\36") + buf.write("\4\37\t\37\4 \t \4!\t!\4\"\t\"\4#\t#\4$\t$\4%\t%\4&\t") + buf.write("&\4\'\t\'\4(\t(\4)\t)\4*\t*\4+\t+\4,\t,\4-\t-\4.\t.\4") + buf.write("/\t/\4\60\t\60\4\61\t\61\4\62\t\62\4\63\t\63\4\64\t\64") + buf.write("\4\65\t\65\4\66\t\66\4\67\t\67\48\t8\49\t9\4:\t:\4;\t") + buf.write(";\4<\t<\4=\t=\4>\t>\4?\t?\4@\t@\4A\tA\4B\tB\4C\tC\4D\t") + buf.write("D\4E\tE\4F\tF\4G\tG\4H\tH\4I\tI\4J\tJ\4K\tK\4L\tL\4M\t") + buf.write("M\4N\tN\4O\tO\4P\tP\4Q\tQ\4R\tR\4S\tS\4T\tT\4U\tU\4V\t") + buf.write("V\4W\tW\4X\tX\4Y\tY\4Z\tZ\4[\t[\4\\\t\\\4]\t]\4^\t^\4") + buf.write("_\t_\4`\t`\4a\ta\4b\tb\4c\tc\4d\td\4e\te\4f\tf\4g\tg\4") + buf.write("h\th\4i\ti\4j\tj\4k\tk\4l\tl\4m\tm\4n\tn\4o\to\4p\tp\4") + buf.write("q\tq\4r\tr\4s\ts\4t\tt\4u\tu\4v\tv\4w\tw\4x\tx\4y\ty\4") + buf.write("z\tz\4{\t{\4|\t|\4}\t}\4~\t~\4\177\t\177\4\u0080\t\u0080") + buf.write("\4\u0081\t\u0081\4\u0082\t\u0082\4\u0083\t\u0083\4\u0084") + buf.write("\t\u0084\4\u0085\t\u0085\4\u0086\t\u0086\4\u0087\t\u0087") + buf.write("\4\u0088\t\u0088\4\u0089\t\u0089\4\u008a\t\u008a\4\u008b") + buf.write("\t\u008b\4\u008c\t\u008c\4\u008d\t\u008d\3\2\7\2\u011c") + buf.write("\n\2\f\2\16\2\u011f\13\2\3\2\7\2\u0122\n\2\f\2\16\2\u0125") + buf.write("\13\2\3\2\3\2\3\3\3\3\3\4\3\4\3\4\3\4\3\4\5\4\u0130\n") + buf.write("\4\3\5\3\5\5\5\u0134\n\5\3\6\3\6\3\6\3\6\3\6\3\6\7\6\u013c") + buf.write("\n\6\f\6\16\6\u013f\13\6\3\7\3\7\3\7\3\7\3\7\3\7\3\7\3") + buf.write("\7\3\7\3\7\3\7\5\7\u014c\n\7\3\b\3\b\3\b\3\b\3\b\3\b\3") + buf.write("\t\3\t\3\n\3\n\3\13\3\13\3\13\3\13\3\13\3\f\3\f\3\f\3") + buf.write("\f\3\f\3\f\3\f\3\f\3\r\3\r\3\16\3\16\5\16\u0169\n\16\3") + buf.write("\17\3\17\3\17\7\17\u016e\n\17\f\17\16\17\u0171\13\17\3") + buf.write("\20\3\20\3\20\3\20\3\21\3\21\3\21\3\21\3\21\5\21\u017c") + buf.write("\n\21\3\21\3\21\5\21\u0180\n\21\3\21\3\21\3\22\3\22\3") + buf.write("\22\3\22\5\22\u0188\n\22\3\23\3\23\3\23\3\23\5\23\u018e") + buf.write("\n\23\3\24\3\24\3\25\3\25\3\25\3\25\3\25\3\25\3\25\7\25") + buf.write("\u0199\n\25\f\25\16\25\u019c\13\25\3\25\3\25\3\25\3\26") + buf.write("\3\26\3\26\5\26\u01a4\n\26\3\27\3\27\3\30\3\30\3\31\3") + buf.write("\31\3\32\3\32\3\32\3\32\3\33\3\33\3\33\3\33\3\33\5\33") + buf.write("\u01b5\n\33\3\33\3\33\3\34\3\34\3\34\5\34\u01bc\n\34\3") + buf.write("\34\3\34\3\34\3\34\6\34\u01c2\n\34\r\34\16\34\u01c3\3") + buf.write("\34\3\34\3\34\5\34\u01c9\n\34\3\35\3\35\3\35\5\35\u01ce") + buf.write("\n\35\3\36\3\36\3\36\3\36\3\36\5\36\u01d5\n\36\3\37\3") + buf.write("\37\3 \3 \3!\3!\3!\5!\u01de\n!\3!\3!\3!\3!\6!\u01e4\n") + buf.write("!\r!\16!\u01e5\3!\3!\3!\5!\u01eb\n!\3\"\3\"\3\"\5\"\u01f0") + buf.write("\n\"\3#\3#\3#\3#\3#\5#\u01f7\n#\3$\3$\3%\3%\3%\5%\u01fe") + buf.write("\n%\3%\3%\3%\3%\3%\6%\u0205\n%\r%\16%\u0206\3%\3%\3%\5") + buf.write("%\u020c\n%\3&\3&\3&\5&\u0211\n&\3\'\3\'\3\'\3\'\3\'\3") + buf.write("\'\5\'\u0219\n\'\3(\3(\3(\5(\u021e\n(\3(\3(\3)\3)\3*\3") + buf.write("*\3*\5*\u0227\n*\3*\3*\3*\3*\3*\6*\u022e\n*\r*\16*\u022f") + buf.write("\3*\3*\3*\5*\u0235\n*\3+\3+\3+\5+\u023a\n+\3,\3,\3,\3") + buf.write(",\5,\u0240\n,\3,\3,\3,\5,\u0245\n,\3,\3,\3,\3,\6,\u024b") + buf.write("\n,\r,\16,\u024c\3,\3,\3,\5,\u0252\n,\3-\3-\3.\3.\5.\u0258") + buf.write("\n.\3/\3/\3/\3/\3/\3/\3/\7/\u0261\n/\f/\16/\u0264\13/") + buf.write("\3/\3/\3/\3\60\3\60\3\60\3\60\3\60\3\60\6\60\u026f\n\60") + buf.write("\r\60\16\60\u0270\3\60\3\60\3\61\3\61\5\61\u0277\n\61") + buf.write("\3\62\3\62\3\62\3\62\5\62\u027d\n\62\3\63\3\63\3\63\3") + buf.write("\63\7\63\u0283\n\63\f\63\16\63\u0286\13\63\3\63\3\63\3") + buf.write("\63\3\63\5\63\u028c\n\63\3\63\3\63\5\63\u0290\n\63\3\64") + buf.write("\3\64\5\64\u0294\n\64\3\65\3\65\3\65\5\65\u0299\n\65\3") + buf.write("\66\3\66\3\67\3\67\3\67\3\67\38\38\39\39\3:\3:\3:\3:\3") + buf.write(":\3:\5:\u02ab\n:\3:\3:\5:\u02af\n:\3:\3:\3;\3;\5;\u02b5") + buf.write("\n;\3;\3;\5;\u02b9\n;\3;\5;\u02bc\n;\3<\3<\3<\3=\3=\3") + buf.write("=\3>\3>\3?\3?\3@\3@\3@\5@\u02cb\n@\3@\3@\3A\3A\3A\3A\3") + buf.write("A\5A\u02d4\nA\3B\3B\3B\3B\3B\3C\3C\3C\3C\3C\3D\3D\3D\3") + buf.write("D\3D\3E\3E\3E\3E\3E\3E\3E\3E\5E\u02ed\nE\3E\3E\3F\3F\3") + buf.write("G\3G\3H\3H\5H\u02f7\nH\3I\3I\3I\7I\u02fc\nI\fI\16I\u02ff") + buf.write("\13I\3I\3I\3I\3I\5I\u0305\nI\3I\3I\5I\u0309\nI\3J\3J\3") + buf.write("J\3J\7J\u030f\nJ\fJ\16J\u0312\13J\3J\3J\3J\3J\3J\5J\u0319") + buf.write("\nJ\5J\u031b\nJ\3J\3J\3K\3K\3K\3K\3K\3K\3K\5K\u0326\n") + buf.write("K\3K\3K\3L\3L\3M\3M\3M\3M\3M\6M\u0331\nM\rM\16M\u0332") + buf.write("\3M\3M\3N\3N\5N\u0339\nN\3O\3O\5O\u033d\nO\3P\3P\3P\5") + buf.write("P\u0342\nP\3P\3P\3P\3P\3Q\3Q\3R\3R\3S\3S\3S\3S\3S\3S\3") + buf.write("T\3T\5T\u0354\nT\3U\3U\5U\u0358\nU\3U\3U\5U\u035c\nU\3") + buf.write("U\3U\3U\5U\u0361\nU\3U\3U\3U\3V\3V\3V\3V\3V\3W\3W\5W\u036d") + buf.write("\nW\3X\3X\3X\3X\3X\3X\6X\u0375\nX\rX\16X\u0376\3X\3X\3") + buf.write("Y\3Y\5Y\u037d\nY\3Z\3Z\3Z\3[\3[\3[\5[\u0385\n[\3[\3[\3") + buf.write("[\3[\3[\5[\u038c\n[\3\\\3\\\3\\\5\\\u0391\n\\\3\\\5\\") + buf.write("\u0394\n\\\3\\\3\\\3\\\3\\\6\\\u039a\n\\\r\\\16\\\u039b") + buf.write("\3\\\3\\\5\\\u03a0\n\\\3]\3]\3^\3^\3^\5^\u03a7\n^\3^\3") + buf.write("^\3^\5^\u03ac\n^\3^\3^\3^\5^\u03b1\n^\3_\3_\3_\3_\3_\6") + buf.write("_\u03b8\n_\r_\16_\u03b9\3_\3_\3`\3`\3`\5`\u03c1\n`\3a") + buf.write("\3a\3b\3b\3c\3c\3c\3c\3d\3d\3d\3d\3d\3d\5d\u03d1\nd\3") + buf.write("d\3d\3e\3e\3e\3e\3f\3f\3f\3f\3g\3g\3g\5g\u03e0\ng\3g\3") + buf.write("g\3h\3h\3h\3h\5h\u03e8\nh\3h\3h\3h\5h\u03ed\nh\3h\3h\3") + buf.write("h\3i\3i\3j\3j\5j\u03f6\nj\3j\3j\3j\3j\3j\3j\3j\5j\u03ff") + buf.write("\nj\3j\3j\5j\u0403\nj\3k\3k\3l\3l\3m\3m\5m\u040b\nm\3") + buf.write("n\3n\3n\5n\u0410\nn\3n\7n\u0413\nn\fn\16n\u0416\13n\3") + buf.write("n\3n\3n\3o\3o\3o\5o\u041e\no\3o\7o\u0421\no\fo\16o\u0424") + buf.write("\13o\3o\3o\3o\3p\3p\3p\3p\3p\3p\3p\3p\3p\3p\3p\3p\3p\3") + buf.write("p\3p\3p\3p\3p\3p\3p\3p\3p\5p\u043f\np\3q\3q\3r\3r\5r\u0445") + buf.write("\nr\3s\3s\3s\3s\3s\3s\3t\3t\3t\7t\u0450\nt\ft\16t\u0453") + buf.write("\13t\3u\3u\3u\7u\u0458\nu\fu\16u\u045b\13u\3v\3v\3v\7") + buf.write("v\u0460\nv\fv\16v\u0463\13v\3w\3w\3w\5w\u0468\nw\3x\3") + buf.write("x\3x\3x\3x\3x\3x\7x\u0471\nx\fx\16x\u0474\13x\3y\3y\3") + buf.write("z\3z\3z\3z\3z\3z\3z\7z\u047f\nz\fz\16z\u0482\13z\3{\3") + buf.write("{\3|\3|\3|\3|\3|\3|\3|\7|\u048d\n|\f|\16|\u0490\13|\3") + buf.write("}\3}\3~\3~\3~\5~\u0497\n~\3\177\3\177\3\177\3\177\3\177") + buf.write("\3\177\3\177\3\177\3\177\3\177\3\177\3\177\3\177\3\177") + buf.write("\3\177\3\177\3\177\3\177\3\177\3\177\3\177\3\177\3\177") + buf.write("\3\177\3\177\5\177\u04b2\n\177\3\177\3\177\3\177\3\177") + buf.write("\7\177\u04b8\n\177\f\177\16\177\u04bb\13\177\3\u0080\3") + buf.write("\u0080\3\u0080\3\u0080\3\u0081\3\u0081\3\u0081\3\u0081") + buf.write("\3\u0081\3\u0081\3\u0081\5\u0081\u04c8\n\u0081\3\u0082") + buf.write("\3\u0082\3\u0082\3\u0082\3\u0082\3\u0082\3\u0082\3\u0082") + buf.write("\3\u0082\5\u0082\u04d3\n\u0082\3\u0083\3\u0083\3\u0083") + buf.write("\3\u0083\7\u0083\u04d9\n\u0083\f\u0083\16\u0083\u04dc") + buf.write("\13\u0083\3\u0083\3\u0083\3\u0084\3\u0084\3\u0084\3\u0084") + buf.write("\3\u0084\3\u0084\3\u0084\3\u0084\3\u0084\3\u0084\3\u0084") + buf.write("\3\u0084\3\u0084\5\u0084\u04ed\n\u0084\3\u0085\3\u0085") + buf.write("\3\u0085\7\u0085\u04f2\n\u0085\f\u0085\16\u0085\u04f5") + buf.write("\13\u0085\3\u0085\3\u0085\3\u0086\3\u0086\3\u0086\7\u0086") + buf.write("\u04fc\n\u0086\f\u0086\16\u0086\u04ff\13\u0086\3\u0087") + buf.write("\3\u0087\3\u0087\3\u0087\3\u0087\5\u0087\u0506\n\u0087") + buf.write("\3\u0088\3\u0088\3\u0089\3\u0089\3\u0089\7\u0089\u050d") + buf.write("\n\u0089\f\u0089\16\u0089\u0510\13\u0089\3\u0089\3\u0089") + buf.write("\7\u0089\u0514\n\u0089\f\u0089\16\u0089\u0517\13\u0089") + buf.write("\3\u0089\3\u0089\3\u0089\7\u0089\u051c\n\u0089\f\u0089") + buf.write("\16\u0089\u051f\13\u0089\5\u0089\u0521\n\u0089\3\u008a") + buf.write("\3\u008a\3\u008b\3\u008b\3\u008b\3\u008b\3\u008c\3\u008c") + buf.write("\5\u008c\u052b\n\u008c\3\u008c\3\u008c\3\u008d\3\u008d") + buf.write("\3\u008d\2\7\n\u00ee\u00f2\u00f6\u00fc\u008e\2\4\6\b\n") + buf.write("\f\16\20\22\24\26\30\32\34\36 \"$&(*,.\60\62\64\668:<") + buf.write(">@BDFHJLNPRTVXZ\\^`bdfhjlnprtvxz|~\u0080\u0082\u0084\u0086") + buf.write("\u0088\u008a\u008c\u008e\u0090\u0092\u0094\u0096\u0098") + buf.write("\u009a\u009c\u009e\u00a0\u00a2\u00a4\u00a6\u00a8\u00aa") + buf.write("\u00ac\u00ae\u00b0\u00b2\u00b4\u00b6\u00b8\u00ba\u00bc") + buf.write("\u00be\u00c0\u00c2\u00c4\u00c6\u00c8\u00ca\u00cc\u00ce") + buf.write("\u00d0\u00d2\u00d4\u00d6\u00d8\u00da\u00dc\u00de\u00e0") + buf.write("\u00e2\u00e4\u00e6\u00e8\u00ea\u00ec\u00ee\u00f0\u00f2") + buf.write("\u00f4\u00f6\u00f8\u00fa\u00fc\u00fe\u0100\u0102\u0104") + buf.write("\u0106\u0108\u010a\u010c\u010e\u0110\u0112\u0114\u0116") + buf.write("\u0118\2\13\3\2\16\25\3\2ef\3\2#\'\3\2\64\65\3\29;\4\2") + buf.write("\31\31NS\3\2TU\3\2VX\3\2eg\2\u0550\2\u011d\3\2\2\2\4\u0128") + buf.write("\3\2\2\2\6\u012f\3\2\2\2\b\u0133\3\2\2\2\n\u0135\3\2\2") + buf.write("\2\f\u014b\3\2\2\2\16\u014d\3\2\2\2\20\u0153\3\2\2\2\22") + buf.write("\u0155\3\2\2\2\24\u0157\3\2\2\2\26\u015c\3\2\2\2\30\u0164") + buf.write("\3\2\2\2\32\u0168\3\2\2\2\34\u016a\3\2\2\2\36\u0172\3") + buf.write("\2\2\2 \u0176\3\2\2\2\"\u0183\3\2\2\2$\u0189\3\2\2\2&") + buf.write("\u018f\3\2\2\2(\u0191\3\2\2\2*\u01a0\3\2\2\2,\u01a5\3") + buf.write("\2\2\2.\u01a7\3\2\2\2\60\u01a9\3\2\2\2\62\u01ab\3\2\2") + buf.write("\2\64\u01af\3\2\2\2\66\u01b8\3\2\2\28\u01ca\3\2\2\2:\u01d4") + buf.write("\3\2\2\2<\u01d6\3\2\2\2>\u01d8\3\2\2\2@\u01da\3\2\2\2") + buf.write("B\u01ec\3\2\2\2D\u01f6\3\2\2\2F\u01f8\3\2\2\2H\u01fa\3") + buf.write("\2\2\2J\u020d\3\2\2\2L\u0218\3\2\2\2N\u021d\3\2\2\2P\u0221") + buf.write("\3\2\2\2R\u0223\3\2\2\2T\u0236\3\2\2\2V\u023b\3\2\2\2") + buf.write("X\u0253\3\2\2\2Z\u0257\3\2\2\2\\\u0259\3\2\2\2^\u0268") + buf.write("\3\2\2\2`\u0276\3\2\2\2b\u027c\3\2\2\2d\u027e\3\2\2\2") + buf.write("f\u0293\3\2\2\2h\u0298\3\2\2\2j\u029a\3\2\2\2l\u029c\3") + buf.write("\2\2\2n\u02a0\3\2\2\2p\u02a2\3\2\2\2r\u02a4\3\2\2\2t\u02bb") + buf.write("\3\2\2\2v\u02bd\3\2\2\2x\u02c0\3\2\2\2z\u02c3\3\2\2\2") + buf.write("|\u02c5\3\2\2\2~\u02ca\3\2\2\2\u0080\u02d3\3\2\2\2\u0082") + buf.write("\u02d5\3\2\2\2\u0084\u02da\3\2\2\2\u0086\u02df\3\2\2\2") + buf.write("\u0088\u02e4\3\2\2\2\u008a\u02f0\3\2\2\2\u008c\u02f2\3") + buf.write("\2\2\2\u008e\u02f6\3\2\2\2\u0090\u02f8\3\2\2\2\u0092\u030a") + buf.write("\3\2\2\2\u0094\u031e\3\2\2\2\u0096\u0329\3\2\2\2\u0098") + buf.write("\u032b\3\2\2\2\u009a\u0338\3\2\2\2\u009c\u033c\3\2\2\2") + buf.write("\u009e\u033e\3\2\2\2\u00a0\u0347\3\2\2\2\u00a2\u0349\3") + buf.write("\2\2\2\u00a4\u034b\3\2\2\2\u00a6\u0353\3\2\2\2\u00a8\u035b") + buf.write("\3\2\2\2\u00aa\u0365\3\2\2\2\u00ac\u036c\3\2\2\2\u00ae") + buf.write("\u036e\3\2\2\2\u00b0\u037c\3\2\2\2\u00b2\u037e\3\2\2\2") + buf.write("\u00b4\u0384\3\2\2\2\u00b6\u038d\3\2\2\2\u00b8\u03a1\3") + buf.write("\2\2\2\u00ba\u03a6\3\2\2\2\u00bc\u03b2\3\2\2\2\u00be\u03c0") + buf.write("\3\2\2\2\u00c0\u03c2\3\2\2\2\u00c2\u03c4\3\2\2\2\u00c4") + buf.write("\u03c6\3\2\2\2\u00c6\u03ca\3\2\2\2\u00c8\u03d4\3\2\2\2") + buf.write("\u00ca\u03d8\3\2\2\2\u00cc\u03dc\3\2\2\2\u00ce\u03e3\3") + buf.write("\2\2\2\u00d0\u03f1\3\2\2\2\u00d2\u03f3\3\2\2\2\u00d4\u0404") + buf.write("\3\2\2\2\u00d6\u0406\3\2\2\2\u00d8\u040a\3\2\2\2\u00da") + buf.write("\u040c\3\2\2\2\u00dc\u041a\3\2\2\2\u00de\u043e\3\2\2\2") + buf.write("\u00e0\u0440\3\2\2\2\u00e2\u0444\3\2\2\2\u00e4\u0446\3") + buf.write("\2\2\2\u00e6\u044c\3\2\2\2\u00e8\u0454\3\2\2\2\u00ea\u045c") + buf.write("\3\2\2\2\u00ec\u0467\3\2\2\2\u00ee\u0469\3\2\2\2\u00f0") + buf.write("\u0475\3\2\2\2\u00f2\u0477\3\2\2\2\u00f4\u0483\3\2\2\2") + buf.write("\u00f6\u0485\3\2\2\2\u00f8\u0491\3\2\2\2\u00fa\u0496\3") + buf.write("\2\2\2\u00fc\u0498\3\2\2\2\u00fe\u04bc\3\2\2\2\u0100\u04c7") + buf.write("\3\2\2\2\u0102\u04d2\3\2\2\2\u0104\u04d4\3\2\2\2\u0106") + buf.write("\u04ec\3\2\2\2\u0108\u04f3\3\2\2\2\u010a\u04f8\3\2\2\2") + buf.write("\u010c\u0500\3\2\2\2\u010e\u0507\3\2\2\2\u0110\u0520\3") + buf.write("\2\2\2\u0112\u0522\3\2\2\2\u0114\u0524\3\2\2\2\u0116\u052a") + buf.write("\3\2\2\2\u0118\u052e\3\2\2\2\u011a\u011c\5\4\3\2\u011b") + buf.write("\u011a\3\2\2\2\u011c\u011f\3\2\2\2\u011d\u011b\3\2\2\2") + buf.write("\u011d\u011e\3\2\2\2\u011e\u0123\3\2\2\2\u011f\u011d\3") + buf.write("\2\2\2\u0120\u0122\5\f\7\2\u0121\u0120\3\2\2\2\u0122\u0125") + buf.write("\3\2\2\2\u0123\u0121\3\2\2\2\u0123\u0124\3\2\2\2\u0124") + buf.write("\u0126\3\2\2\2\u0125\u0123\3\2\2\2\u0126\u0127\7\2\2\3") + buf.write("\u0127\3\3\2\2\2\u0128\u0129\5\6\4\2\u0129\5\3\2\2\2\u012a") + buf.write("\u012b\7\3\2\2\u012b\u012c\5\b\5\2\u012c\u012d\7[\2\2") + buf.write("\u012d\u0130\3\2\2\2\u012e\u0130\7[\2\2\u012f\u012a\3") + buf.write("\2\2\2\u012f\u012e\3\2\2\2\u0130\7\3\2\2\2\u0131\u0134") + buf.write("\7c\2\2\u0132\u0134\5\n\6\2\u0133\u0131\3\2\2\2\u0133") + buf.write("\u0132\3\2\2\2\u0134\t\3\2\2\2\u0135\u0136\b\6\1\2\u0136") + buf.write("\u0137\7i\2\2\u0137\u013d\3\2\2\2\u0138\u0139\f\3\2\2") + buf.write("\u0139\u013a\7\4\2\2\u013a\u013c\7i\2\2\u013b\u0138\3") + buf.write("\2\2\2\u013c\u013f\3\2\2\2\u013d\u013b\3\2\2\2\u013d\u013e") + buf.write("\3\2\2\2\u013e\13\3\2\2\2\u013f\u013d\3\2\2\2\u0140\u014c") + buf.write("\5\16\b\2\u0141\u014c\5\26\f\2\u0142\u014c\5(\25\2\u0143") + buf.write("\u014c\5\66\34\2\u0144\u014c\5@!\2\u0145\u014c\5R*\2\u0146") + buf.write("\u014c\5H%\2\u0147\u014c\5V,\2\u0148\u014c\5Z.\2\u0149") + buf.write("\u014c\5d\63\2\u014a\u014c\7[\2\2\u014b\u0140\3\2\2\2") + buf.write("\u014b\u0141\3\2\2\2\u014b\u0142\3\2\2\2\u014b\u0143\3") + buf.write("\2\2\2\u014b\u0144\3\2\2\2\u014b\u0145\3\2\2\2\u014b\u0146") + buf.write("\3\2\2\2\u014b\u0147\3\2\2\2\u014b\u0148\3\2\2\2\u014b") + buf.write("\u0149\3\2\2\2\u014b\u014a\3\2\2\2\u014c\r\3\2\2\2\u014d") + buf.write("\u014e\7\5\2\2\u014e\u014f\5\20\t\2\u014f\u0150\7\6\2") + buf.write("\2\u0150\u0151\5\22\n\2\u0151\u0152\7[\2\2\u0152\17\3") + buf.write("\2\2\2\u0153\u0154\7i\2\2\u0154\21\3\2\2\2\u0155\u0156") + buf.write("\5\24\13\2\u0156\23\3\2\2\2\u0157\u0158\7\7\2\2\u0158") + buf.write("\u0159\7^\2\2\u0159\u015a\5\34\17\2\u015a\u015b\7_\2\2") + buf.write("\u015b\25\3\2\2\2\u015c\u015d\7\b\2\2\u015d\u015e\5\32") + buf.write("\16\2\u015e\u015f\7\t\2\2\u015f\u0160\5\20\t\2\u0160\u0161") + buf.write("\7\6\2\2\u0161\u0162\5\30\r\2\u0162\u0163\7[\2\2\u0163") + buf.write("\27\3\2\2\2\u0164\u0165\5 \21\2\u0165\31\3\2\2\2\u0166") + buf.write("\u0169\7i\2\2\u0167\u0169\5&\24\2\u0168\u0166\3\2\2\2") + buf.write("\u0168\u0167\3\2\2\2\u0169\33\3\2\2\2\u016a\u016f\5\36") + buf.write("\20\2\u016b\u016c\7\n\2\2\u016c\u016e\5\36\20\2\u016d") + buf.write("\u016b\3\2\2\2\u016e\u0171\3\2\2\2\u016f\u016d\3\2\2\2") + buf.write("\u016f\u0170\3\2\2\2\u0170\35\3\2\2\2\u0171\u016f\3\2") + buf.write("\2\2\u0172\u0173\5&\24\2\u0173\u0174\7\13\2\2\u0174\u0175") + buf.write("\5\u0118\u008d\2\u0175\37\3\2\2\2\u0176\u0177\7\7\2\2") + buf.write("\u0177\u0178\7^\2\2\u0178\u017b\5\34\17\2\u0179\u017a") + buf.write("\7\n\2\2\u017a\u017c\5\"\22\2\u017b\u0179\3\2\2\2\u017b") + buf.write("\u017c\3\2\2\2\u017c\u017f\3\2\2\2\u017d\u017e\7\n\2\2") + buf.write("\u017e\u0180\5$\23\2\u017f\u017d\3\2\2\2\u017f\u0180\3") + buf.write("\2\2\2\u0180\u0181\3\2\2\2\u0181\u0182\7_\2\2\u0182!\3") + buf.write("\2\2\2\u0183\u0184\7\f\2\2\u0184\u0187\7\13\2\2\u0185") + buf.write("\u0188\7d\2\2\u0186\u0188\5\u0118\u008d\2\u0187\u0185") + buf.write("\3\2\2\2\u0187\u0186\3\2\2\2\u0188#\3\2\2\2\u0189\u018a") + buf.write("\7\r\2\2\u018a\u018d\7\13\2\2\u018b\u018e\7d\2\2\u018c") + buf.write("\u018e\5\u0118\u008d\2\u018d\u018b\3\2\2\2\u018d\u018c") + buf.write("\3\2\2\2\u018e%\3\2\2\2\u018f\u0190\t\2\2\2\u0190\'\3") + buf.write("\2\2\2\u0191\u0192\7\26\2\2\u0192\u0193\5.\30\2\u0193") + buf.write("\u0194\7\13\2\2\u0194\u0195\7\\\2\2\u0195\u019a\5*\26") + buf.write("\2\u0196\u0197\7\n\2\2\u0197\u0199\5*\26\2\u0198\u0196") + buf.write("\3\2\2\2\u0199\u019c\3\2\2\2\u019a\u0198\3\2\2\2\u019a") + buf.write("\u019b\3\2\2\2\u019b\u019d\3\2\2\2\u019c\u019a\3\2\2\2") + buf.write("\u019d\u019e\7]\2\2\u019e\u019f\7[\2\2\u019f)\3\2\2\2") + buf.write("\u01a0\u01a3\5\60\31\2\u01a1\u01a2\7\27\2\2\u01a2\u01a4") + buf.write("\5,\27\2\u01a3\u01a1\3\2\2\2\u01a3\u01a4\3\2\2\2\u01a4") + buf.write("+\3\2\2\2\u01a5\u01a6\t\3\2\2\u01a6-\3\2\2\2\u01a7\u01a8") + buf.write("\7i\2\2\u01a8/\3\2\2\2\u01a9\u01aa\7i\2\2\u01aa\61\3\2") + buf.write("\2\2\u01ab\u01ac\5.\30\2\u01ac\u01ad\7\30\2\2\u01ad\u01ae") + buf.write("\5\60\31\2\u01ae\63\3\2\2\2\u01af\u01b0\7^\2\2\u01b0\u01b1") + buf.write("\5<\37\2\u01b1\u01b4\7\31\2\2\u01b2\u01b5\5\62\32\2\u01b3") + buf.write("\u01b5\7h\2\2\u01b4\u01b2\3\2\2\2\u01b4\u01b3\3\2\2\2") + buf.write("\u01b5\u01b6\3\2\2\2\u01b6\u01b7\7_\2\2\u01b7\65\3\2\2") + buf.write("\2\u01b8\u01b9\7\32\2\2\u01b9\u01bb\5> \2\u01ba\u01bc") + buf.write("\58\35\2\u01bb\u01ba\3\2\2\2\u01bb\u01bc\3\2\2\2\u01bc") + buf.write("\u01c8\3\2\2\2\u01bd\u01be\7\13\2\2\u01be\u01bf\7[\2\2") + buf.write("\u01bf\u01c1\7j\2\2\u01c0\u01c2\5:\36\2\u01c1\u01c0\3") + buf.write("\2\2\2\u01c2\u01c3\3\2\2\2\u01c3\u01c1\3\2\2\2\u01c3\u01c4") + buf.write("\3\2\2\2\u01c4\u01c5\3\2\2\2\u01c5\u01c6\7k\2\2\u01c6") + buf.write("\u01c9\3\2\2\2\u01c7\u01c9\7[\2\2\u01c8\u01bd\3\2\2\2") + buf.write("\u01c8\u01c7\3\2\2\2\u01c9\67\3\2\2\2\u01ca\u01cb\7\33") + buf.write("\2\2\u01cb\u01cd\5> \2\u01cc\u01ce\5\64\33\2\u01cd\u01cc") + buf.write("\3\2\2\2\u01cd\u01ce\3\2\2\2\u01ce9\3\2\2\2\u01cf\u01d5") + buf.write("\5r:\2\u01d0\u01d5\5\u008eH\2\u01d1\u01d5\5\u009cO\2\u01d2") + buf.write("\u01d5\5\u00ceh\2\u01d3\u01d5\5\u00d8m\2\u01d4\u01cf\3") + buf.write("\2\2\2\u01d4\u01d0\3\2\2\2\u01d4\u01d1\3\2\2\2\u01d4\u01d2") + buf.write("\3\2\2\2\u01d4\u01d3\3\2\2\2\u01d5;\3\2\2\2\u01d6\u01d7") + buf.write("\7i\2\2\u01d7=\3\2\2\2\u01d8\u01d9\7i\2\2\u01d9?\3\2\2") + buf.write("\2\u01da\u01db\7\34\2\2\u01db\u01dd\5F$\2\u01dc\u01de") + buf.write("\5B\"\2\u01dd\u01dc\3\2\2\2\u01dd\u01de\3\2\2\2\u01de") + buf.write("\u01ea\3\2\2\2\u01df\u01e0\7\13\2\2\u01e0\u01e1\7[\2\2") + buf.write("\u01e1\u01e3\7j\2\2\u01e2\u01e4\5D#\2\u01e3\u01e2\3\2") + buf.write("\2\2\u01e4\u01e5\3\2\2\2\u01e5\u01e3\3\2\2\2\u01e5\u01e6") + buf.write("\3\2\2\2\u01e6\u01e7\3\2\2\2\u01e7\u01e8\7k\2\2\u01e8") + buf.write("\u01eb\3\2\2\2\u01e9\u01eb\7[\2\2\u01ea\u01df\3\2\2\2") + buf.write("\u01ea\u01e9\3\2\2\2\u01ebA\3\2\2\2\u01ec\u01ed\7\33\2") + buf.write("\2\u01ed\u01ef\5F$\2\u01ee\u01f0\5\64\33\2\u01ef\u01ee") + buf.write("\3\2\2\2\u01ef\u01f0\3\2\2\2\u01f0C\3\2\2\2\u01f1\u01f7") + buf.write("\5r:\2\u01f2\u01f7\5\u008eH\2\u01f3\u01f7\5\u009cO\2\u01f4") + buf.write("\u01f7\5\u00ceh\2\u01f5\u01f7\5\u00d8m\2\u01f6\u01f1\3") + buf.write("\2\2\2\u01f6\u01f2\3\2\2\2\u01f6\u01f3\3\2\2\2\u01f6\u01f4") + buf.write("\3\2\2\2\u01f6\u01f5\3\2\2\2\u01f7E\3\2\2\2\u01f8\u01f9") + buf.write("\7i\2\2\u01f9G\3\2\2\2\u01fa\u01fb\7\35\2\2\u01fb\u01fd") + buf.write("\5N(\2\u01fc\u01fe\5J&\2\u01fd\u01fc\3\2\2\2\u01fd\u01fe") + buf.write("\3\2\2\2\u01fe\u020b\3\2\2\2\u01ff\u0200\7\13\2\2\u0200") + buf.write("\u0201\7[\2\2\u0201\u0204\7j\2\2\u0202\u0205\5L\'\2\u0203") + buf.write("\u0205\5\u00acW\2\u0204\u0202\3\2\2\2\u0204\u0203\3\2") + buf.write("\2\2\u0205\u0206\3\2\2\2\u0206\u0204\3\2\2\2\u0206\u0207") + buf.write("\3\2\2\2\u0207\u0208\3\2\2\2\u0208\u0209\7k\2\2\u0209") + buf.write("\u020c\3\2\2\2\u020a\u020c\7[\2\2\u020b\u01ff\3\2\2\2") + buf.write("\u020b\u020a\3\2\2\2\u020cI\3\2\2\2\u020d\u020e\7\33\2") + buf.write("\2\u020e\u0210\5N(\2\u020f\u0211\5\64\33\2\u0210\u020f") + buf.write("\3\2\2\2\u0210\u0211\3\2\2\2\u0211K\3\2\2\2\u0212\u0219") + buf.write("\5r:\2\u0213\u0219\5\u008eH\2\u0214\u0219\5\u009cO\2\u0215") + buf.write("\u0219\5\u00ceh\2\u0216\u0219\5\u00d8m\2\u0217\u0219\5") + buf.write("\u00a8U\2\u0218\u0212\3\2\2\2\u0218\u0213\3\2\2\2\u0218") + buf.write("\u0214\3\2\2\2\u0218\u0215\3\2\2\2\u0218\u0216\3\2\2\2") + buf.write("\u0218\u0217\3\2\2\2\u0219M\3\2\2\2\u021a\u021b\5F$\2") + buf.write("\u021b\u021c\7\4\2\2\u021c\u021e\3\2\2\2\u021d\u021a\3") + buf.write("\2\2\2\u021d\u021e\3\2\2\2\u021e\u021f\3\2\2\2\u021f\u0220") + buf.write("\5P)\2\u0220O\3\2\2\2\u0221\u0222\7i\2\2\u0222Q\3\2\2") + buf.write("\2\u0223\u0224\7\36\2\2\u0224\u0226\5N(\2\u0225\u0227") + buf.write("\5T+\2\u0226\u0225\3\2\2\2\u0226\u0227\3\2\2\2\u0227\u0234") + buf.write("\3\2\2\2\u0228\u0229\7\13\2\2\u0229\u022a\7[\2\2\u022a") + buf.write("\u022d\7j\2\2\u022b\u022e\5L\'\2\u022c\u022e\5\u00acW") + buf.write("\2\u022d\u022b\3\2\2\2\u022d\u022c\3\2\2\2\u022e\u022f") + buf.write("\3\2\2\2\u022f\u022d\3\2\2\2\u022f\u0230\3\2\2\2\u0230") + buf.write("\u0231\3\2\2\2\u0231\u0232\7k\2\2\u0232\u0235\3\2\2\2") + buf.write("\u0233\u0235\7[\2\2\u0234\u0228\3\2\2\2\u0234\u0233\3") + buf.write("\2\2\2\u0235S\3\2\2\2\u0236\u0237\7\33\2\2\u0237\u0239") + buf.write("\5N(\2\u0238\u023a\5\64\33\2\u0239\u0238\3\2\2\2\u0239") + buf.write("\u023a\3\2\2\2\u023aU\3\2\2\2\u023b\u023f\7\37\2\2\u023c") + buf.write("\u023d\5F$\2\u023d\u023e\7\4\2\2\u023e\u0240\3\2\2\2\u023f") + buf.write("\u023c\3\2\2\2\u023f\u0240\3\2\2\2\u0240\u0241\3\2\2\2") + buf.write("\u0241\u0244\5X-\2\u0242\u0243\7\t\2\2\u0243\u0245\5N") + buf.write("(\2\u0244\u0242\3\2\2\2\u0244\u0245\3\2\2\2\u0245\u0251") + buf.write("\3\2\2\2\u0246\u0247\7\13\2\2\u0247\u0248\7[\2\2\u0248") + buf.write("\u024a\7j\2\2\u0249\u024b\5L\'\2\u024a\u0249\3\2\2\2\u024b") + buf.write("\u024c\3\2\2\2\u024c\u024a\3\2\2\2\u024c\u024d\3\2\2\2") + buf.write("\u024d\u024e\3\2\2\2\u024e\u024f\7k\2\2\u024f\u0252\3") + buf.write("\2\2\2\u0250\u0252\7[\2\2\u0251\u0246\3\2\2\2\u0251\u0250") + buf.write("\3\2\2\2\u0252W\3\2\2\2\u0253\u0254\7i\2\2\u0254Y\3\2") + buf.write("\2\2\u0255\u0258\5\\/\2\u0256\u0258\5^\60\2\u0257\u0255") + buf.write("\3\2\2\2\u0257\u0256\3\2\2\2\u0258[\3\2\2\2\u0259\u025a") + buf.write("\7 \2\2\u025a\u025b\5.\30\2\u025b\u025c\7\13\2\2\u025c") + buf.write("\u025d\7\\\2\2\u025d\u0262\5*\26\2\u025e\u025f\7\n\2\2") + buf.write("\u025f\u0261\5*\26\2\u0260\u025e\3\2\2\2\u0261\u0264\3") + buf.write("\2\2\2\u0262\u0260\3\2\2\2\u0262\u0263\3\2\2\2\u0263\u0265") + buf.write("\3\2\2\2\u0264\u0262\3\2\2\2\u0265\u0266\7]\2\2\u0266") + buf.write("\u0267\7[\2\2\u0267]\3\2\2\2\u0268\u0269\7 \2\2\u0269") + buf.write("\u026a\5`\61\2\u026a\u026b\7\13\2\2\u026b\u026c\7[\2\2") + buf.write("\u026c\u026e\7j\2\2\u026d\u026f\5b\62\2\u026e\u026d\3") + buf.write("\2\2\2\u026f\u0270\3\2\2\2\u0270\u026e\3\2\2\2\u0270\u0271") + buf.write("\3\2\2\2\u0271\u0272\3\2\2\2\u0272\u0273\7k\2\2\u0273") + buf.write("_\3\2\2\2\u0274\u0277\5p9\2\u0275\u0277\5N(\2\u0276\u0274") + buf.write("\3\2\2\2\u0276\u0275\3\2\2\2\u0277a\3\2\2\2\u0278\u027d") + buf.write("\5:\36\2\u0279\u027d\5D#\2\u027a\u027d\5L\'\2\u027b\u027d") + buf.write("\5\u00acW\2\u027c\u0278\3\2\2\2\u027c\u0279\3\2\2\2\u027c") + buf.write("\u027a\3\2\2\2\u027c\u027b\3\2\2\2\u027dc\3\2\2\2\u027e") + buf.write("\u027f\7!\2\2\u027f\u0284\5<\37\2\u0280\u0281\7\n\2\2") + buf.write("\u0281\u0283\5<\37\2\u0282\u0280\3\2\2\2\u0283\u0286\3") + buf.write("\2\2\2\u0284\u0282\3\2\2\2\u0284\u0285\3\2\2\2\u0285\u0287") + buf.write("\3\2\2\2\u0286\u0284\3\2\2\2\u0287\u0288\7\13\2\2\u0288") + buf.write("\u028b\5f\64\2\u0289\u028a\7\27\2\2\u028a\u028c\5\u0096") + buf.write("L\2\u028b\u0289\3\2\2\2\u028b\u028c\3\2\2\2\u028c\u028f") + buf.write("\3\2\2\2\u028d\u0290\5\u0098M\2\u028e\u0290\7[\2\2\u028f") + buf.write("\u028d\3\2\2\2\u028f\u028e\3\2\2\2\u0290e\3\2\2\2\u0291") + buf.write("\u0294\5h\65\2\u0292\u0294\5j\66\2\u0293\u0291\3\2\2\2") + buf.write("\u0293\u0292\3\2\2\2\u0294g\3\2\2\2\u0295\u0299\5n8\2") + buf.write("\u0296\u0299\5p9\2\u0297\u0299\5N(\2\u0298\u0295\3\2\2") + buf.write("\2\u0298\u0296\3\2\2\2\u0298\u0297\3\2\2\2\u0299i\3\2") + buf.write("\2\2\u029a\u029b\5l\67\2\u029bk\3\2\2\2\u029c\u029d\7") + buf.write("\"\2\2\u029d\u029e\7\t\2\2\u029e\u029f\5h\65\2\u029fm") + buf.write("\3\2\2\2\u02a0\u02a1\t\4\2\2\u02a1o\3\2\2\2\u02a2\u02a3") + buf.write("\7i\2\2\u02a3q\3\2\2\2\u02a4\u02a5\7(\2\2\u02a5\u02aa") + buf.write("\5|?\2\u02a6\u02a7\7^\2\2\u02a7\u02a8\5\u010a\u0086\2") + buf.write("\u02a8\u02a9\7_\2\2\u02a9\u02ab\3\2\2\2\u02aa\u02a6\3") + buf.write("\2\2\2\u02aa\u02ab\3\2\2\2\u02ab\u02ae\3\2\2\2\u02ac\u02ad") + buf.write("\7\6\2\2\u02ad\u02af\5t;\2\u02ae\u02ac\3\2\2\2\u02ae\u02af") + buf.write("\3\2\2\2\u02af\u02b0\3\2\2\2\u02b0\u02b1\7[\2\2\u02b1") + buf.write("s\3\2\2\2\u02b2\u02b8\5v<\2\u02b3\u02b5\5x=\2\u02b4\u02b3") + buf.write("\3\2\2\2\u02b4\u02b5\3\2\2\2\u02b5\u02b6\3\2\2\2\u02b6") + buf.write("\u02b7\7)\2\2\u02b7\u02b9\5\u0080A\2\u02b8\u02b4\3\2\2") + buf.write("\2\u02b8\u02b9\3\2\2\2\u02b9\u02bc\3\2\2\2\u02ba\u02bc") + buf.write("\5\u0080A\2\u02bb\u02b2\3\2\2\2\u02bb\u02ba\3\2\2\2\u02bc") + buf.write("u\3\2\2\2\u02bd\u02be\7*\2\2\u02be\u02bf\5~@\2\u02bfw") + buf.write("\3\2\2\2\u02c0\u02c1\7+\2\2\u02c1\u02c2\5z>\2\u02c2y\3") + buf.write("\2\2\2\u02c3\u02c4\7i\2\2\u02c4{\3\2\2\2\u02c5\u02c6\7") + buf.write("i\2\2\u02c6}\3\2\2\2\u02c7\u02c8\5\u00e2r\2\u02c8\u02c9") + buf.write("\7\4\2\2\u02c9\u02cb\3\2\2\2\u02ca\u02c7\3\2\2\2\u02ca") + buf.write("\u02cb\3\2\2\2\u02cb\u02cc\3\2\2\2\u02cc\u02cd\5|?\2\u02cd") + buf.write("\177\3\2\2\2\u02ce\u02d4\5\u008aF\2\u02cf\u02d4\5\u0082") + buf.write("B\2\u02d0\u02d4\5\u0084C\2\u02d1\u02d4\5\u0086D\2\u02d2") + buf.write("\u02d4\5\u0088E\2\u02d3\u02ce\3\2\2\2\u02d3\u02cf\3\2") + buf.write("\2\2\u02d3\u02d0\3\2\2\2\u02d3\u02d1\3\2\2\2\u02d3\u02d2") + buf.write("\3\2\2\2\u02d4\u0081\3\2\2\2\u02d5\u02d6\7,\2\2\u02d6") + buf.write("\u02d7\7^\2\2\u02d7\u02d8\5\u008aF\2\u02d8\u02d9\7_\2") + buf.write("\2\u02d9\u0083\3\2\2\2\u02da\u02db\7-\2\2\u02db\u02dc") + buf.write("\7^\2\2\u02dc\u02dd\5\u008aF\2\u02dd\u02de\7_\2\2\u02de") + buf.write("\u0085\3\2\2\2\u02df\u02e0\7.\2\2\u02e0\u02e1\7^\2\2\u02e1") + buf.write("\u02e2\5\u008cG\2\u02e2\u02e3\7_\2\2\u02e3\u0087\3\2\2") + buf.write("\2\u02e4\u02e5\7/\2\2\u02e5\u02e6\7^\2\2\u02e6\u02ec\5") + buf.write("\u008cG\2\u02e7\u02e8\7\n\2\2\u02e8\u02e9\7i\2\2\u02e9") + buf.write("\u02ea\bE\1\2\u02ea\u02eb\7\13\2\2\u02eb\u02ed\5\u008c") + buf.write("G\2\u02ec\u02e7\3\2\2\2\u02ec\u02ed\3\2\2\2\u02ed\u02ee") + buf.write("\3\2\2\2\u02ee\u02ef\7_\2\2\u02ef\u0089\3\2\2\2\u02f0") + buf.write("\u02f1\5\u00e2r\2\u02f1\u008b\3\2\2\2\u02f2\u02f3\5\u00e2") + buf.write("r\2\u02f3\u008d\3\2\2\2\u02f4\u02f7\5\u0090I\2\u02f5\u02f7") + buf.write("\5\u0092J\2\u02f6\u02f4\3\2\2\2\u02f6\u02f5\3\2\2\2\u02f7") + buf.write("\u008f\3\2\2\2\u02f8\u02fd\5<\37\2\u02f9\u02fa\7\n\2\2") + buf.write("\u02fa\u02fc\5<\37\2\u02fb\u02f9\3\2\2\2\u02fc\u02ff\3") + buf.write("\2\2\2\u02fd\u02fb\3\2\2\2\u02fd\u02fe\3\2\2\2\u02fe\u0300") + buf.write("\3\2\2\2\u02ff\u02fd\3\2\2\2\u0300\u0301\7\13\2\2\u0301") + buf.write("\u0304\5f\64\2\u0302\u0303\7\27\2\2\u0303\u0305\5\u0096") + buf.write("L\2\u0304\u0302\3\2\2\2\u0304\u0305\3\2\2\2\u0305\u0308") + buf.write("\3\2\2\2\u0306\u0309\5\u0098M\2\u0307\u0309\7[\2\2\u0308") + buf.write("\u0306\3\2\2\2\u0308\u0307\3\2\2\2\u0309\u0091\3\2\2\2") + buf.write("\u030a\u030b\7\60\2\2\u030b\u0310\5<\37\2\u030c\u030d") + buf.write("\7\n\2\2\u030d\u030f\5<\37\2\u030e\u030c\3\2\2\2\u030f") + buf.write("\u0312\3\2\2\2\u0310\u030e\3\2\2\2\u0310\u0311\3\2\2\2") + buf.write("\u0311\u0313\3\2\2\2\u0312\u0310\3\2\2\2\u0313\u0314\7") + buf.write("\13\2\2\u0314\u031a\5f\64\2\u0315\u0318\7\27\2\2\u0316") + buf.write("\u0319\5\u0094K\2\u0317\u0319\5\u0102\u0082\2\u0318\u0316") + buf.write("\3\2\2\2\u0318\u0317\3\2\2\2\u0319\u031b\3\2\2\2\u031a") + buf.write("\u0315\3\2\2\2\u031a\u031b\3\2\2\2\u031b\u031c\3\2\2\2") + buf.write("\u031c\u031d\7[\2\2\u031d\u0093\3\2\2\2\u031e\u031f\7") + buf.write("\61\2\2\u031f\u0320\7^\2\2\u0320\u0321\5\u00e2r\2\u0321") + buf.write("\u0322\7\n\2\2\u0322\u0325\5t;\2\u0323\u0324\7\n\2\2\u0324") + buf.write("\u0326\5\u0096L\2\u0325\u0323\3\2\2\2\u0325\u0326\3\2") + buf.write("\2\2\u0326\u0327\3\2\2\2\u0327\u0328\7_\2\2\u0328\u0095") + buf.write("\3\2\2\2\u0329\u032a\5\u00e2r\2\u032a\u0097\3\2\2\2\u032b") + buf.write("\u032c\7\62\2\2\u032c\u032d\7\13\2\2\u032d\u032e\7[\2") + buf.write("\2\u032e\u0330\7j\2\2\u032f\u0331\5\u009aN\2\u0330\u032f") + buf.write("\3\2\2\2\u0331\u0332\3\2\2\2\u0332\u0330\3\2\2\2\u0332") + buf.write("\u0333\3\2\2\2\u0333\u0334\3\2\2\2\u0334\u0335\7k\2\2") + buf.write("\u0335\u0099\3\2\2\2\u0336\u0339\5\u009cO\2\u0337\u0339") + buf.write("\5\u00d8m\2\u0338\u0336\3\2\2\2\u0338\u0337\3\2\2\2\u0339") + buf.write("\u009b\3\2\2\2\u033a\u033d\5\u009eP\2\u033b\u033d\5\u00a4") + buf.write("S\2\u033c\u033a\3\2\2\2\u033c\u033b\3\2\2\2\u033d\u009d") + buf.write("\3\2\2\2\u033e\u033f\7\63\2\2\u033f\u0341\7^\2\2\u0340") + buf.write("\u0342\5\u00a0Q\2\u0341\u0340\3\2\2\2\u0341\u0342\3\2") + buf.write("\2\2\u0342\u0343\3\2\2\2\u0343\u0344\5\u00a2R\2\u0344") + buf.write("\u0345\7_\2\2\u0345\u0346\7[\2\2\u0346\u009f\3\2\2\2\u0347") + buf.write("\u0348\t\5\2\2\u0348\u00a1\3\2\2\2\u0349\u034a\5\u00e2") + buf.write("r\2\u034a\u00a3\3\2\2\2\u034b\u034c\7\66\2\2\u034c\u034d") + buf.write("\7^\2\2\u034d\u034e\5\u00a6T\2\u034e\u034f\7_\2\2\u034f") + buf.write("\u0350\7[\2\2\u0350\u00a5\3\2\2\2\u0351\u0354\5<\37\2") + buf.write("\u0352\u0354\5\u00fe\u0080\2\u0353\u0351\3\2\2\2\u0353") + buf.write("\u0352\3\2\2\2\u0354\u00a7\3\2\2\2\u0355\u0358\5\u00aa") + buf.write("V\2\u0356\u0358\5\u00c2b\2\u0357\u0355\3\2\2\2\u0357\u0356") + buf.write("\3\2\2\2\u0358\u0359\3\2\2\2\u0359\u035a\7\4\2\2\u035a") + buf.write("\u035c\3\2\2\2\u035b\u0357\3\2\2\2\u035b\u035c\3\2\2\2") + buf.write("\u035c\u035d\3\2\2\2\u035d\u035e\5X-\2\u035e\u0360\7^") + buf.write("\2\2\u035f\u0361\5\u0110\u0089\2\u0360\u035f\3\2\2\2\u0360") + buf.write("\u0361\3\2\2\2\u0361\u0362\3\2\2\2\u0362\u0363\7_\2\2") + buf.write("\u0363\u0364\7[\2\2\u0364\u00a9\3\2\2\2\u0365\u0366\5") + buf.write("\u00c2b\2\u0366\u0367\7\4\2\2\u0367\u0368\3\2\2\2\u0368") + buf.write("\u0369\5P)\2\u0369\u00ab\3\2\2\2\u036a\u036d\5\u00aeX") + buf.write("\2\u036b\u036d\5\u00b2Z\2\u036c\u036a\3\2\2\2\u036c\u036b") + buf.write("\3\2\2\2\u036d\u00ad\3\2\2\2\u036e\u036f\7\67\2\2\u036f") + buf.write("\u0370\5t;\2\u0370\u0371\7\13\2\2\u0371\u0372\7[\2\2\u0372") + buf.write("\u0374\7j\2\2\u0373\u0375\5\u00b0Y\2\u0374\u0373\3\2\2") + buf.write("\2\u0375\u0376\3\2\2\2\u0376\u0374\3\2\2\2\u0376\u0377") + buf.write("\3\2\2\2\u0377\u0378\3\2\2\2\u0378\u0379\7k\2\2\u0379") + buf.write("\u00af\3\2\2\2\u037a\u037d\5\u00c8e\2\u037b\u037d\5\u00c6") + buf.write("d\2\u037c\u037a\3\2\2\2\u037c\u037b\3\2\2\2\u037d\u00b1") + buf.write("\3\2\2\2\u037e\u037f\78\2\2\u037f\u0380\5\u00b4[\2\u0380") + buf.write("\u00b3\3\2\2\2\u0381\u0382\5\u00c0a\2\u0382\u0383\7\13") + buf.write("\2\2\u0383\u0385\3\2\2\2\u0384\u0381\3\2\2\2\u0384\u0385") + buf.write("\3\2\2\2\u0385\u038b\3\2\2\2\u0386\u038c\5\u00b6\\\2\u0387") + buf.write("\u038c\5\u00ba^\2\u0388\u038c\5\u00c4c\2\u0389\u038c\5") + buf.write("\u00c6d\2\u038a\u038c\5\u00c8e\2\u038b\u0386\3\2\2\2\u038b") + buf.write("\u0387\3\2\2\2\u038b\u0388\3\2\2\2\u038b\u0389\3\2\2\2") + buf.write("\u038b\u038a\3\2\2\2\u038c\u00b5\3\2\2\2\u038d\u0393\5") + buf.write("\u00b8]\2\u038e\u0390\7^\2\2\u038f\u0391\5\u0110\u0089") + buf.write("\2\u0390\u038f\3\2\2\2\u0390\u0391\3\2\2\2\u0391\u0392") + buf.write("\3\2\2\2\u0392\u0394\7_\2\2\u0393\u038e\3\2\2\2\u0393") + buf.write("\u0394\3\2\2\2\u0394\u0395\3\2\2\2\u0395\u0396\7\13\2") + buf.write("\2\u0396\u0397\7[\2\2\u0397\u0399\7j\2\2\u0398\u039a\5") + buf.write("\u00b4[\2\u0399\u0398\3\2\2\2\u039a\u039b\3\2\2\2\u039b") + buf.write("\u0399\3\2\2\2\u039b\u039c\3\2\2\2\u039c\u039d\3\2\2\2") + buf.write("\u039d\u039f\7k\2\2\u039e\u03a0\5\u00bc_\2\u039f\u039e") + buf.write("\3\2\2\2\u039f\u03a0\3\2\2\2\u03a0\u00b7\3\2\2\2\u03a1") + buf.write("\u03a2\t\6\2\2\u03a2\u00b9\3\2\2\2\u03a3\u03a4\5\u00c2") + buf.write("b\2\u03a4\u03a5\7\4\2\2\u03a5\u03a7\3\2\2\2\u03a6\u03a3") + buf.write("\3\2\2\2\u03a6\u03a7\3\2\2\2\u03a7\u03a8\3\2\2\2\u03a8") + buf.write("\u03a9\5P)\2\u03a9\u03ab\7^\2\2\u03aa\u03ac\5\u0110\u0089") + buf.write("\2\u03ab\u03aa\3\2\2\2\u03ab\u03ac\3\2\2\2\u03ac\u03ad") + buf.write("\3\2\2\2\u03ad\u03b0\7_\2\2\u03ae\u03b1\5\u00bc_\2\u03af") + buf.write("\u03b1\7[\2\2\u03b0\u03ae\3\2\2\2\u03b0\u03af\3\2\2\2") + buf.write("\u03b1\u00bb\3\2\2\2\u03b2\u03b3\7\62\2\2\u03b3\u03b4") + buf.write("\7\13\2\2\u03b4\u03b5\7[\2\2\u03b5\u03b7\7j\2\2\u03b6") + buf.write("\u03b8\5\u00be`\2\u03b7\u03b6\3\2\2\2\u03b8\u03b9\3\2") + buf.write("\2\2\u03b9\u03b7\3\2\2\2\u03b9\u03ba\3\2\2\2\u03ba\u03bb") + buf.write("\3\2\2\2\u03bb\u03bc\7k\2\2\u03bc\u00bd\3\2\2\2\u03bd") + buf.write("\u03c1\5\u009cO\2\u03be\u03c1\5\u00a8U\2\u03bf\u03c1\5") + buf.write("\u00caf\2\u03c0\u03bd\3\2\2\2\u03c0\u03be\3\2\2\2\u03c0") + buf.write("\u03bf\3\2\2\2\u03c1\u00bf\3\2\2\2\u03c2\u03c3\7i\2\2") + buf.write("\u03c3\u00c1\3\2\2\2\u03c4\u03c5\5F$\2\u03c5\u00c3\3\2") + buf.write("\2\2\u03c6\u03c7\7<\2\2\u03c7\u03c8\5t;\2\u03c8\u03c9") + buf.write("\7[\2\2\u03c9\u00c5\3\2\2\2\u03ca\u03cb\7=\2\2\u03cb\u03d0") + buf.write("\5|?\2\u03cc\u03cd\7^\2\2\u03cd\u03ce\5\u0110\u0089\2") + buf.write("\u03ce\u03cf\7_\2\2\u03cf\u03d1\3\2\2\2\u03d0\u03cc\3") + buf.write("\2\2\2\u03d0\u03d1\3\2\2\2\u03d1\u03d2\3\2\2\2\u03d2\u03d3") + buf.write("\7[\2\2\u03d3\u00c7\3\2\2\2\u03d4\u03d5\7>\2\2\u03d5\u03d6") + buf.write("\5\u00ccg\2\u03d6\u03d7\7[\2\2\u03d7\u00c9\3\2\2\2\u03d8") + buf.write("\u03d9\7?\2\2\u03d9\u03da\5t;\2\u03da\u03db\7[\2\2\u03db") + buf.write("\u00cb\3\2\2\2\u03dc\u03dd\5\u00fc\177\2\u03dd\u03df\7") + buf.write("^\2\2\u03de\u03e0\5\u0110\u0089\2\u03df\u03de\3\2\2\2") + buf.write("\u03df\u03e0\3\2\2\2\u03e0\u03e1\3\2\2\2\u03e1\u03e2\7") + buf.write("_\2\2\u03e2\u00cd\3\2\2\2\u03e3\u03e4\7@\2\2\u03e4\u03e5") + buf.write("\5\u00d6l\2\u03e5\u03e7\7^\2\2\u03e6\u03e8\5\u010a\u0086") + buf.write("\2\u03e7\u03e6\3\2\2\2\u03e7\u03e8\3\2\2\2\u03e8\u03e9") + buf.write("\3\2\2\2\u03e9\u03ec\7_\2\2\u03ea\u03eb\7A\2\2\u03eb\u03ed") + buf.write("\5\u00d0i\2\u03ec\u03ea\3\2\2\2\u03ec\u03ed\3\2\2\2\u03ed") + buf.write("\u03ee\3\2\2\2\u03ee\u03ef\5\u00d2j\2\u03ef\u03f0\7[\2") + buf.write("\2\u03f0\u00cf\3\2\2\2\u03f1\u03f2\5f\64\2\u03f2\u00d1") + buf.write("\3\2\2\2\u03f3\u03f5\7\6\2\2\u03f4\u03f6\5\u00d4k\2\u03f5") + buf.write("\u03f4\3\2\2\2\u03f5\u03f6\3\2\2\2\u03f6\u0402\3\2\2\2") + buf.write("\u03f7\u03f8\7B\2\2\u03f8\u0403\5\u00e2r\2\u03f9\u0403") + buf.write("\7C\2\2\u03fa\u03fb\7D\2\2\u03fb\u03fc\5\n\6\2\u03fc\u03fe") + buf.write("\7^\2\2\u03fd\u03ff\5\u0110\u0089\2\u03fe\u03fd\3\2\2") + buf.write("\2\u03fe\u03ff\3\2\2\2\u03ff\u0400\3\2\2\2\u0400\u0401") + buf.write("\7_\2\2\u0401\u0403\3\2\2\2\u0402\u03f7\3\2\2\2\u0402") + buf.write("\u03f9\3\2\2\2\u0402\u03fa\3\2\2\2\u0403\u00d3\3\2\2\2") + buf.write("\u0404\u0405\7E\2\2\u0405\u00d5\3\2\2\2\u0406\u0407\7") + buf.write("i\2\2\u0407\u00d7\3\2\2\2\u0408\u040b\5\u00dan\2\u0409") + buf.write("\u040b\5\u00dco\2\u040a\u0408\3\2\2\2\u040a\u0409\3\2") + buf.write("\2\2\u040b\u00d9\3\2\2\2\u040c\u040d\7F\2\2\u040d\u040f") + buf.write("\7^\2\2\u040e\u0410\5\u00e0q\2\u040f\u040e\3\2\2\2\u040f") + buf.write("\u0410\3\2\2\2\u0410\u0414\3\2\2\2\u0411\u0413\5\u00de") + buf.write("p\2\u0412\u0411\3\2\2\2\u0413\u0416\3\2\2\2\u0414\u0412") + buf.write("\3\2\2\2\u0414\u0415\3\2\2\2\u0415\u0417\3\2\2\2\u0416") + buf.write("\u0414\3\2\2\2\u0417\u0418\7_\2\2\u0418\u0419\7[\2\2\u0419") + buf.write("\u00db\3\2\2\2\u041a\u041b\7G\2\2\u041b\u041d\7^\2\2\u041c") + buf.write("\u041e\5\u00e0q\2\u041d\u041c\3\2\2\2\u041d\u041e\3\2") + buf.write("\2\2\u041e\u0422\3\2\2\2\u041f\u0421\5\u00dep\2\u0420") + buf.write("\u041f\3\2\2\2\u0421\u0424\3\2\2\2\u0422\u0420\3\2\2\2") + buf.write("\u0422\u0423\3\2\2\2\u0423\u0425\3\2\2\2\u0424\u0422\3") + buf.write("\2\2\2\u0425\u0426\7_\2\2\u0426\u0427\7[\2\2\u0427\u00dd") + buf.write("\3\2\2\2\u0428\u0429\7\n\2\2\u0429\u042a\7B\2\2\u042a") + buf.write("\u042b\7\13\2\2\u042b\u043f\5\u00e2r\2\u042c\u042d\7\n") + buf.write("\2\2\u042d\u042e\7\b\2\2\u042e\u042f\7\13\2\2\u042f\u043f") + buf.write("\5\32\16\2\u0430\u0431\7\n\2\2\u0431\u0432\7H\2\2\u0432") + buf.write("\u0433\7\13\2\2\u0433\u043f\5\u0106\u0084\2\u0434\u0435") + buf.write("\7\n\2\2\u0435\u0436\7/\2\2\u0436\u0437\7\13\2\2\u0437") + buf.write("\u043f\5\u0102\u0082\2\u0438\u0439\7\n\2\2\u0439\u043a") + buf.write("\7(\2\2\u043a\u043b\7\13\2\2\u043b\u043f\5|?\2\u043c\u043d") + buf.write("\7\n\2\2\u043d\u043f\5\u0114\u008b\2\u043e\u0428\3\2\2") + buf.write("\2\u043e\u042c\3\2\2\2\u043e\u0430\3\2\2\2\u043e\u0434") + buf.write("\3\2\2\2\u043e\u0438\3\2\2\2\u043e\u043c\3\2\2\2\u043f") + buf.write("\u00df\3\2\2\2\u0440\u0441\7i\2\2\u0441\u00e1\3\2\2\2") + buf.write("\u0442\u0445\5\u00e6t\2\u0443\u0445\5\u00e4s\2\u0444\u0442") + buf.write("\3\2\2\2\u0444\u0443\3\2\2\2\u0445\u00e3\3\2\2\2\u0446") + buf.write("\u0447\5\u00e6t\2\u0447\u0448\7I\2\2\u0448\u0449\5\u00e2") + buf.write("r\2\u0449\u044a\7\13\2\2\u044a\u044b\5\u00e2r\2\u044b") + buf.write("\u00e5\3\2\2\2\u044c\u0451\5\u00e8u\2\u044d\u044e\7J\2") + buf.write("\2\u044e\u0450\5\u00e8u\2\u044f\u044d\3\2\2\2\u0450\u0453") + buf.write("\3\2\2\2\u0451\u044f\3\2\2\2\u0451\u0452\3\2\2\2\u0452") + buf.write("\u00e7\3\2\2\2\u0453\u0451\3\2\2\2\u0454\u0459\5\u00ea") + buf.write("v\2\u0455\u0456\7K\2\2\u0456\u0458\5\u00eav\2\u0457\u0455") + buf.write("\3\2\2\2\u0458\u045b\3\2\2\2\u0459\u0457\3\2\2\2\u0459") + buf.write("\u045a\3\2\2\2\u045a\u00e9\3\2\2\2\u045b\u0459\3\2\2\2") + buf.write("\u045c\u0461\5\u00ecw\2\u045d\u045e\7L\2\2\u045e\u0460") + buf.write("\5\u00ecw\2\u045f\u045d\3\2\2\2\u0460\u0463\3\2\2\2\u0461") + buf.write("\u045f\3\2\2\2\u0461\u0462\3\2\2\2\u0462\u00eb\3\2\2\2") + buf.write("\u0463\u0461\3\2\2\2\u0464\u0465\7M\2\2\u0465\u0468\5") + buf.write("\u00ecw\2\u0466\u0468\5\u00eex\2\u0467\u0464\3\2\2\2\u0467") + buf.write("\u0466\3\2\2\2\u0468\u00ed\3\2\2\2\u0469\u046a\bx\1\2") + buf.write("\u046a\u046b\5\u00f2z\2\u046b\u0472\3\2\2\2\u046c\u046d") + buf.write("\f\3\2\2\u046d\u046e\5\u00f0y\2\u046e\u046f\5\u00f2z\2") + buf.write("\u046f\u0471\3\2\2\2\u0470\u046c\3\2\2\2\u0471\u0474\3") + buf.write("\2\2\2\u0472\u0470\3\2\2\2\u0472\u0473\3\2\2\2\u0473\u00ef") + buf.write("\3\2\2\2\u0474\u0472\3\2\2\2\u0475\u0476\t\7\2\2\u0476") + buf.write("\u00f1\3\2\2\2\u0477\u0478\bz\1\2\u0478\u0479\5\u00f6") + buf.write("|\2\u0479\u0480\3\2\2\2\u047a\u047b\f\3\2\2\u047b\u047c") + buf.write("\5\u00f4{\2\u047c\u047d\5\u00f6|\2\u047d\u047f\3\2\2\2") + buf.write("\u047e\u047a\3\2\2\2\u047f\u0482\3\2\2\2\u0480\u047e\3") + buf.write("\2\2\2\u0480\u0481\3\2\2\2\u0481\u00f3\3\2\2\2\u0482\u0480") + buf.write("\3\2\2\2\u0483\u0484\t\b\2\2\u0484\u00f5\3\2\2\2\u0485") + buf.write("\u0486\b|\1\2\u0486\u0487\5\u00fa~\2\u0487\u048e\3\2\2") + buf.write("\2\u0488\u0489\f\3\2\2\u0489\u048a\5\u00f8}\2\u048a\u048b") + buf.write("\5\u00fa~\2\u048b\u048d\3\2\2\2\u048c\u0488\3\2\2\2\u048d") + buf.write("\u0490\3\2\2\2\u048e\u048c\3\2\2\2\u048e\u048f\3\2\2\2") + buf.write("\u048f\u00f7\3\2\2\2\u0490\u048e\3\2\2\2\u0491\u0492\t") + buf.write("\t\2\2\u0492\u00f9\3\2\2\2\u0493\u0497\5\u00fc\177\2\u0494") + buf.write("\u0495\7U\2\2\u0495\u0497\5\u00fa~\2\u0496\u0493\3\2\2") + buf.write("\2\u0496\u0494\3\2\2\2\u0497\u00fb\3\2\2\2\u0498\u0499") + buf.write("\b\177\1\2\u0499\u049a\5\u0100\u0081\2\u049a\u04b9\3\2") + buf.write("\2\2\u049b\u049c\f\7\2\2\u049c\u049d\7\4\2\2\u049d\u049e") + buf.write("\7+\2\2\u049e\u049f\7^\2\2\u049f\u04a0\5f\64\2\u04a0\u04a1") + buf.write("\7_\2\2\u04a1\u04b8\3\2\2\2\u04a2\u04a3\f\6\2\2\u04a3") + buf.write("\u04a4\7\4\2\2\u04a4\u04a5\7\6\2\2\u04a5\u04a6\7^\2\2") + buf.write("\u04a6\u04a7\5f\64\2\u04a7\u04a8\7_\2\2\u04a8\u04b8\3") + buf.write("\2\2\2\u04a9\u04aa\f\5\2\2\u04aa\u04ab\7\\\2\2\u04ab\u04ac") + buf.write("\5\u00e2r\2\u04ac\u04ad\7]\2\2\u04ad\u04b8\3\2\2\2\u04ae") + buf.write("\u04af\f\4\2\2\u04af\u04b1\7^\2\2\u04b0\u04b2\5\u0110") + buf.write("\u0089\2\u04b1\u04b0\3\2\2\2\u04b1\u04b2\3\2\2\2\u04b2") + buf.write("\u04b3\3\2\2\2\u04b3\u04b8\7_\2\2\u04b4\u04b5\f\3\2\2") + buf.write("\u04b5\u04b6\7\4\2\2\u04b6\u04b8\5<\37\2\u04b7\u049b\3") + buf.write("\2\2\2\u04b7\u04a2\3\2\2\2\u04b7\u04a9\3\2\2\2\u04b7\u04ae") + buf.write("\3\2\2\2\u04b7\u04b4\3\2\2\2\u04b8\u04bb\3\2\2\2\u04b9") + buf.write("\u04b7\3\2\2\2\u04b9\u04ba\3\2\2\2\u04ba\u00fd\3\2\2\2") + buf.write("\u04bb\u04b9\3\2\2\2\u04bc\u04bd\5\u00fc\177\2\u04bd\u04be") + buf.write("\7\4\2\2\u04be\u04bf\5<\37\2\u04bf\u00ff\3\2\2\2\u04c0") + buf.write("\u04c8\5\u0102\u0082\2\u04c1\u04c8\7Y\2\2\u04c2\u04c8") + buf.write("\7i\2\2\u04c3\u04c4\7^\2\2\u04c4\u04c5\5\u00e2r\2\u04c5") + buf.write("\u04c6\7_\2\2\u04c6\u04c8\3\2\2\2\u04c7\u04c0\3\2\2\2") + buf.write("\u04c7\u04c1\3\2\2\2\u04c7\u04c2\3\2\2\2\u04c7\u04c3\3") + buf.write("\2\2\2\u04c8\u0101\3\2\2\2\u04c9\u04d3\5\u0116\u008c\2") + buf.write("\u04ca\u04d3\7d\2\2\u04cb\u04d3\5\u0118\u008d\2\u04cc") + buf.write("\u04d3\7h\2\2\u04cd\u04d3\7c\2\2\u04ce\u04d3\5\u0108\u0085") + buf.write("\2\u04cf\u04d3\5\62\32\2\u04d0\u04d3\5\u0104\u0083\2\u04d1") + buf.write("\u04d3\5\u0106\u0084\2\u04d2\u04c9\3\2\2\2\u04d2\u04ca") + buf.write("\3\2\2\2\u04d2\u04cb\3\2\2\2\u04d2\u04cc\3\2\2\2\u04d2") + buf.write("\u04cd\3\2\2\2\u04d2\u04ce\3\2\2\2\u04d2\u04cf\3\2\2\2") + buf.write("\u04d2\u04d0\3\2\2\2\u04d2\u04d1\3\2\2\2\u04d3\u0103\3") + buf.write("\2\2\2\u04d4\u04d5\7\\\2\2\u04d5\u04da\5\u00e2r\2\u04d6") + buf.write("\u04d7\7\n\2\2\u04d7\u04d9\5\u00e2r\2\u04d8\u04d6\3\2") + buf.write("\2\2\u04d9\u04dc\3\2\2\2\u04da\u04d8\3\2\2\2\u04da\u04db") + buf.write("\3\2\2\2\u04db\u04dd\3\2\2\2\u04dc\u04da\3\2\2\2\u04dd") + buf.write("\u04de\7]\2\2\u04de\u0105\3\2\2\2\u04df\u04e0\7H\2\2\u04e0") + buf.write("\u04e1\7^\2\2\u04e1\u04e2\5\u00e2r\2\u04e2\u04e3\7\n\2") + buf.write("\2\u04e3\u04e4\5\u00e2r\2\u04e4\u04e5\7_\2\2\u04e5\u04ed") + buf.write("\3\2\2\2\u04e6\u04e7\7\\\2\2\u04e7\u04e8\5\u00e2r\2\u04e8") + buf.write("\u04e9\7Z\2\2\u04e9\u04ea\5\u00e2r\2\u04ea\u04eb\7]\2") + buf.write("\2\u04eb\u04ed\3\2\2\2\u04ec\u04df\3\2\2\2\u04ec\u04e6") + buf.write("\3\2\2\2\u04ed\u0107\3\2\2\2\u04ee\u04ef\5<\37\2\u04ef") + buf.write("\u04f0\7\4\2\2\u04f0\u04f2\3\2\2\2\u04f1\u04ee\3\2\2\2") + buf.write("\u04f2\u04f5\3\2\2\2\u04f3\u04f1\3\2\2\2\u04f3\u04f4\3") + buf.write("\2\2\2\u04f4\u04f6\3\2\2\2\u04f5\u04f3\3\2\2\2\u04f6\u04f7") + buf.write("\5<\37\2\u04f7\u0109\3\2\2\2\u04f8\u04fd\5\u010c\u0087") + buf.write("\2\u04f9\u04fa\7\n\2\2\u04fa\u04fc\5\u010c\u0087\2\u04fb") + buf.write("\u04f9\3\2\2\2\u04fc\u04ff\3\2\2\2\u04fd\u04fb\3\2\2\2") + buf.write("\u04fd\u04fe\3\2\2\2\u04fe\u010b\3\2\2\2\u04ff\u04fd\3") + buf.write("\2\2\2\u0500\u0501\5\u010e\u0088\2\u0501\u0502\7\13\2") + buf.write("\2\u0502\u0505\5f\64\2\u0503\u0504\7\27\2\2\u0504\u0506") + buf.write("\5\u0096L\2\u0505\u0503\3\2\2\2\u0505\u0506\3\2\2\2\u0506") + buf.write("\u010d\3\2\2\2\u0507\u0508\7i\2\2\u0508\u010f\3\2\2\2") + buf.write("\u0509\u050e\5\u0112\u008a\2\u050a\u050b\7\n\2\2\u050b") + buf.write("\u050d\5\u0112\u008a\2\u050c\u050a\3\2\2\2\u050d\u0510") + buf.write("\3\2\2\2\u050e\u050c\3\2\2\2\u050e\u050f\3\2\2\2\u050f") + buf.write("\u0515\3\2\2\2\u0510\u050e\3\2\2\2\u0511\u0512\7\n\2\2") + buf.write("\u0512\u0514\5\u0114\u008b\2\u0513\u0511\3\2\2\2\u0514") + buf.write("\u0517\3\2\2\2\u0515\u0513\3\2\2\2\u0515\u0516\3\2\2\2") + buf.write("\u0516\u0521\3\2\2\2\u0517\u0515\3\2\2\2\u0518\u051d\5") + buf.write("\u0114\u008b\2\u0519\u051a\7\n\2\2\u051a\u051c\5\u0114") + buf.write("\u008b\2\u051b\u0519\3\2\2\2\u051c\u051f\3\2\2\2\u051d") + buf.write("\u051b\3\2\2\2\u051d\u051e\3\2\2\2\u051e\u0521\3\2\2\2") + buf.write("\u051f\u051d\3\2\2\2\u0520\u0509\3\2\2\2\u0520\u0518\3") + buf.write("\2\2\2\u0521\u0111\3\2\2\2\u0522\u0523\5\u00e2r\2\u0523") + buf.write("\u0113\3\2\2\2\u0524\u0525\5\u010e\u0088\2\u0525\u0526") + buf.write("\7\13\2\2\u0526\u0527\5\u00e2r\2\u0527\u0115\3\2\2\2\u0528") + buf.write("\u052b\7d\2\2\u0529\u052b\5\u0118\u008d\2\u052a\u0528") + buf.write("\3\2\2\2\u052a\u0529\3\2\2\2\u052b\u052c\3\2\2\2\u052c") + buf.write("\u052d\5\32\16\2\u052d\u0117\3\2\2\2\u052e\u052f\t\n\2") + buf.write("\2\u052f\u0119\3\2\2\2\u0080\u011d\u0123\u012f\u0133\u013d") + buf.write("\u014b\u0168\u016f\u017b\u017f\u0187\u018d\u019a\u01a3") + buf.write("\u01b4\u01bb\u01c3\u01c8\u01cd\u01d4\u01dd\u01e5\u01ea") + buf.write("\u01ef\u01f6\u01fd\u0204\u0206\u020b\u0210\u0218\u021d") + buf.write("\u0226\u022d\u022f\u0234\u0239\u023f\u0244\u024c\u0251") + buf.write("\u0257\u0262\u0270\u0276\u027c\u0284\u028b\u028f\u0293") + buf.write("\u0298\u02aa\u02ae\u02b4\u02b8\u02bb\u02ca\u02d3\u02ec") + buf.write("\u02f6\u02fd\u0304\u0308\u0310\u0318\u031a\u0325\u0332") + buf.write("\u0338\u033c\u0341\u0353\u0357\u035b\u0360\u036c\u0376") + buf.write("\u037c\u0384\u038b\u0390\u0393\u039b\u039f\u03a6\u03ab") + buf.write("\u03b0\u03b9\u03c0\u03d0\u03df\u03e7\u03ec\u03f5\u03fe") + buf.write("\u0402\u040a\u040f\u0414\u041d\u0422\u043e\u0444\u0451") + buf.write("\u0459\u0461\u0467\u0472\u0480\u048e\u0496\u04b1\u04b7") + buf.write("\u04b9\u04c7\u04d2\u04da\u04ec\u04f3\u04fd\u0505\u050e") + buf.write("\u0515\u051d\u0520\u052a") + return buf.getvalue() + + +class OpenSCENARIO2Parser (Parser): + + grammarFileName = "OpenSCENARIO2.g4" + + atn = ATNDeserializer().deserialize(serializedATN()) + + decisionsToDFA = [DFA(ds, i) for i, ds in enumerate(atn.decisionToState)] + + sharedContextCache = PredictionContextCache() + + literalNames = ["", "'import'", "'.'", "'type'", "'is'", "'SI'", + "'unit'", "'of'", "','", "':'", "'factor'", "'offset'", + "'kg'", "'m'", "'s'", "'A'", "'K'", "'mol'", "'cd'", + "'rad'", "'enum'", "'='", "'!'", "'=='", "'struct'", + "'inherits'", "'actor'", "'scenario'", "'action'", + "'modifier'", "'extend'", "'global'", "'list'", "'int'", + "'uint'", "'float'", "'bool'", "'string'", "'event'", + "'if'", "'@'", "'as'", "'rise'", "'fall'", "'elapsed'", + "'every'", "'var'", "'sample'", "'with'", "'keep'", + "'default'", "'hard'", "'remove_default'", "'on'", + "'do'", "'serial'", "'one_of'", "'parallel'", "'wait'", + "'emit'", "'call'", "'until'", "'def'", "'->'", "'expression'", + "'undefined'", "'external'", "'only'", "'cover'", "'record'", + "'range'", "'?'", "'=>'", "'or'", "'and'", "'not'", + "'!='", "'<'", "'<='", "'>'", "'>='", "'in'", "'+'", + "'-'", "'*'", "'/'", "'%'", "'it'", "'..'", "", + "'['", "']'", "'('", "')'"] + + symbolicNames = ["", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "", "", "", + "", "NEWLINE", "OPEN_BRACK", "CLOSE_BRACK", + "OPEN_PAREN", "CLOSE_PAREN", "SKIP_", "BLOCK_COMMENT", + "LINE_COMMENT", "StringLiteral", "FloatLiteral", "UintLiteral", + "HexUintLiteral", "IntLiteral", "BoolLiteral", "Identifier", + "INDENT", "DEDENT"] + + RULE_osc_file = 0 + RULE_preludeStatement = 1 + RULE_importStatement = 2 + RULE_importReference = 3 + RULE_structuredIdentifier = 4 + RULE_oscDeclaration = 5 + RULE_physicalTypeDeclaration = 6 + RULE_physicalTypeName = 7 + RULE_baseUnitSpecifier = 8 + RULE_sIBaseUnitSpecifier = 9 + RULE_unitDeclaration = 10 + RULE_unitSpecifier = 11 + RULE_unitName = 12 + RULE_siBaseExponentList = 13 + RULE_siBaseExponent = 14 + RULE_siUnitSpecifier = 15 + RULE_siFactor = 16 + RULE_siOffset = 17 + RULE_siBaseUnitName = 18 + RULE_enumDeclaration = 19 + RULE_enumMemberDecl = 20 + RULE_enumMemberValue = 21 + RULE_enumName = 22 + RULE_enumMemberName = 23 + RULE_enumValueReference = 24 + RULE_inheritsCondition = 25 + RULE_structDeclaration = 26 + RULE_structInherits = 27 + RULE_structMemberDecl = 28 + RULE_fieldName = 29 + RULE_structName = 30 + RULE_actorDeclaration = 31 + RULE_actorInherits = 32 + RULE_actorMemberDecl = 33 + RULE_actorName = 34 + RULE_scenarioDeclaration = 35 + RULE_scenarioInherits = 36 + RULE_scenarioMemberDecl = 37 + RULE_qualifiedBehaviorName = 38 + RULE_behaviorName = 39 + RULE_actionDeclaration = 40 + RULE_actionInherits = 41 + RULE_modifierDeclaration = 42 + RULE_modifierName = 43 + RULE_typeExtension = 44 + RULE_enumTypeExtension = 45 + RULE_structuredTypeExtension = 46 + RULE_extendableTypeName = 47 + RULE_extensionMemberDecl = 48 + RULE_globalParameterDeclaration = 49 + RULE_typeDeclarator = 50 + RULE_nonAggregateTypeDeclarator = 51 + RULE_aggregateTypeDeclarator = 52 + RULE_listTypeDeclarator = 53 + RULE_primitiveType = 54 + RULE_typeName = 55 + RULE_eventDeclaration = 56 + RULE_eventSpecification = 57 + RULE_eventReference = 58 + RULE_eventFieldDecl = 59 + RULE_eventFieldName = 60 + RULE_eventName = 61 + RULE_eventPath = 62 + RULE_eventCondition = 63 + RULE_riseExpression = 64 + RULE_fallExpression = 65 + RULE_elapsedExpression = 66 + RULE_everyExpression = 67 + RULE_boolExpression = 68 + RULE_durationExpression = 69 + RULE_fieldDeclaration = 70 + RULE_parameterDeclaration = 71 + RULE_variableDeclaration = 72 + RULE_sampleExpression = 73 + RULE_defaultValue = 74 + RULE_parameterWithDeclaration = 75 + RULE_parameterWithMember = 76 + RULE_constraintDeclaration = 77 + RULE_keepConstraintDeclaration = 78 + RULE_constraintQualifier = 79 + RULE_constraintExpression = 80 + RULE_removeDefaultDeclaration = 81 + RULE_parameterReference = 82 + RULE_modifierInvocation = 83 + RULE_behaviorExpression = 84 + RULE_behaviorSpecification = 85 + RULE_onDirective = 86 + RULE_onMember = 87 + RULE_doDirective = 88 + RULE_doMember = 89 + RULE_composition = 90 + RULE_compositionOperator = 91 + RULE_behaviorInvocation = 92 + RULE_behaviorWithDeclaration = 93 + RULE_behaviorWithMember = 94 + RULE_labelName = 95 + RULE_actorExpression = 96 + RULE_waitDirective = 97 + RULE_emitDirective = 98 + RULE_callDirective = 99 + RULE_untilDirective = 100 + RULE_methodInvocation = 101 + RULE_methodDeclaration = 102 + RULE_returnType = 103 + RULE_methodImplementation = 104 + RULE_methodQualifier = 105 + RULE_methodName = 106 + RULE_coverageDeclaration = 107 + RULE_coverDeclaration = 108 + RULE_recordDeclaration = 109 + RULE_coverageArgumentList = 110 + RULE_targetName = 111 + RULE_expression = 112 + RULE_ternaryOpExp = 113 + RULE_implication = 114 + RULE_disjunction = 115 + RULE_conjunction = 116 + RULE_inversion = 117 + RULE_relation = 118 + RULE_relationalOp = 119 + RULE_sumExpression = 120 + RULE_additiveOp = 121 + RULE_term = 122 + RULE_multiplicativeOp = 123 + RULE_factor = 124 + RULE_postfixExp = 125 + RULE_fieldAccess = 126 + RULE_primaryExp = 127 + RULE_valueExp = 128 + RULE_listConstructor = 129 + RULE_rangeConstructor = 130 + RULE_identifierReference = 131 + RULE_argumentListSpecification = 132 + RULE_argumentSpecification = 133 + RULE_argumentName = 134 + RULE_argumentList = 135 + RULE_positionalArgument = 136 + RULE_namedArgument = 137 + RULE_physicalLiteral = 138 + RULE_integerLiteral = 139 + + ruleNames = ["osc_file", "preludeStatement", "importStatement", "importReference", + "structuredIdentifier", "oscDeclaration", "physicalTypeDeclaration", + "physicalTypeName", "baseUnitSpecifier", "sIBaseUnitSpecifier", + "unitDeclaration", "unitSpecifier", "unitName", "siBaseExponentList", + "siBaseExponent", "siUnitSpecifier", "siFactor", "siOffset", + "siBaseUnitName", "enumDeclaration", "enumMemberDecl", + "enumMemberValue", "enumName", "enumMemberName", "enumValueReference", + "inheritsCondition", "structDeclaration", "structInherits", + "structMemberDecl", "fieldName", "structName", "actorDeclaration", + "actorInherits", "actorMemberDecl", "actorName", "scenarioDeclaration", + "scenarioInherits", "scenarioMemberDecl", "qualifiedBehaviorName", + "behaviorName", "actionDeclaration", "actionInherits", + "modifierDeclaration", "modifierName", "typeExtension", + "enumTypeExtension", "structuredTypeExtension", "extendableTypeName", + "extensionMemberDecl", "globalParameterDeclaration", + "typeDeclarator", "nonAggregateTypeDeclarator", "aggregateTypeDeclarator", + "listTypeDeclarator", "primitiveType", "typeName", "eventDeclaration", + "eventSpecification", "eventReference", "eventFieldDecl", + "eventFieldName", "eventName", "eventPath", "eventCondition", + "riseExpression", "fallExpression", "elapsedExpression", + "everyExpression", "boolExpression", "durationExpression", + "fieldDeclaration", "parameterDeclaration", "variableDeclaration", + "sampleExpression", "defaultValue", "parameterWithDeclaration", + "parameterWithMember", "constraintDeclaration", "keepConstraintDeclaration", + "constraintQualifier", "constraintExpression", "removeDefaultDeclaration", + "parameterReference", "modifierInvocation", "behaviorExpression", + "behaviorSpecification", "onDirective", "onMember", "doDirective", + "doMember", "composition", "compositionOperator", "behaviorInvocation", + "behaviorWithDeclaration", "behaviorWithMember", "labelName", + "actorExpression", "waitDirective", "emitDirective", + "callDirective", "untilDirective", "methodInvocation", + "methodDeclaration", "returnType", "methodImplementation", + "methodQualifier", "methodName", "coverageDeclaration", + "coverDeclaration", "recordDeclaration", "coverageArgumentList", + "targetName", "expression", "ternaryOpExp", "implication", + "disjunction", "conjunction", "inversion", "relation", + "relationalOp", "sumExpression", "additiveOp", "term", + "multiplicativeOp", "factor", "postfixExp", "fieldAccess", + "primaryExp", "valueExp", "listConstructor", "rangeConstructor", + "identifierReference", "argumentListSpecification", "argumentSpecification", + "argumentName", "argumentList", "positionalArgument", + "namedArgument", "physicalLiteral", "integerLiteral"] + + EOF = Token.EOF + T__0 = 1 + T__1 = 2 + T__2 = 3 + T__3 = 4 + T__4 = 5 + T__5 = 6 + T__6 = 7 + T__7 = 8 + T__8 = 9 + T__9 = 10 + T__10 = 11 + T__11 = 12 + T__12 = 13 + T__13 = 14 + T__14 = 15 + T__15 = 16 + T__16 = 17 + T__17 = 18 + T__18 = 19 + T__19 = 20 + T__20 = 21 + T__21 = 22 + T__22 = 23 + T__23 = 24 + T__24 = 25 + T__25 = 26 + T__26 = 27 + T__27 = 28 + T__28 = 29 + T__29 = 30 + T__30 = 31 + T__31 = 32 + T__32 = 33 + T__33 = 34 + T__34 = 35 + T__35 = 36 + T__36 = 37 + T__37 = 38 + T__38 = 39 + T__39 = 40 + T__40 = 41 + T__41 = 42 + T__42 = 43 + T__43 = 44 + T__44 = 45 + T__45 = 46 + T__46 = 47 + T__47 = 48 + T__48 = 49 + T__49 = 50 + T__50 = 51 + T__51 = 52 + T__52 = 53 + T__53 = 54 + T__54 = 55 + T__55 = 56 + T__56 = 57 + T__57 = 58 + T__58 = 59 + T__59 = 60 + T__60 = 61 + T__61 = 62 + T__62 = 63 + T__63 = 64 + T__64 = 65 + T__65 = 66 + T__66 = 67 + T__67 = 68 + T__68 = 69 + T__69 = 70 + T__70 = 71 + T__71 = 72 + T__72 = 73 + T__73 = 74 + T__74 = 75 + T__75 = 76 + T__76 = 77 + T__77 = 78 + T__78 = 79 + T__79 = 80 + T__80 = 81 + T__81 = 82 + T__82 = 83 + T__83 = 84 + T__84 = 85 + T__85 = 86 + T__86 = 87 + T__87 = 88 + NEWLINE = 89 + OPEN_BRACK = 90 + CLOSE_BRACK = 91 + OPEN_PAREN = 92 + CLOSE_PAREN = 93 + SKIP_ = 94 + BLOCK_COMMENT = 95 + LINE_COMMENT = 96 + StringLiteral = 97 + FloatLiteral = 98 + UintLiteral = 99 + HexUintLiteral = 100 + IntLiteral = 101 + BoolLiteral = 102 + Identifier = 103 + INDENT = 104 + DEDENT = 105 + + def __init__(self, input: TokenStream, output: TextIO = sys.stdout): + super().__init__(input, output) + self.checkVersion("4.7.2") + self._interp = ParserATNSimulator(self, self.atn, self.decisionsToDFA, self.sharedContextCache) + self._predicates = None + + class Osc_fileContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def EOF(self): + return self.getToken(OpenSCENARIO2Parser.EOF, 0) + + def preludeStatement(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.PreludeStatementContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.PreludeStatementContext, i) + + def oscDeclaration(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.OscDeclarationContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.OscDeclarationContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_osc_file + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOsc_file"): + listener.enterOsc_file(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOsc_file"): + listener.exitOsc_file(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOsc_file"): + return visitor.visitOsc_file(self) + else: + return visitor.visitChildren(self) + + def osc_file(self): + + localctx = OpenSCENARIO2Parser.Osc_fileContext(self, self._ctx, self.state) + self.enterRule(localctx, 0, self.RULE_osc_file) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 283 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 0, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + self.state = 280 + self.preludeStatement() + self.state = 285 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 0, self._ctx) + + self.state = 289 + self._errHandler.sync(self) + _la = self._input.LA(1) + while (((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__2) | (1 << OpenSCENARIO2Parser.T__5) | (1 << OpenSCENARIO2Parser.T__19) | (1 << OpenSCENARIO2Parser.T__23) | (1 << OpenSCENARIO2Parser.T__25) | (1 << OpenSCENARIO2Parser.T__26) | (1 << OpenSCENARIO2Parser.T__27) | (1 << OpenSCENARIO2Parser.T__28) | (1 << OpenSCENARIO2Parser.T__29) | (1 << OpenSCENARIO2Parser.T__30))) != 0) or _la == OpenSCENARIO2Parser.NEWLINE: + self.state = 286 + self.oscDeclaration() + self.state = 291 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 292 + self.match(OpenSCENARIO2Parser.EOF) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PreludeStatementContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def importStatement(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImportStatementContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_preludeStatement + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPreludeStatement"): + listener.enterPreludeStatement(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPreludeStatement"): + listener.exitPreludeStatement(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPreludeStatement"): + return visitor.visitPreludeStatement(self) + else: + return visitor.visitChildren(self) + + def preludeStatement(self): + + localctx = OpenSCENARIO2Parser.PreludeStatementContext(self, self._ctx, self.state) + self.enterRule(localctx, 2, self.RULE_preludeStatement) + try: + self.enterOuterAlt(localctx, 1) + self.state = 294 + self.importStatement() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ImportStatementContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def importReference(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImportReferenceContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_importStatement + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterImportStatement"): + listener.enterImportStatement(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitImportStatement"): + listener.exitImportStatement(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitImportStatement"): + return visitor.visitImportStatement(self) + else: + return visitor.visitChildren(self) + + def importStatement(self): + + localctx = OpenSCENARIO2Parser.ImportStatementContext(self, self._ctx, self.state) + self.enterRule(localctx, 4, self.RULE_importStatement) + try: + self.state = 301 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__0]: + self.enterOuterAlt(localctx, 1) + self.state = 296 + self.match(OpenSCENARIO2Parser.T__0) + self.state = 297 + self.importReference() + self.state = 298 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.enterOuterAlt(localctx, 2) + self.state = 300 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ImportReferenceContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def StringLiteral(self): + return self.getToken(OpenSCENARIO2Parser.StringLiteral, 0) + + def structuredIdentifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_importReference + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterImportReference"): + listener.enterImportReference(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitImportReference"): + listener.exitImportReference(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitImportReference"): + return visitor.visitImportReference(self) + else: + return visitor.visitChildren(self) + + def importReference(self): + + localctx = OpenSCENARIO2Parser.ImportReferenceContext(self, self._ctx, self.state) + self.enterRule(localctx, 6, self.RULE_importReference) + try: + self.state = 305 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.StringLiteral]: + self.enterOuterAlt(localctx, 1) + self.state = 303 + self.match(OpenSCENARIO2Parser.StringLiteral) + pass + elif token in [OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 2) + self.state = 304 + self.structuredIdentifier(0) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class StructuredIdentifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def structuredIdentifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_structuredIdentifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructuredIdentifier"): + listener.enterStructuredIdentifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructuredIdentifier"): + listener.exitStructuredIdentifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructuredIdentifier"): + return visitor.visitStructuredIdentifier(self) + else: + return visitor.visitChildren(self) + + def structuredIdentifier(self, _p: int = 0): + _parentctx = self._ctx + _parentState = self.state + localctx = OpenSCENARIO2Parser.StructuredIdentifierContext(self, self._ctx, _parentState) + _prevctx = localctx + _startState = 8 + self.enterRecursionRule(localctx, 8, self.RULE_structuredIdentifier, _p) + try: + self.enterOuterAlt(localctx, 1) + self.state = 308 + self.match(OpenSCENARIO2Parser.Identifier) + self._ctx.stop = self._input.LT(-1) + self.state = 315 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 4, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + if self._parseListeners is not None: + self.triggerExitRuleEvent() + _prevctx = localctx + localctx = OpenSCENARIO2Parser.StructuredIdentifierContext(self, _parentctx, _parentState) + self.pushNewRecursionContext(localctx, _startState, self.RULE_structuredIdentifier) + self.state = 310 + if not self.precpred(self._ctx, 1): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 1)") + self.state = 311 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 312 + self.match(OpenSCENARIO2Parser.Identifier) + self.state = 317 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 4, self._ctx) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.unrollRecursionContexts(_parentctx) + return localctx + + class OscDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def physicalTypeDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeDeclarationContext, 0) + + def unitDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitDeclarationContext, 0) + + def enumDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumDeclarationContext, 0) + + def structDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructDeclarationContext, 0) + + def actorDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorDeclarationContext, 0) + + def actionDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActionDeclarationContext, 0) + + def scenarioDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioDeclarationContext, 0) + + def modifierDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierDeclarationContext, 0) + + def typeExtension(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeExtensionContext, 0) + + def globalParameterDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.GlobalParameterDeclarationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_oscDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOscDeclaration"): + listener.enterOscDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOscDeclaration"): + listener.exitOscDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOscDeclaration"): + return visitor.visitOscDeclaration(self) + else: + return visitor.visitChildren(self) + + def oscDeclaration(self): + + localctx = OpenSCENARIO2Parser.OscDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 10, self.RULE_oscDeclaration) + try: + self.state = 329 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__2]: + self.enterOuterAlt(localctx, 1) + self.state = 318 + self.physicalTypeDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__5]: + self.enterOuterAlt(localctx, 2) + self.state = 319 + self.unitDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__19]: + self.enterOuterAlt(localctx, 3) + self.state = 320 + self.enumDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__23]: + self.enterOuterAlt(localctx, 4) + self.state = 321 + self.structDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__25]: + self.enterOuterAlt(localctx, 5) + self.state = 322 + self.actorDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__27]: + self.enterOuterAlt(localctx, 6) + self.state = 323 + self.actionDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__26]: + self.enterOuterAlt(localctx, 7) + self.state = 324 + self.scenarioDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__28]: + self.enterOuterAlt(localctx, 8) + self.state = 325 + self.modifierDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__29]: + self.enterOuterAlt(localctx, 9) + self.state = 326 + self.typeExtension() + pass + elif token in [OpenSCENARIO2Parser.T__30]: + self.enterOuterAlt(localctx, 10) + self.state = 327 + self.globalParameterDeclaration() + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.enterOuterAlt(localctx, 11) + self.state = 328 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PhysicalTypeDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def physicalTypeName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeNameContext, 0) + + def baseUnitSpecifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BaseUnitSpecifierContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_physicalTypeDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPhysicalTypeDeclaration"): + listener.enterPhysicalTypeDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPhysicalTypeDeclaration"): + listener.exitPhysicalTypeDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPhysicalTypeDeclaration"): + return visitor.visitPhysicalTypeDeclaration(self) + else: + return visitor.visitChildren(self) + + def physicalTypeDeclaration(self): + + localctx = OpenSCENARIO2Parser.PhysicalTypeDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 12, self.RULE_physicalTypeDeclaration) + try: + self.enterOuterAlt(localctx, 1) + self.state = 331 + self.match(OpenSCENARIO2Parser.T__2) + self.state = 332 + self.physicalTypeName() + self.state = 333 + self.match(OpenSCENARIO2Parser.T__3) + self.state = 334 + self.baseUnitSpecifier() + self.state = 335 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PhysicalTypeNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_physicalTypeName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPhysicalTypeName"): + listener.enterPhysicalTypeName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPhysicalTypeName"): + listener.exitPhysicalTypeName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPhysicalTypeName"): + return visitor.visitPhysicalTypeName(self) + else: + return visitor.visitChildren(self) + + def physicalTypeName(self): + + localctx = OpenSCENARIO2Parser.PhysicalTypeNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 14, self.RULE_physicalTypeName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 337 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BaseUnitSpecifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def sIBaseUnitSpecifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SIBaseUnitSpecifierContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_baseUnitSpecifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBaseUnitSpecifier"): + listener.enterBaseUnitSpecifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBaseUnitSpecifier"): + listener.exitBaseUnitSpecifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBaseUnitSpecifier"): + return visitor.visitBaseUnitSpecifier(self) + else: + return visitor.visitChildren(self) + + def baseUnitSpecifier(self): + + localctx = OpenSCENARIO2Parser.BaseUnitSpecifierContext(self, self._ctx, self.state) + self.enterRule(localctx, 16, self.RULE_baseUnitSpecifier) + try: + self.enterOuterAlt(localctx, 1) + self.state = 339 + self.sIBaseUnitSpecifier() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SIBaseUnitSpecifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def siBaseExponentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentListContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_sIBaseUnitSpecifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSIBaseUnitSpecifier"): + listener.enterSIBaseUnitSpecifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSIBaseUnitSpecifier"): + listener.exitSIBaseUnitSpecifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSIBaseUnitSpecifier"): + return visitor.visitSIBaseUnitSpecifier(self) + else: + return visitor.visitChildren(self) + + def sIBaseUnitSpecifier(self): + + localctx = OpenSCENARIO2Parser.SIBaseUnitSpecifierContext(self, self._ctx, self.state) + self.enterRule(localctx, 18, self.RULE_sIBaseUnitSpecifier) + try: + self.enterOuterAlt(localctx, 1) + self.state = 341 + self.match(OpenSCENARIO2Parser.T__4) + self.state = 342 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 343 + self.siBaseExponentList() + self.state = 344 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class UnitDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def unitName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext, 0) + + def physicalTypeName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalTypeNameContext, 0) + + def unitSpecifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitSpecifierContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_unitDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUnitDeclaration"): + listener.enterUnitDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUnitDeclaration"): + listener.exitUnitDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUnitDeclaration"): + return visitor.visitUnitDeclaration(self) + else: + return visitor.visitChildren(self) + + def unitDeclaration(self): + + localctx = OpenSCENARIO2Parser.UnitDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 20, self.RULE_unitDeclaration) + try: + self.enterOuterAlt(localctx, 1) + self.state = 346 + self.match(OpenSCENARIO2Parser.T__5) + self.state = 347 + self.unitName() + self.state = 348 + self.match(OpenSCENARIO2Parser.T__6) + self.state = 349 + self.physicalTypeName() + self.state = 350 + self.match(OpenSCENARIO2Parser.T__3) + self.state = 351 + self.unitSpecifier() + self.state = 352 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class UnitSpecifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def siUnitSpecifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiUnitSpecifierContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_unitSpecifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUnitSpecifier"): + listener.enterUnitSpecifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUnitSpecifier"): + listener.exitUnitSpecifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUnitSpecifier"): + return visitor.visitUnitSpecifier(self) + else: + return visitor.visitChildren(self) + + def unitSpecifier(self): + + localctx = OpenSCENARIO2Parser.UnitSpecifierContext(self, self._ctx, self.state) + self.enterRule(localctx, 22, self.RULE_unitSpecifier) + try: + self.enterOuterAlt(localctx, 1) + self.state = 354 + self.siUnitSpecifier() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class UnitNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def siBaseUnitName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseUnitNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_unitName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUnitName"): + listener.enterUnitName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUnitName"): + listener.exitUnitName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUnitName"): + return visitor.visitUnitName(self) + else: + return visitor.visitChildren(self) + + def unitName(self): + + localctx = OpenSCENARIO2Parser.UnitNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 24, self.RULE_unitName) + try: + self.state = 358 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 1) + self.state = 356 + self.match(OpenSCENARIO2Parser.Identifier) + pass + elif token in [OpenSCENARIO2Parser.T__11, OpenSCENARIO2Parser.T__12, OpenSCENARIO2Parser.T__13, OpenSCENARIO2Parser.T__14, OpenSCENARIO2Parser.T__15, OpenSCENARIO2Parser.T__16, OpenSCENARIO2Parser.T__17, OpenSCENARIO2Parser.T__18]: + self.enterOuterAlt(localctx, 2) + self.state = 357 + self.siBaseUnitName() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SiBaseExponentListContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def siBaseExponent(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.SiBaseExponentContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_siBaseExponentList + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiBaseExponentList"): + listener.enterSiBaseExponentList(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiBaseExponentList"): + listener.exitSiBaseExponentList(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiBaseExponentList"): + return visitor.visitSiBaseExponentList(self) + else: + return visitor.visitChildren(self) + + def siBaseExponentList(self): + + localctx = OpenSCENARIO2Parser.SiBaseExponentListContext(self, self._ctx, self.state) + self.enterRule(localctx, 26, self.RULE_siBaseExponentList) + try: + self.enterOuterAlt(localctx, 1) + self.state = 360 + self.siBaseExponent() + self.state = 365 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 7, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + self.state = 361 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 362 + self.siBaseExponent() + self.state = 367 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 7, self._ctx) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SiBaseExponentContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def siBaseUnitName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseUnitNameContext, 0) + + def integerLiteral(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_siBaseExponent + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiBaseExponent"): + listener.enterSiBaseExponent(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiBaseExponent"): + listener.exitSiBaseExponent(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiBaseExponent"): + return visitor.visitSiBaseExponent(self) + else: + return visitor.visitChildren(self) + + def siBaseExponent(self): + + localctx = OpenSCENARIO2Parser.SiBaseExponentContext(self, self._ctx, self.state) + self.enterRule(localctx, 28, self.RULE_siBaseExponent) + try: + self.enterOuterAlt(localctx, 1) + self.state = 368 + self.siBaseUnitName() + self.state = 369 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 370 + self.integerLiteral() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SiUnitSpecifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def siBaseExponentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiBaseExponentListContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def siFactor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiFactorContext, 0) + + def siOffset(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SiOffsetContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_siUnitSpecifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiUnitSpecifier"): + listener.enterSiUnitSpecifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiUnitSpecifier"): + listener.exitSiUnitSpecifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiUnitSpecifier"): + return visitor.visitSiUnitSpecifier(self) + else: + return visitor.visitChildren(self) + + def siUnitSpecifier(self): + + localctx = OpenSCENARIO2Parser.SiUnitSpecifierContext(self, self._ctx, self.state) + self.enterRule(localctx, 30, self.RULE_siUnitSpecifier) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 372 + self.match(OpenSCENARIO2Parser.T__4) + self.state = 373 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 374 + self.siBaseExponentList() + self.state = 377 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 8, self._ctx) + if la_ == 1: + self.state = 375 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 376 + self.siFactor() + + self.state = 381 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__7: + self.state = 379 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 380 + self.siOffset() + + self.state = 383 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SiFactorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def FloatLiteral(self): + return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) + + def integerLiteral(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_siFactor + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiFactor"): + listener.enterSiFactor(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiFactor"): + listener.exitSiFactor(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiFactor"): + return visitor.visitSiFactor(self) + else: + return visitor.visitChildren(self) + + def siFactor(self): + + localctx = OpenSCENARIO2Parser.SiFactorContext(self, self._ctx, self.state) + self.enterRule(localctx, 32, self.RULE_siFactor) + try: + self.enterOuterAlt(localctx, 1) + self.state = 385 + self.match(OpenSCENARIO2Parser.T__9) + self.state = 386 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 389 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.FloatLiteral]: + self.state = 387 + self.match(OpenSCENARIO2Parser.FloatLiteral) + pass + elif token in [OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral]: + self.state = 388 + self.integerLiteral() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SiOffsetContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def FloatLiteral(self): + return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) + + def integerLiteral(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_siOffset + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiOffset"): + listener.enterSiOffset(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiOffset"): + listener.exitSiOffset(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiOffset"): + return visitor.visitSiOffset(self) + else: + return visitor.visitChildren(self) + + def siOffset(self): + + localctx = OpenSCENARIO2Parser.SiOffsetContext(self, self._ctx, self.state) + self.enterRule(localctx, 34, self.RULE_siOffset) + try: + self.enterOuterAlt(localctx, 1) + self.state = 391 + self.match(OpenSCENARIO2Parser.T__10) + self.state = 392 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 395 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.FloatLiteral]: + self.state = 393 + self.match(OpenSCENARIO2Parser.FloatLiteral) + pass + elif token in [OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral]: + self.state = 394 + self.integerLiteral() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SiBaseUnitNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_siBaseUnitName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSiBaseUnitName"): + listener.enterSiBaseUnitName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSiBaseUnitName"): + listener.exitSiBaseUnitName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSiBaseUnitName"): + return visitor.visitSiBaseUnitName(self) + else: + return visitor.visitChildren(self) + + def siBaseUnitName(self): + + localctx = OpenSCENARIO2Parser.SiBaseUnitNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 36, self.RULE_siBaseUnitName) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 397 + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__11) | (1 << OpenSCENARIO2Parser.T__12) | (1 << OpenSCENARIO2Parser.T__13) | (1 << OpenSCENARIO2Parser.T__14) | (1 << OpenSCENARIO2Parser.T__15) | (1 << OpenSCENARIO2Parser.T__16) | (1 << OpenSCENARIO2Parser.T__17) | (1 << OpenSCENARIO2Parser.T__18))) != 0)): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def enumName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext, 0) + + def OPEN_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) + + def enumMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.EnumMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberDeclContext, i) + + def CLOSE_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumDeclaration"): + listener.enterEnumDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumDeclaration"): + listener.exitEnumDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumDeclaration"): + return visitor.visitEnumDeclaration(self) + else: + return visitor.visitChildren(self) + + def enumDeclaration(self): + + localctx = OpenSCENARIO2Parser.EnumDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 38, self.RULE_enumDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 399 + self.match(OpenSCENARIO2Parser.T__19) + self.state = 400 + self.enumName() + self.state = 401 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 402 + self.match(OpenSCENARIO2Parser.OPEN_BRACK) + self.state = 403 + self.enumMemberDecl() + self.state = 408 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 404 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 405 + self.enumMemberDecl() + self.state = 410 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 411 + self.match(OpenSCENARIO2Parser.CLOSE_BRACK) + self.state = 412 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumMemberDeclContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def enumMemberName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberNameContext, 0) + + def enumMemberValue(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberValueContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumMemberDecl + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumMemberDecl"): + listener.enterEnumMemberDecl(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumMemberDecl"): + listener.exitEnumMemberDecl(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumMemberDecl"): + return visitor.visitEnumMemberDecl(self) + else: + return visitor.visitChildren(self) + + def enumMemberDecl(self): + + localctx = OpenSCENARIO2Parser.EnumMemberDeclContext(self, self._ctx, self.state) + self.enterRule(localctx, 40, self.RULE_enumMemberDecl) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 414 + self.enumMemberName() + self.state = 417 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__20: + self.state = 415 + self.match(OpenSCENARIO2Parser.T__20) + self.state = 416 + self.enumMemberValue() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumMemberValueContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def UintLiteral(self): + return self.getToken(OpenSCENARIO2Parser.UintLiteral, 0) + + def HexUintLiteral(self): + return self.getToken(OpenSCENARIO2Parser.HexUintLiteral, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumMemberValue + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumMemberValue"): + listener.enterEnumMemberValue(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumMemberValue"): + listener.exitEnumMemberValue(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumMemberValue"): + return visitor.visitEnumMemberValue(self) + else: + return visitor.visitChildren(self) + + def enumMemberValue(self): + + localctx = OpenSCENARIO2Parser.EnumMemberValueContext(self, self._ctx, self.state) + self.enterRule(localctx, 42, self.RULE_enumMemberValue) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 419 + _la = self._input.LA(1) + if not (_la == OpenSCENARIO2Parser.UintLiteral or _la == OpenSCENARIO2Parser.HexUintLiteral): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumName"): + listener.enterEnumName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumName"): + listener.exitEnumName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumName"): + return visitor.visitEnumName(self) + else: + return visitor.visitChildren(self) + + def enumName(self): + + localctx = OpenSCENARIO2Parser.EnumNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 44, self.RULE_enumName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 421 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumMemberNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumMemberName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumMemberName"): + listener.enterEnumMemberName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumMemberName"): + listener.exitEnumMemberName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumMemberName"): + return visitor.visitEnumMemberName(self) + else: + return visitor.visitChildren(self) + + def enumMemberName(self): + + localctx = OpenSCENARIO2Parser.EnumMemberNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 46, self.RULE_enumMemberName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 423 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumValueReferenceContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def enumName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext, 0) + + def enumMemberName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumValueReference + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumValueReference"): + listener.enterEnumValueReference(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumValueReference"): + listener.exitEnumValueReference(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumValueReference"): + return visitor.visitEnumValueReference(self) + else: + return visitor.visitChildren(self) + + def enumValueReference(self): + + localctx = OpenSCENARIO2Parser.EnumValueReferenceContext(self, self._ctx, self.state) + self.enterRule(localctx, 48, self.RULE_enumValueReference) + try: + self.enterOuterAlt(localctx, 1) + self.state = 425 + self.enumName() + self.state = 426 + self.match(OpenSCENARIO2Parser.T__21) + self.state = 427 + self.enumMemberName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class InheritsConditionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def fieldName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def enumValueReference(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumValueReferenceContext, 0) + + def BoolLiteral(self): + return self.getToken(OpenSCENARIO2Parser.BoolLiteral, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_inheritsCondition + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterInheritsCondition"): + listener.enterInheritsCondition(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitInheritsCondition"): + listener.exitInheritsCondition(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitInheritsCondition"): + return visitor.visitInheritsCondition(self) + else: + return visitor.visitChildren(self) + + def inheritsCondition(self): + + localctx = OpenSCENARIO2Parser.InheritsConditionContext(self, self._ctx, self.state) + self.enterRule(localctx, 50, self.RULE_inheritsCondition) + try: + self.enterOuterAlt(localctx, 1) + self.state = 429 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 430 + self.fieldName() + self.state = 431 + self.match(OpenSCENARIO2Parser.T__22) + self.state = 434 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.Identifier]: + self.state = 432 + self.enumValueReference() + pass + elif token in [OpenSCENARIO2Parser.BoolLiteral]: + self.state = 433 + self.match(OpenSCENARIO2Parser.BoolLiteral) + pass + else: + raise NoViableAltException(self) + + self.state = 436 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class StructDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def structName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def structInherits(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructInheritsContext, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def structMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.StructMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructMemberDeclContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_structDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructDeclaration"): + listener.enterStructDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructDeclaration"): + listener.exitStructDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructDeclaration"): + return visitor.visitStructDeclaration(self) + else: + return visitor.visitChildren(self) + + def structDeclaration(self): + + localctx = OpenSCENARIO2Parser.StructDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 52, self.RULE_structDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 438 + self.match(OpenSCENARIO2Parser.T__23) + self.state = 439 + self.structName() + self.state = 441 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__24: + self.state = 440 + self.structInherits() + + self.state = 454 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__8]: + self.state = 443 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 444 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 445 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 447 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 446 + self.structMemberDecl() + self.state = 449 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__61))) != 0) or ((((_la - 68)) & ~0x3f) == 0 and ((1 << (_la - 68)) & ((1 << (OpenSCENARIO2Parser.T__67 - 68)) | (1 << (OpenSCENARIO2Parser.T__68 - 68)) | (1 << (OpenSCENARIO2Parser.Identifier - 68)))) != 0)): + break + + self.state = 451 + self.match(OpenSCENARIO2Parser.DEDENT) + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 453 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class StructInheritsContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def structName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructNameContext, 0) + + def inheritsCondition(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_structInherits + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructInherits"): + listener.enterStructInherits(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructInherits"): + listener.exitStructInherits(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructInherits"): + return visitor.visitStructInherits(self) + else: + return visitor.visitChildren(self) + + def structInherits(self): + + localctx = OpenSCENARIO2Parser.StructInheritsContext(self, self._ctx, self.state) + self.enterRule(localctx, 54, self.RULE_structInherits) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 456 + self.match(OpenSCENARIO2Parser.T__24) + self.state = 457 + self.structName() + self.state = 459 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 458 + self.inheritsCondition() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class StructMemberDeclContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext, 0) + + def fieldDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext, 0) + + def constraintDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) + + def methodDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext, 0) + + def coverageDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_structMemberDecl + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructMemberDecl"): + listener.enterStructMemberDecl(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructMemberDecl"): + listener.exitStructMemberDecl(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructMemberDecl"): + return visitor.visitStructMemberDecl(self) + else: + return visitor.visitChildren(self) + + def structMemberDecl(self): + + localctx = OpenSCENARIO2Parser.StructMemberDeclContext(self, self._ctx, self.state) + self.enterRule(localctx, 56, self.RULE_structMemberDecl) + try: + self.state = 466 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__37]: + self.enterOuterAlt(localctx, 1) + self.state = 461 + self.eventDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__45, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 2) + self.state = 462 + self.fieldDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__48, OpenSCENARIO2Parser.T__51]: + self.enterOuterAlt(localctx, 3) + self.state = 463 + self.constraintDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__61]: + self.enterOuterAlt(localctx, 4) + self.state = 464 + self.methodDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__67, OpenSCENARIO2Parser.T__68]: + self.enterOuterAlt(localctx, 5) + self.state = 465 + self.coverageDeclaration() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class FieldNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_fieldName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldName"): + listener.enterFieldName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldName"): + listener.exitFieldName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldName"): + return visitor.visitFieldName(self) + else: + return visitor.visitChildren(self) + + def fieldName(self): + + localctx = OpenSCENARIO2Parser.FieldNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 58, self.RULE_fieldName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 468 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class StructNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_structName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructName"): + listener.enterStructName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructName"): + listener.exitStructName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructName"): + return visitor.visitStructName(self) + else: + return visitor.visitChildren(self) + + def structName(self): + + localctx = OpenSCENARIO2Parser.StructNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 60, self.RULE_structName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 470 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActorDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def actorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def actorInherits(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorInheritsContext, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def actorMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ActorMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorMemberDeclContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actorDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorDeclaration"): + listener.enterActorDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorDeclaration"): + listener.exitActorDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorDeclaration"): + return visitor.visitActorDeclaration(self) + else: + return visitor.visitChildren(self) + + def actorDeclaration(self): + + localctx = OpenSCENARIO2Parser.ActorDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 62, self.RULE_actorDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 472 + self.match(OpenSCENARIO2Parser.T__25) + self.state = 473 + self.actorName() + self.state = 475 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__24: + self.state = 474 + self.actorInherits() + + self.state = 488 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__8]: + self.state = 477 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 478 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 479 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 481 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 480 + self.actorMemberDecl() + self.state = 483 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__61))) != 0) or ((((_la - 68)) & ~0x3f) == 0 and ((1 << (_la - 68)) & ((1 << (OpenSCENARIO2Parser.T__67 - 68)) | (1 << (OpenSCENARIO2Parser.T__68 - 68)) | (1 << (OpenSCENARIO2Parser.Identifier - 68)))) != 0)): + break + + self.state = 485 + self.match(OpenSCENARIO2Parser.DEDENT) + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 487 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActorInheritsContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def actorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) + + def inheritsCondition(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actorInherits + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorInherits"): + listener.enterActorInherits(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorInherits"): + listener.exitActorInherits(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorInherits"): + return visitor.visitActorInherits(self) + else: + return visitor.visitChildren(self) + + def actorInherits(self): + + localctx = OpenSCENARIO2Parser.ActorInheritsContext(self, self._ctx, self.state) + self.enterRule(localctx, 64, self.RULE_actorInherits) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 490 + self.match(OpenSCENARIO2Parser.T__24) + self.state = 491 + self.actorName() + self.state = 493 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 492 + self.inheritsCondition() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActorMemberDeclContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext, 0) + + def fieldDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext, 0) + + def constraintDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) + + def methodDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext, 0) + + def coverageDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actorMemberDecl + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorMemberDecl"): + listener.enterActorMemberDecl(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorMemberDecl"): + listener.exitActorMemberDecl(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorMemberDecl"): + return visitor.visitActorMemberDecl(self) + else: + return visitor.visitChildren(self) + + def actorMemberDecl(self): + + localctx = OpenSCENARIO2Parser.ActorMemberDeclContext(self, self._ctx, self.state) + self.enterRule(localctx, 66, self.RULE_actorMemberDecl) + try: + self.state = 500 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__37]: + self.enterOuterAlt(localctx, 1) + self.state = 495 + self.eventDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__45, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 2) + self.state = 496 + self.fieldDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__48, OpenSCENARIO2Parser.T__51]: + self.enterOuterAlt(localctx, 3) + self.state = 497 + self.constraintDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__61]: + self.enterOuterAlt(localctx, 4) + self.state = 498 + self.methodDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__67, OpenSCENARIO2Parser.T__68]: + self.enterOuterAlt(localctx, 5) + self.state = 499 + self.coverageDeclaration() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActorNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actorName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorName"): + listener.enterActorName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorName"): + listener.exitActorName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorName"): + return visitor.visitActorName(self) + else: + return visitor.visitChildren(self) + + def actorName(self): + + localctx = OpenSCENARIO2Parser.ActorNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 68, self.RULE_actorName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 502 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ScenarioDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def scenarioInherits(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioInheritsContext, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def scenarioMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ScenarioMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, i) + + def behaviorSpecification(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.BehaviorSpecificationContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_scenarioDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterScenarioDeclaration"): + listener.enterScenarioDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitScenarioDeclaration"): + listener.exitScenarioDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitScenarioDeclaration"): + return visitor.visitScenarioDeclaration(self) + else: + return visitor.visitChildren(self) + + def scenarioDeclaration(self): + + localctx = OpenSCENARIO2Parser.ScenarioDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 70, self.RULE_scenarioDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 504 + self.match(OpenSCENARIO2Parser.T__26) + self.state = 505 + self.qualifiedBehaviorName() + self.state = 507 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__24: + self.state = 506 + self.scenarioInherits() + + self.state = 521 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__8]: + self.state = 509 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 510 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 511 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 514 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 514 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__37, OpenSCENARIO2Parser.T__45, OpenSCENARIO2Parser.T__48, OpenSCENARIO2Parser.T__51, OpenSCENARIO2Parser.T__61, OpenSCENARIO2Parser.T__67, OpenSCENARIO2Parser.T__68, OpenSCENARIO2Parser.Identifier]: + self.state = 512 + self.scenarioMemberDecl() + pass + elif token in [OpenSCENARIO2Parser.T__52, OpenSCENARIO2Parser.T__53]: + self.state = 513 + self.behaviorSpecification() + pass + else: + raise NoViableAltException(self) + + self.state = 516 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__52) | (1 << OpenSCENARIO2Parser.T__53) | (1 << OpenSCENARIO2Parser.T__61))) != 0) or ((((_la - 68)) & ~0x3f) == 0 and ((1 << (_la - 68)) & ((1 << (OpenSCENARIO2Parser.T__67 - 68)) | (1 << (OpenSCENARIO2Parser.T__68 - 68)) | (1 << (OpenSCENARIO2Parser.Identifier - 68)))) != 0)): + break + + self.state = 518 + self.match(OpenSCENARIO2Parser.DEDENT) + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 520 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ScenarioInheritsContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def inheritsCondition(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_scenarioInherits + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterScenarioInherits"): + listener.enterScenarioInherits(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitScenarioInherits"): + listener.exitScenarioInherits(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitScenarioInherits"): + return visitor.visitScenarioInherits(self) + else: + return visitor.visitChildren(self) + + def scenarioInherits(self): + + localctx = OpenSCENARIO2Parser.ScenarioInheritsContext(self, self._ctx, self.state) + self.enterRule(localctx, 72, self.RULE_scenarioInherits) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 523 + self.match(OpenSCENARIO2Parser.T__24) + self.state = 524 + self.qualifiedBehaviorName() + self.state = 526 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 525 + self.inheritsCondition() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ScenarioMemberDeclContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventDeclarationContext, 0) + + def fieldDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldDeclarationContext, 0) + + def constraintDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) + + def methodDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodDeclarationContext, 0) + + def coverageDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) + + def modifierInvocation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierInvocationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_scenarioMemberDecl + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterScenarioMemberDecl"): + listener.enterScenarioMemberDecl(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitScenarioMemberDecl"): + listener.exitScenarioMemberDecl(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitScenarioMemberDecl"): + return visitor.visitScenarioMemberDecl(self) + else: + return visitor.visitChildren(self) + + def scenarioMemberDecl(self): + + localctx = OpenSCENARIO2Parser.ScenarioMemberDeclContext(self, self._ctx, self.state) + self.enterRule(localctx, 74, self.RULE_scenarioMemberDecl) + try: + self.state = 534 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 30, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 528 + self.eventDeclaration() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 529 + self.fieldDeclaration() + pass + + elif la_ == 3: + self.enterOuterAlt(localctx, 3) + self.state = 530 + self.constraintDeclaration() + pass + + elif la_ == 4: + self.enterOuterAlt(localctx, 4) + self.state = 531 + self.methodDeclaration() + pass + + elif la_ == 5: + self.enterOuterAlt(localctx, 5) + self.state = 532 + self.coverageDeclaration() + pass + + elif la_ == 6: + self.enterOuterAlt(localctx, 6) + self.state = 533 + self.modifierInvocation() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class QualifiedBehaviorNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def behaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext, 0) + + def actorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_qualifiedBehaviorName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterQualifiedBehaviorName"): + listener.enterQualifiedBehaviorName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitQualifiedBehaviorName"): + listener.exitQualifiedBehaviorName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitQualifiedBehaviorName"): + return visitor.visitQualifiedBehaviorName(self) + else: + return visitor.visitChildren(self) + + def qualifiedBehaviorName(self): + + localctx = OpenSCENARIO2Parser.QualifiedBehaviorNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 76, self.RULE_qualifiedBehaviorName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 539 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 31, self._ctx) + if la_ == 1: + self.state = 536 + self.actorName() + self.state = 537 + self.match(OpenSCENARIO2Parser.T__1) + + self.state = 541 + self.behaviorName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BehaviorNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_behaviorName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorName"): + listener.enterBehaviorName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorName"): + listener.exitBehaviorName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorName"): + return visitor.visitBehaviorName(self) + else: + return visitor.visitChildren(self) + + def behaviorName(self): + + localctx = OpenSCENARIO2Parser.BehaviorNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 78, self.RULE_behaviorName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 543 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActionDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def actionInherits(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActionInheritsContext, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def scenarioMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ScenarioMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, i) + + def behaviorSpecification(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.BehaviorSpecificationContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actionDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActionDeclaration"): + listener.enterActionDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActionDeclaration"): + listener.exitActionDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActionDeclaration"): + return visitor.visitActionDeclaration(self) + else: + return visitor.visitChildren(self) + + def actionDeclaration(self): + + localctx = OpenSCENARIO2Parser.ActionDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 80, self.RULE_actionDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 545 + self.match(OpenSCENARIO2Parser.T__27) + self.state = 546 + self.qualifiedBehaviorName() + self.state = 548 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__24: + self.state = 547 + self.actionInherits() + + self.state = 562 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__8]: + self.state = 550 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 551 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 552 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 555 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 555 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__37, OpenSCENARIO2Parser.T__45, OpenSCENARIO2Parser.T__48, OpenSCENARIO2Parser.T__51, OpenSCENARIO2Parser.T__61, OpenSCENARIO2Parser.T__67, OpenSCENARIO2Parser.T__68, OpenSCENARIO2Parser.Identifier]: + self.state = 553 + self.scenarioMemberDecl() + pass + elif token in [OpenSCENARIO2Parser.T__52, OpenSCENARIO2Parser.T__53]: + self.state = 554 + self.behaviorSpecification() + pass + else: + raise NoViableAltException(self) + + self.state = 557 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__52) | (1 << OpenSCENARIO2Parser.T__53) | (1 << OpenSCENARIO2Parser.T__61))) != 0) or ((((_la - 68)) & ~0x3f) == 0 and ((1 << (_la - 68)) & ((1 << (OpenSCENARIO2Parser.T__67 - 68)) | (1 << (OpenSCENARIO2Parser.T__68 - 68)) | (1 << (OpenSCENARIO2Parser.Identifier - 68)))) != 0)): + break + + self.state = 559 + self.match(OpenSCENARIO2Parser.DEDENT) + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 561 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActionInheritsContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def inheritsCondition(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.InheritsConditionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actionInherits + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActionInherits"): + listener.enterActionInherits(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActionInherits"): + listener.exitActionInherits(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActionInherits"): + return visitor.visitActionInherits(self) + else: + return visitor.visitChildren(self) + + def actionInherits(self): + + localctx = OpenSCENARIO2Parser.ActionInheritsContext(self, self._ctx, self.state) + self.enterRule(localctx, 82, self.RULE_actionInherits) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 564 + self.match(OpenSCENARIO2Parser.T__24) + self.state = 565 + self.qualifiedBehaviorName() + self.state = 567 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 566 + self.inheritsCondition() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ModifierDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def modifierName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def actorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def scenarioMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ScenarioMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_modifierDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterModifierDeclaration"): + listener.enterModifierDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitModifierDeclaration"): + listener.exitModifierDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitModifierDeclaration"): + return visitor.visitModifierDeclaration(self) + else: + return visitor.visitChildren(self) + + def modifierDeclaration(self): + + localctx = OpenSCENARIO2Parser.ModifierDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 84, self.RULE_modifierDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 569 + self.match(OpenSCENARIO2Parser.T__28) + self.state = 573 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 37, self._ctx) + if la_ == 1: + self.state = 570 + self.actorName() + self.state = 571 + self.match(OpenSCENARIO2Parser.T__1) + + self.state = 575 + self.modifierName() + self.state = 578 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__6: + self.state = 576 + self.match(OpenSCENARIO2Parser.T__6) + self.state = 577 + self.qualifiedBehaviorName() + + self.state = 591 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__8]: + self.state = 580 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 581 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 582 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 584 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 583 + self.scenarioMemberDecl() + self.state = 586 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__61))) != 0) or ((((_la - 68)) & ~0x3f) == 0 and ((1 << (_la - 68)) & ((1 << (OpenSCENARIO2Parser.T__67 - 68)) | (1 << (OpenSCENARIO2Parser.T__68 - 68)) | (1 << (OpenSCENARIO2Parser.Identifier - 68)))) != 0)): + break + + self.state = 588 + self.match(OpenSCENARIO2Parser.DEDENT) + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 590 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ModifierNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_modifierName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterModifierName"): + listener.enterModifierName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitModifierName"): + listener.exitModifierName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitModifierName"): + return visitor.visitModifierName(self) + else: + return visitor.visitChildren(self) + + def modifierName(self): + + localctx = OpenSCENARIO2Parser.ModifierNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 86, self.RULE_modifierName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 593 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class TypeExtensionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def enumTypeExtension(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumTypeExtensionContext, 0) + + def structuredTypeExtension(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredTypeExtensionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_typeExtension + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeExtension"): + listener.enterTypeExtension(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeExtension"): + listener.exitTypeExtension(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeExtension"): + return visitor.visitTypeExtension(self) + else: + return visitor.visitChildren(self) + + def typeExtension(self): + + localctx = OpenSCENARIO2Parser.TypeExtensionContext(self, self._ctx, self.state) + self.enterRule(localctx, 88, self.RULE_typeExtension) + try: + self.state = 597 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 41, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 595 + self.enumTypeExtension() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 596 + self.structuredTypeExtension() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EnumTypeExtensionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def enumName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumNameContext, 0) + + def OPEN_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) + + def enumMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.EnumMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumMemberDeclContext, i) + + def CLOSE_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_enumTypeExtension + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEnumTypeExtension"): + listener.enterEnumTypeExtension(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEnumTypeExtension"): + listener.exitEnumTypeExtension(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEnumTypeExtension"): + return visitor.visitEnumTypeExtension(self) + else: + return visitor.visitChildren(self) + + def enumTypeExtension(self): + + localctx = OpenSCENARIO2Parser.EnumTypeExtensionContext(self, self._ctx, self.state) + self.enterRule(localctx, 90, self.RULE_enumTypeExtension) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 599 + self.match(OpenSCENARIO2Parser.T__29) + self.state = 600 + self.enumName() + self.state = 601 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 602 + self.match(OpenSCENARIO2Parser.OPEN_BRACK) + self.state = 603 + self.enumMemberDecl() + self.state = 608 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 604 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 605 + self.enumMemberDecl() + self.state = 610 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 611 + self.match(OpenSCENARIO2Parser.CLOSE_BRACK) + self.state = 612 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class StructuredTypeExtensionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def extendableTypeName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExtendableTypeNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def extensionMemberDecl(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExtensionMemberDeclContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExtensionMemberDeclContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_structuredTypeExtension + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterStructuredTypeExtension"): + listener.enterStructuredTypeExtension(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitStructuredTypeExtension"): + listener.exitStructuredTypeExtension(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitStructuredTypeExtension"): + return visitor.visitStructuredTypeExtension(self) + else: + return visitor.visitChildren(self) + + def structuredTypeExtension(self): + + localctx = OpenSCENARIO2Parser.StructuredTypeExtensionContext(self, self._ctx, self.state) + self.enterRule(localctx, 92, self.RULE_structuredTypeExtension) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 614 + self.match(OpenSCENARIO2Parser.T__29) + self.state = 615 + self.extendableTypeName() + self.state = 616 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 617 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 618 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 620 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 619 + self.extensionMemberDecl() + self.state = 622 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__37) | (1 << OpenSCENARIO2Parser.T__45) | (1 << OpenSCENARIO2Parser.T__48) | (1 << OpenSCENARIO2Parser.T__51) | (1 << OpenSCENARIO2Parser.T__52) | (1 << OpenSCENARIO2Parser.T__53) | (1 << OpenSCENARIO2Parser.T__61))) != 0) or ((((_la - 68)) & ~0x3f) == 0 and ((1 << (_la - 68)) & ((1 << (OpenSCENARIO2Parser.T__67 - 68)) | (1 << (OpenSCENARIO2Parser.T__68 - 68)) | (1 << (OpenSCENARIO2Parser.Identifier - 68)))) != 0)): + break + + self.state = 624 + self.match(OpenSCENARIO2Parser.DEDENT) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ExtendableTypeNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def typeName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeNameContext, 0) + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_extendableTypeName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterExtendableTypeName"): + listener.enterExtendableTypeName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitExtendableTypeName"): + listener.exitExtendableTypeName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitExtendableTypeName"): + return visitor.visitExtendableTypeName(self) + else: + return visitor.visitChildren(self) + + def extendableTypeName(self): + + localctx = OpenSCENARIO2Parser.ExtendableTypeNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 94, self.RULE_extendableTypeName) + try: + self.state = 628 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 44, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 626 + self.typeName() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 627 + self.qualifiedBehaviorName() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ExtensionMemberDeclContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def structMemberDecl(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructMemberDeclContext, 0) + + def actorMemberDecl(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorMemberDeclContext, 0) + + def scenarioMemberDecl(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ScenarioMemberDeclContext, 0) + + def behaviorSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorSpecificationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_extensionMemberDecl + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterExtensionMemberDecl"): + listener.enterExtensionMemberDecl(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitExtensionMemberDecl"): + listener.exitExtensionMemberDecl(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitExtensionMemberDecl"): + return visitor.visitExtensionMemberDecl(self) + else: + return visitor.visitChildren(self) + + def extensionMemberDecl(self): + + localctx = OpenSCENARIO2Parser.ExtensionMemberDeclContext(self, self._ctx, self.state) + self.enterRule(localctx, 96, self.RULE_extensionMemberDecl) + try: + self.state = 634 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 45, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 630 + self.structMemberDecl() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 631 + self.actorMemberDecl() + pass + + elif la_ == 3: + self.enterOuterAlt(localctx, 3) + self.state = 632 + self.scenarioMemberDecl() + pass + + elif la_ == 4: + self.enterOuterAlt(localctx, 4) + self.state = 633 + self.behaviorSpecification() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class GlobalParameterDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def fieldName(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def parameterWithDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithDeclarationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def defaultValue(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_globalParameterDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterGlobalParameterDeclaration"): + listener.enterGlobalParameterDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitGlobalParameterDeclaration"): + listener.exitGlobalParameterDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitGlobalParameterDeclaration"): + return visitor.visitGlobalParameterDeclaration(self) + else: + return visitor.visitChildren(self) + + def globalParameterDeclaration(self): + + localctx = OpenSCENARIO2Parser.GlobalParameterDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 98, self.RULE_globalParameterDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 636 + self.match(OpenSCENARIO2Parser.T__30) + self.state = 637 + self.fieldName() + self.state = 642 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 638 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 639 + self.fieldName() + self.state = 644 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 645 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 646 + self.typeDeclarator() + self.state = 649 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__20: + self.state = 647 + self.match(OpenSCENARIO2Parser.T__20) + self.state = 648 + self.defaultValue() + + self.state = 653 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__47]: + self.state = 651 + self.parameterWithDeclaration() + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 652 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class TypeDeclaratorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def nonAggregateTypeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext, 0) + + def aggregateTypeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.AggregateTypeDeclaratorContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_typeDeclarator + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeDeclarator"): + listener.enterTypeDeclarator(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeDeclarator"): + listener.exitTypeDeclarator(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeDeclarator"): + return visitor.visitTypeDeclarator(self) + else: + return visitor.visitChildren(self) + + def typeDeclarator(self): + + localctx = OpenSCENARIO2Parser.TypeDeclaratorContext(self, self._ctx, self.state) + self.enterRule(localctx, 100, self.RULE_typeDeclarator) + try: + self.state = 657 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__32, OpenSCENARIO2Parser.T__33, OpenSCENARIO2Parser.T__34, OpenSCENARIO2Parser.T__35, OpenSCENARIO2Parser.T__36, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 1) + self.state = 655 + self.nonAggregateTypeDeclarator() + pass + elif token in [OpenSCENARIO2Parser.T__31]: + self.enterOuterAlt(localctx, 2) + self.state = 656 + self.aggregateTypeDeclarator() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class NonAggregateTypeDeclaratorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def primitiveType(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PrimitiveTypeContext, 0) + + def typeName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeNameContext, 0) + + def qualifiedBehaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.QualifiedBehaviorNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_nonAggregateTypeDeclarator + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterNonAggregateTypeDeclarator"): + listener.enterNonAggregateTypeDeclarator(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitNonAggregateTypeDeclarator"): + listener.exitNonAggregateTypeDeclarator(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitNonAggregateTypeDeclarator"): + return visitor.visitNonAggregateTypeDeclarator(self) + else: + return visitor.visitChildren(self) + + def nonAggregateTypeDeclarator(self): + + localctx = OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext(self, self._ctx, self.state) + self.enterRule(localctx, 102, self.RULE_nonAggregateTypeDeclarator) + try: + self.state = 662 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 50, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 659 + self.primitiveType() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 660 + self.typeName() + pass + + elif la_ == 3: + self.enterOuterAlt(localctx, 3) + self.state = 661 + self.qualifiedBehaviorName() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class AggregateTypeDeclaratorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def listTypeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ListTypeDeclaratorContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_aggregateTypeDeclarator + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterAggregateTypeDeclarator"): + listener.enterAggregateTypeDeclarator(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitAggregateTypeDeclarator"): + listener.exitAggregateTypeDeclarator(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitAggregateTypeDeclarator"): + return visitor.visitAggregateTypeDeclarator(self) + else: + return visitor.visitChildren(self) + + def aggregateTypeDeclarator(self): + + localctx = OpenSCENARIO2Parser.AggregateTypeDeclaratorContext(self, self._ctx, self.state) + self.enterRule(localctx, 104, self.RULE_aggregateTypeDeclarator) + try: + self.enterOuterAlt(localctx, 1) + self.state = 664 + self.listTypeDeclarator() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ListTypeDeclaratorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def nonAggregateTypeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_listTypeDeclarator + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterListTypeDeclarator"): + listener.enterListTypeDeclarator(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitListTypeDeclarator"): + listener.exitListTypeDeclarator(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitListTypeDeclarator"): + return visitor.visitListTypeDeclarator(self) + else: + return visitor.visitChildren(self) + + def listTypeDeclarator(self): + + localctx = OpenSCENARIO2Parser.ListTypeDeclaratorContext(self, self._ctx, self.state) + self.enterRule(localctx, 106, self.RULE_listTypeDeclarator) + try: + self.enterOuterAlt(localctx, 1) + self.state = 666 + self.match(OpenSCENARIO2Parser.T__31) + self.state = 667 + self.match(OpenSCENARIO2Parser.T__6) + self.state = 668 + self.nonAggregateTypeDeclarator() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PrimitiveTypeContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_primitiveType + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPrimitiveType"): + listener.enterPrimitiveType(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPrimitiveType"): + listener.exitPrimitiveType(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPrimitiveType"): + return visitor.visitPrimitiveType(self) + else: + return visitor.visitChildren(self) + + def primitiveType(self): + + localctx = OpenSCENARIO2Parser.PrimitiveTypeContext(self, self._ctx, self.state) + self.enterRule(localctx, 108, self.RULE_primitiveType) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 670 + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__32) | (1 << OpenSCENARIO2Parser.T__33) | (1 << OpenSCENARIO2Parser.T__34) | (1 << OpenSCENARIO2Parser.T__35) | (1 << OpenSCENARIO2Parser.T__36))) != 0)): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class TypeNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_typeName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeName"): + listener.enterTypeName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeName"): + listener.exitTypeName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeName"): + return visitor.visitTypeName(self) + else: + return visitor.visitChildren(self) + + def typeName(self): + + localctx = OpenSCENARIO2Parser.TypeNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 110, self.RULE_typeName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 672 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def argumentListSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListSpecificationContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def eventSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventDeclaration"): + listener.enterEventDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventDeclaration"): + listener.exitEventDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventDeclaration"): + return visitor.visitEventDeclaration(self) + else: + return visitor.visitChildren(self) + + def eventDeclaration(self): + + localctx = OpenSCENARIO2Parser.EventDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 112, self.RULE_eventDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 674 + self.match(OpenSCENARIO2Parser.T__37) + self.state = 675 + self.eventName() + self.state = 680 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 676 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 677 + self.argumentListSpecification() + self.state = 678 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + + self.state = 684 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__3: + self.state = 682 + self.match(OpenSCENARIO2Parser.T__3) + self.state = 683 + self.eventSpecification() + + self.state = 686 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventSpecificationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventReference(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventReferenceContext, 0) + + def eventCondition(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventConditionContext, 0) + + def eventFieldDecl(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventFieldDeclContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventSpecification + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventSpecification"): + listener.enterEventSpecification(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventSpecification"): + listener.exitEventSpecification(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventSpecification"): + return visitor.visitEventSpecification(self) + else: + return visitor.visitChildren(self) + + def eventSpecification(self): + + localctx = OpenSCENARIO2Parser.EventSpecificationContext(self, self._ctx, self.state) + self.enterRule(localctx, 114, self.RULE_eventSpecification) + self._la = 0 # Token type + try: + self.state = 697 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__39]: + self.enterOuterAlt(localctx, 1) + self.state = 688 + self.eventReference() + self.state = 694 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__38 or _la == OpenSCENARIO2Parser.T__40: + self.state = 690 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__40: + self.state = 689 + self.eventFieldDecl() + + self.state = 692 + self.match(OpenSCENARIO2Parser.T__38) + self.state = 693 + self.eventCondition() + + pass + elif token in [OpenSCENARIO2Parser.T__41, OpenSCENARIO2Parser.T__42, OpenSCENARIO2Parser.T__43, OpenSCENARIO2Parser.T__44, OpenSCENARIO2Parser.T__69, OpenSCENARIO2Parser.T__74, OpenSCENARIO2Parser.T__82, OpenSCENARIO2Parser.T__86, OpenSCENARIO2Parser.OPEN_BRACK, OpenSCENARIO2Parser.OPEN_PAREN, OpenSCENARIO2Parser.StringLiteral, OpenSCENARIO2Parser.FloatLiteral, OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral, OpenSCENARIO2Parser.BoolLiteral, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 2) + self.state = 696 + self.eventCondition() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventReferenceContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventPath(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventPathContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventReference + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventReference"): + listener.enterEventReference(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventReference"): + listener.exitEventReference(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventReference"): + return visitor.visitEventReference(self) + else: + return visitor.visitChildren(self) + + def eventReference(self): + + localctx = OpenSCENARIO2Parser.EventReferenceContext(self, self._ctx, self.state) + self.enterRule(localctx, 116, self.RULE_eventReference) + try: + self.enterOuterAlt(localctx, 1) + self.state = 699 + self.match(OpenSCENARIO2Parser.T__39) + self.state = 700 + self.eventPath() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventFieldDeclContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventFieldName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventFieldNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventFieldDecl + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventFieldDecl"): + listener.enterEventFieldDecl(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventFieldDecl"): + listener.exitEventFieldDecl(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventFieldDecl"): + return visitor.visitEventFieldDecl(self) + else: + return visitor.visitChildren(self) + + def eventFieldDecl(self): + + localctx = OpenSCENARIO2Parser.EventFieldDeclContext(self, self._ctx, self.state) + self.enterRule(localctx, 118, self.RULE_eventFieldDecl) + try: + self.enterOuterAlt(localctx, 1) + self.state = 702 + self.match(OpenSCENARIO2Parser.T__40) + self.state = 703 + self.eventFieldName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventFieldNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventFieldName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventFieldName"): + listener.enterEventFieldName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventFieldName"): + listener.exitEventFieldName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventFieldName"): + return visitor.visitEventFieldName(self) + else: + return visitor.visitChildren(self) + + def eventFieldName(self): + + localctx = OpenSCENARIO2Parser.EventFieldNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 120, self.RULE_eventFieldName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 705 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventName"): + listener.enterEventName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventName"): + listener.exitEventName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventName"): + return visitor.visitEventName(self) + else: + return visitor.visitChildren(self) + + def eventName(self): + + localctx = OpenSCENARIO2Parser.EventNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 122, self.RULE_eventName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 707 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventPathContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventPath + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventPath"): + listener.enterEventPath(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventPath"): + listener.exitEventPath(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventPath"): + return visitor.visitEventPath(self) + else: + return visitor.visitChildren(self) + + def eventPath(self): + + localctx = OpenSCENARIO2Parser.EventPathContext(self, self._ctx, self.state) + self.enterRule(localctx, 124, self.RULE_eventPath) + try: + self.enterOuterAlt(localctx, 1) + self.state = 712 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 56, self._ctx) + if la_ == 1: + self.state = 709 + self.expression() + self.state = 710 + self.match(OpenSCENARIO2Parser.T__1) + + self.state = 714 + self.eventName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EventConditionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def boolExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext, 0) + + def riseExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RiseExpressionContext, 0) + + def fallExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FallExpressionContext, 0) + + def elapsedExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ElapsedExpressionContext, 0) + + def everyExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EveryExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_eventCondition + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEventCondition"): + listener.enterEventCondition(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEventCondition"): + listener.exitEventCondition(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEventCondition"): + return visitor.visitEventCondition(self) + else: + return visitor.visitChildren(self) + + def eventCondition(self): + + localctx = OpenSCENARIO2Parser.EventConditionContext(self, self._ctx, self.state) + self.enterRule(localctx, 126, self.RULE_eventCondition) + try: + self.state = 721 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__69, OpenSCENARIO2Parser.T__74, OpenSCENARIO2Parser.T__82, OpenSCENARIO2Parser.T__86, OpenSCENARIO2Parser.OPEN_BRACK, OpenSCENARIO2Parser.OPEN_PAREN, OpenSCENARIO2Parser.StringLiteral, OpenSCENARIO2Parser.FloatLiteral, OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral, OpenSCENARIO2Parser.BoolLiteral, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 1) + self.state = 716 + self.boolExpression() + pass + elif token in [OpenSCENARIO2Parser.T__41]: + self.enterOuterAlt(localctx, 2) + self.state = 717 + self.riseExpression() + pass + elif token in [OpenSCENARIO2Parser.T__42]: + self.enterOuterAlt(localctx, 3) + self.state = 718 + self.fallExpression() + pass + elif token in [OpenSCENARIO2Parser.T__43]: + self.enterOuterAlt(localctx, 4) + self.state = 719 + self.elapsedExpression() + pass + elif token in [OpenSCENARIO2Parser.T__44]: + self.enterOuterAlt(localctx, 5) + self.state = 720 + self.everyExpression() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class RiseExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def boolExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_riseExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRiseExpression"): + listener.enterRiseExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRiseExpression"): + listener.exitRiseExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRiseExpression"): + return visitor.visitRiseExpression(self) + else: + return visitor.visitChildren(self) + + def riseExpression(self): + + localctx = OpenSCENARIO2Parser.RiseExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 128, self.RULE_riseExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 723 + self.match(OpenSCENARIO2Parser.T__41) + self.state = 724 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 725 + self.boolExpression() + self.state = 726 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class FallExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def boolExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BoolExpressionContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_fallExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFallExpression"): + listener.enterFallExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFallExpression"): + listener.exitFallExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFallExpression"): + return visitor.visitFallExpression(self) + else: + return visitor.visitChildren(self) + + def fallExpression(self): + + localctx = OpenSCENARIO2Parser.FallExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 130, self.RULE_fallExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 728 + self.match(OpenSCENARIO2Parser.T__42) + self.state = 729 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 730 + self.boolExpression() + self.state = 731 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ElapsedExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def durationExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DurationExpressionContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_elapsedExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterElapsedExpression"): + listener.enterElapsedExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitElapsedExpression"): + listener.exitElapsedExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitElapsedExpression"): + return visitor.visitElapsedExpression(self) + else: + return visitor.visitChildren(self) + + def elapsedExpression(self): + + localctx = OpenSCENARIO2Parser.ElapsedExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 132, self.RULE_elapsedExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 733 + self.match(OpenSCENARIO2Parser.T__43) + self.state = 734 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 735 + self.durationExpression() + self.state = 736 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EveryExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + self._Identifier = None # Token + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def durationExpression(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.DurationExpressionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.DurationExpressionContext, i) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_everyExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEveryExpression"): + listener.enterEveryExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEveryExpression"): + listener.exitEveryExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEveryExpression"): + return visitor.visitEveryExpression(self) + else: + return visitor.visitChildren(self) + + def everyExpression(self): + + localctx = OpenSCENARIO2Parser.EveryExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 134, self.RULE_everyExpression) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 738 + self.match(OpenSCENARIO2Parser.T__44) + self.state = 739 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 740 + self.durationExpression() + self.state = 746 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__7: + self.state = 741 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 742 + localctx._Identifier = self.match(OpenSCENARIO2Parser.Identifier) + + offsetName = (None if localctx._Identifier is None else localctx._Identifier.text) + if (not (offsetName == "offset")): + print("%s must be offset" % offsetName) + raise NoViableAltException(self) + + self.state = 744 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 745 + self.durationExpression() + + self.state = 748 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BoolExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_boolExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBoolExpression"): + listener.enterBoolExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBoolExpression"): + listener.exitBoolExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBoolExpression"): + return visitor.visitBoolExpression(self) + else: + return visitor.visitChildren(self) + + def boolExpression(self): + + localctx = OpenSCENARIO2Parser.BoolExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 136, self.RULE_boolExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 750 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class DurationExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_durationExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDurationExpression"): + listener.enterDurationExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDurationExpression"): + listener.exitDurationExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDurationExpression"): + return visitor.visitDurationExpression(self) + else: + return visitor.visitChildren(self) + + def durationExpression(self): + + localctx = OpenSCENARIO2Parser.DurationExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 138, self.RULE_durationExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 752 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class FieldDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def parameterDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterDeclarationContext, 0) + + def variableDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.VariableDeclarationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_fieldDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldDeclaration"): + listener.enterFieldDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldDeclaration"): + listener.exitFieldDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldDeclaration"): + return visitor.visitFieldDeclaration(self) + else: + return visitor.visitChildren(self) + + def fieldDeclaration(self): + + localctx = OpenSCENARIO2Parser.FieldDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 140, self.RULE_fieldDeclaration) + try: + self.state = 756 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 1) + self.state = 754 + self.parameterDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__45]: + self.enterOuterAlt(localctx, 2) + self.state = 755 + self.variableDeclaration() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ParameterDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def fieldName(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def parameterWithDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithDeclarationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def defaultValue(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_parameterDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterDeclaration"): + listener.enterParameterDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterDeclaration"): + listener.exitParameterDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterDeclaration"): + return visitor.visitParameterDeclaration(self) + else: + return visitor.visitChildren(self) + + def parameterDeclaration(self): + + localctx = OpenSCENARIO2Parser.ParameterDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 142, self.RULE_parameterDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 758 + self.fieldName() + self.state = 763 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 759 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 760 + self.fieldName() + self.state = 765 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 766 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 767 + self.typeDeclarator() + self.state = 770 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__20: + self.state = 768 + self.match(OpenSCENARIO2Parser.T__20) + self.state = 769 + self.defaultValue() + + self.state = 774 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__47]: + self.state = 772 + self.parameterWithDeclaration() + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 773 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class VariableDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def fieldName(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def sampleExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SampleExpressionContext, 0) + + def valueExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_variableDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterVariableDeclaration"): + listener.enterVariableDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitVariableDeclaration"): + listener.exitVariableDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitVariableDeclaration"): + return visitor.visitVariableDeclaration(self) + else: + return visitor.visitChildren(self) + + def variableDeclaration(self): + + localctx = OpenSCENARIO2Parser.VariableDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 144, self.RULE_variableDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 776 + self.match(OpenSCENARIO2Parser.T__45) + self.state = 777 + self.fieldName() + self.state = 782 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 778 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 779 + self.fieldName() + self.state = 784 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 785 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 786 + self.typeDeclarator() + self.state = 792 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__20: + self.state = 787 + self.match(OpenSCENARIO2Parser.T__20) + self.state = 790 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__46]: + self.state = 788 + self.sampleExpression() + pass + elif token in [OpenSCENARIO2Parser.T__69, OpenSCENARIO2Parser.OPEN_BRACK, OpenSCENARIO2Parser.StringLiteral, OpenSCENARIO2Parser.FloatLiteral, OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral, OpenSCENARIO2Parser.BoolLiteral, OpenSCENARIO2Parser.Identifier]: + self.state = 789 + self.valueExp() + pass + else: + raise NoViableAltException(self) + + self.state = 794 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SampleExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def eventSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def defaultValue(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_sampleExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSampleExpression"): + listener.enterSampleExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSampleExpression"): + listener.exitSampleExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSampleExpression"): + return visitor.visitSampleExpression(self) + else: + return visitor.visitChildren(self) + + def sampleExpression(self): + + localctx = OpenSCENARIO2Parser.SampleExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 146, self.RULE_sampleExpression) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 796 + self.match(OpenSCENARIO2Parser.T__46) + self.state = 797 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 798 + self.expression() + self.state = 799 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 800 + self.eventSpecification() + self.state = 803 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__7: + self.state = 801 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 802 + self.defaultValue() + + self.state = 805 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class DefaultValueContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_defaultValue + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDefaultValue"): + listener.enterDefaultValue(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDefaultValue"): + listener.exitDefaultValue(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDefaultValue"): + return visitor.visitDefaultValue(self) + else: + return visitor.visitChildren(self) + + def defaultValue(self): + + localctx = OpenSCENARIO2Parser.DefaultValueContext(self, self._ctx, self.state) + self.enterRule(localctx, 148, self.RULE_defaultValue) + try: + self.enterOuterAlt(localctx, 1) + self.state = 807 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ParameterWithDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def parameterWithMember(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ParameterWithMemberContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterWithMemberContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_parameterWithDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterWithDeclaration"): + listener.enterParameterWithDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterWithDeclaration"): + listener.exitParameterWithDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterWithDeclaration"): + return visitor.visitParameterWithDeclaration(self) + else: + return visitor.visitChildren(self) + + def parameterWithDeclaration(self): + + localctx = OpenSCENARIO2Parser.ParameterWithDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 150, self.RULE_parameterWithDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 809 + self.match(OpenSCENARIO2Parser.T__47) + self.state = 810 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 811 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 812 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 814 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 813 + self.parameterWithMember() + self.state = 816 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not (((((_la - 49)) & ~0x3f) == 0 and ((1 << (_la - 49)) & ((1 << (OpenSCENARIO2Parser.T__48 - 49)) | (1 << (OpenSCENARIO2Parser.T__51 - 49)) | (1 << (OpenSCENARIO2Parser.T__67 - 49)) | (1 << (OpenSCENARIO2Parser.T__68 - 49)))) != 0)): + break + + self.state = 818 + self.match(OpenSCENARIO2Parser.DEDENT) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ParameterWithMemberContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def constraintDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) + + def coverageDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageDeclarationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_parameterWithMember + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterWithMember"): + listener.enterParameterWithMember(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterWithMember"): + listener.exitParameterWithMember(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterWithMember"): + return visitor.visitParameterWithMember(self) + else: + return visitor.visitChildren(self) + + def parameterWithMember(self): + + localctx = OpenSCENARIO2Parser.ParameterWithMemberContext(self, self._ctx, self.state) + self.enterRule(localctx, 152, self.RULE_parameterWithMember) + try: + self.state = 822 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__48, OpenSCENARIO2Parser.T__51]: + self.enterOuterAlt(localctx, 1) + self.state = 820 + self.constraintDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__67, OpenSCENARIO2Parser.T__68]: + self.enterOuterAlt(localctx, 2) + self.state = 821 + self.coverageDeclaration() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ConstraintDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def keepConstraintDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.KeepConstraintDeclarationContext, 0) + + def removeDefaultDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RemoveDefaultDeclarationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_constraintDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConstraintDeclaration"): + listener.enterConstraintDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConstraintDeclaration"): + listener.exitConstraintDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConstraintDeclaration"): + return visitor.visitConstraintDeclaration(self) + else: + return visitor.visitChildren(self) + + def constraintDeclaration(self): + + localctx = OpenSCENARIO2Parser.ConstraintDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 154, self.RULE_constraintDeclaration) + try: + self.state = 826 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__48]: + self.enterOuterAlt(localctx, 1) + self.state = 824 + self.keepConstraintDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__51]: + self.enterOuterAlt(localctx, 2) + self.state = 825 + self.removeDefaultDeclaration() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class KeepConstraintDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def constraintExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintExpressionContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def constraintQualifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintQualifierContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_keepConstraintDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterKeepConstraintDeclaration"): + listener.enterKeepConstraintDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitKeepConstraintDeclaration"): + listener.exitKeepConstraintDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitKeepConstraintDeclaration"): + return visitor.visitKeepConstraintDeclaration(self) + else: + return visitor.visitChildren(self) + + def keepConstraintDeclaration(self): + + localctx = OpenSCENARIO2Parser.KeepConstraintDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 156, self.RULE_keepConstraintDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 828 + self.match(OpenSCENARIO2Parser.T__48) + self.state = 829 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 831 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__49 or _la == OpenSCENARIO2Parser.T__50: + self.state = 830 + self.constraintQualifier() + + self.state = 833 + self.constraintExpression() + self.state = 834 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 835 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ConstraintQualifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_constraintQualifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConstraintQualifier"): + listener.enterConstraintQualifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConstraintQualifier"): + listener.exitConstraintQualifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConstraintQualifier"): + return visitor.visitConstraintQualifier(self) + else: + return visitor.visitChildren(self) + + def constraintQualifier(self): + + localctx = OpenSCENARIO2Parser.ConstraintQualifierContext(self, self._ctx, self.state) + self.enterRule(localctx, 158, self.RULE_constraintQualifier) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 837 + _la = self._input.LA(1) + if not (_la == OpenSCENARIO2Parser.T__49 or _la == OpenSCENARIO2Parser.T__50): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ConstraintExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_constraintExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConstraintExpression"): + listener.enterConstraintExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConstraintExpression"): + listener.exitConstraintExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConstraintExpression"): + return visitor.visitConstraintExpression(self) + else: + return visitor.visitChildren(self) + + def constraintExpression(self): + + localctx = OpenSCENARIO2Parser.ConstraintExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 160, self.RULE_constraintExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 839 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class RemoveDefaultDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def parameterReference(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ParameterReferenceContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_removeDefaultDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRemoveDefaultDeclaration"): + listener.enterRemoveDefaultDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRemoveDefaultDeclaration"): + listener.exitRemoveDefaultDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRemoveDefaultDeclaration"): + return visitor.visitRemoveDefaultDeclaration(self) + else: + return visitor.visitChildren(self) + + def removeDefaultDeclaration(self): + + localctx = OpenSCENARIO2Parser.RemoveDefaultDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 162, self.RULE_removeDefaultDeclaration) + try: + self.enterOuterAlt(localctx, 1) + self.state = 841 + self.match(OpenSCENARIO2Parser.T__51) + self.state = 842 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 843 + self.parameterReference() + self.state = 844 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 845 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ParameterReferenceContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def fieldName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) + + def fieldAccess(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldAccessContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_parameterReference + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterParameterReference"): + listener.enterParameterReference(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitParameterReference"): + listener.exitParameterReference(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitParameterReference"): + return visitor.visitParameterReference(self) + else: + return visitor.visitChildren(self) + + def parameterReference(self): + + localctx = OpenSCENARIO2Parser.ParameterReferenceContext(self, self._ctx, self.state) + self.enterRule(localctx, 164, self.RULE_parameterReference) + try: + self.state = 849 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 71, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 847 + self.fieldName() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 848 + self.fieldAccess() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ModifierInvocationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def modifierName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierNameContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def behaviorExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorExpressionContext, 0) + + def actorExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_modifierInvocation + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterModifierInvocation"): + listener.enterModifierInvocation(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitModifierInvocation"): + listener.exitModifierInvocation(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitModifierInvocation"): + return visitor.visitModifierInvocation(self) + else: + return visitor.visitChildren(self) + + def modifierInvocation(self): + + localctx = OpenSCENARIO2Parser.ModifierInvocationContext(self, self._ctx, self.state) + self.enterRule(localctx, 166, self.RULE_modifierInvocation) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 857 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 73, self._ctx) + if la_ == 1: + self.state = 853 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 72, self._ctx) + if la_ == 1: + self.state = 851 + self.behaviorExpression() + pass + + elif la_ == 2: + self.state = 852 + self.actorExpression() + pass + + self.state = 855 + self.match(OpenSCENARIO2Parser.T__1) + + self.state = 859 + self.modifierName() + self.state = 860 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 862 + self._errHandler.sync(self) + _la = self._input.LA(1) + if ((((_la - 70)) & ~0x3f) == 0 and ((1 << (_la - 70)) & ((1 << (OpenSCENARIO2Parser.T__69 - 70)) | (1 << (OpenSCENARIO2Parser.T__74 - 70)) | (1 << (OpenSCENARIO2Parser.T__82 - 70)) | (1 << (OpenSCENARIO2Parser.T__86 - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_BRACK - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_PAREN - 70)) | (1 << (OpenSCENARIO2Parser.StringLiteral - 70)) | (1 << (OpenSCENARIO2Parser.FloatLiteral - 70)) | (1 << (OpenSCENARIO2Parser.UintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 70)) | (1 << (OpenSCENARIO2Parser.BoolLiteral - 70)) | (1 << (OpenSCENARIO2Parser.Identifier - 70)))) != 0): + self.state = 861 + self.argumentList() + + self.state = 864 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 865 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BehaviorExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def behaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext, 0) + + def actorExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_behaviorExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorExpression"): + listener.enterBehaviorExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorExpression"): + listener.exitBehaviorExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorExpression"): + return visitor.visitBehaviorExpression(self) + else: + return visitor.visitChildren(self) + + def behaviorExpression(self): + + localctx = OpenSCENARIO2Parser.BehaviorExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 168, self.RULE_behaviorExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 867 + self.actorExpression() + self.state = 868 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 870 + self.behaviorName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BehaviorSpecificationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def onDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.OnDirectiveContext, 0) + + def doDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DoDirectiveContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_behaviorSpecification + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorSpecification"): + listener.enterBehaviorSpecification(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorSpecification"): + listener.exitBehaviorSpecification(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorSpecification"): + return visitor.visitBehaviorSpecification(self) + else: + return visitor.visitChildren(self) + + def behaviorSpecification(self): + + localctx = OpenSCENARIO2Parser.BehaviorSpecificationContext(self, self._ctx, self.state) + self.enterRule(localctx, 170, self.RULE_behaviorSpecification) + try: + self.state = 874 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__52]: + self.enterOuterAlt(localctx, 1) + self.state = 872 + self.onDirective() + pass + elif token in [OpenSCENARIO2Parser.T__53]: + self.enterOuterAlt(localctx, 2) + self.state = 873 + self.doDirective() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class OnDirectiveContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def onMember(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.OnMemberContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.OnMemberContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_onDirective + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOnDirective"): + listener.enterOnDirective(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOnDirective"): + listener.exitOnDirective(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOnDirective"): + return visitor.visitOnDirective(self) + else: + return visitor.visitChildren(self) + + def onDirective(self): + + localctx = OpenSCENARIO2Parser.OnDirectiveContext(self, self._ctx, self.state) + self.enterRule(localctx, 172, self.RULE_onDirective) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 876 + self.match(OpenSCENARIO2Parser.T__52) + self.state = 877 + self.eventSpecification() + self.state = 878 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 879 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 880 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 882 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 881 + self.onMember() + self.state = 884 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not (_la == OpenSCENARIO2Parser.T__58 or _la == OpenSCENARIO2Parser.T__59): + break + + self.state = 886 + self.match(OpenSCENARIO2Parser.DEDENT) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class OnMemberContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def callDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CallDirectiveContext, 0) + + def emitDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EmitDirectiveContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_onMember + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterOnMember"): + listener.enterOnMember(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitOnMember"): + listener.exitOnMember(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitOnMember"): + return visitor.visitOnMember(self) + else: + return visitor.visitChildren(self) + + def onMember(self): + + localctx = OpenSCENARIO2Parser.OnMemberContext(self, self._ctx, self.state) + self.enterRule(localctx, 174, self.RULE_onMember) + try: + self.state = 890 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__59]: + self.enterOuterAlt(localctx, 1) + self.state = 888 + self.callDirective() + pass + elif token in [OpenSCENARIO2Parser.T__58]: + self.enterOuterAlt(localctx, 2) + self.state = 889 + self.emitDirective() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class DoDirectiveContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def doMember(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DoMemberContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_doDirective + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDoDirective"): + listener.enterDoDirective(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDoDirective"): + listener.exitDoDirective(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDoDirective"): + return visitor.visitDoDirective(self) + else: + return visitor.visitChildren(self) + + def doDirective(self): + + localctx = OpenSCENARIO2Parser.DoDirectiveContext(self, self._ctx, self.state) + self.enterRule(localctx, 176, self.RULE_doDirective) + try: + self.enterOuterAlt(localctx, 1) + self.state = 892 + self.match(OpenSCENARIO2Parser.T__53) + self.state = 893 + self.doMember() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class DoMemberContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def composition(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CompositionContext, 0) + + def behaviorInvocation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorInvocationContext, 0) + + def waitDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.WaitDirectiveContext, 0) + + def emitDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EmitDirectiveContext, 0) + + def callDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CallDirectiveContext, 0) + + def labelName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.LabelNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_doMember + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDoMember"): + listener.enterDoMember(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDoMember"): + listener.exitDoMember(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDoMember"): + return visitor.visitDoMember(self) + else: + return visitor.visitChildren(self) + + def doMember(self): + + localctx = OpenSCENARIO2Parser.DoMemberContext(self, self._ctx, self.state) + self.enterRule(localctx, 178, self.RULE_doMember) + try: + self.enterOuterAlt(localctx, 1) + self.state = 898 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 78, self._ctx) + if la_ == 1: + self.state = 895 + self.labelName() + self.state = 896 + self.match(OpenSCENARIO2Parser.T__8) + + self.state = 905 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__54, OpenSCENARIO2Parser.T__55, OpenSCENARIO2Parser.T__56]: + self.state = 900 + self.composition() + pass + elif token in [OpenSCENARIO2Parser.Identifier]: + self.state = 901 + self.behaviorInvocation() + pass + elif token in [OpenSCENARIO2Parser.T__57]: + self.state = 902 + self.waitDirective() + pass + elif token in [OpenSCENARIO2Parser.T__58]: + self.state = 903 + self.emitDirective() + pass + elif token in [OpenSCENARIO2Parser.T__59]: + self.state = 904 + self.callDirective() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class CompositionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def compositionOperator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CompositionOperatorContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def doMember(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.DoMemberContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.DoMemberContext, i) + + def behaviorWithDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithDeclarationContext, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_composition + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterComposition"): + listener.enterComposition(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitComposition"): + listener.exitComposition(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitComposition"): + return visitor.visitComposition(self) + else: + return visitor.visitChildren(self) + + def composition(self): + + localctx = OpenSCENARIO2Parser.CompositionContext(self, self._ctx, self.state) + self.enterRule(localctx, 180, self.RULE_composition) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 907 + self.compositionOperator() + self.state = 913 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 908 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 910 + self._errHandler.sync(self) + _la = self._input.LA(1) + if ((((_la - 70)) & ~0x3f) == 0 and ((1 << (_la - 70)) & ((1 << (OpenSCENARIO2Parser.T__69 - 70)) | (1 << (OpenSCENARIO2Parser.T__74 - 70)) | (1 << (OpenSCENARIO2Parser.T__82 - 70)) | (1 << (OpenSCENARIO2Parser.T__86 - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_BRACK - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_PAREN - 70)) | (1 << (OpenSCENARIO2Parser.StringLiteral - 70)) | (1 << (OpenSCENARIO2Parser.FloatLiteral - 70)) | (1 << (OpenSCENARIO2Parser.UintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 70)) | (1 << (OpenSCENARIO2Parser.BoolLiteral - 70)) | (1 << (OpenSCENARIO2Parser.Identifier - 70)))) != 0): + self.state = 909 + self.argumentList() + + self.state = 912 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + + self.state = 915 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 916 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 917 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 919 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 918 + self.doMember() + self.state = 921 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not (((((_la - 55)) & ~0x3f) == 0 and ((1 << (_la - 55)) & ((1 << (OpenSCENARIO2Parser.T__54 - 55)) | (1 << (OpenSCENARIO2Parser.T__55 - 55)) | (1 << (OpenSCENARIO2Parser.T__56 - 55)) | (1 << (OpenSCENARIO2Parser.T__57 - 55)) | (1 << (OpenSCENARIO2Parser.T__58 - 55)) | (1 << (OpenSCENARIO2Parser.T__59 - 55)) | (1 << (OpenSCENARIO2Parser.Identifier - 55)))) != 0)): + break + + self.state = 923 + self.match(OpenSCENARIO2Parser.DEDENT) + self.state = 925 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__47: + self.state = 924 + self.behaviorWithDeclaration() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class CompositionOperatorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_compositionOperator + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCompositionOperator"): + listener.enterCompositionOperator(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCompositionOperator"): + listener.exitCompositionOperator(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCompositionOperator"): + return visitor.visitCompositionOperator(self) + else: + return visitor.visitChildren(self) + + def compositionOperator(self): + + localctx = OpenSCENARIO2Parser.CompositionOperatorContext(self, self._ctx, self.state) + self.enterRule(localctx, 182, self.RULE_compositionOperator) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 927 + _la = self._input.LA(1) + if not ((((_la) & ~0x3f) == 0 and ((1 << _la) & ((1 << OpenSCENARIO2Parser.T__54) | (1 << OpenSCENARIO2Parser.T__55) | (1 << OpenSCENARIO2Parser.T__56))) != 0)): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BehaviorInvocationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def behaviorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorNameContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def behaviorWithDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithDeclarationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def actorExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorExpressionContext, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_behaviorInvocation + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorInvocation"): + listener.enterBehaviorInvocation(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorInvocation"): + listener.exitBehaviorInvocation(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorInvocation"): + return visitor.visitBehaviorInvocation(self) + else: + return visitor.visitChildren(self) + + def behaviorInvocation(self): + + localctx = OpenSCENARIO2Parser.BehaviorInvocationContext(self, self._ctx, self.state) + self.enterRule(localctx, 184, self.RULE_behaviorInvocation) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 932 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 84, self._ctx) + if la_ == 1: + self.state = 929 + self.actorExpression() + self.state = 930 + self.match(OpenSCENARIO2Parser.T__1) + + self.state = 934 + self.behaviorName() + self.state = 935 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 937 + self._errHandler.sync(self) + _la = self._input.LA(1) + if ((((_la - 70)) & ~0x3f) == 0 and ((1 << (_la - 70)) & ((1 << (OpenSCENARIO2Parser.T__69 - 70)) | (1 << (OpenSCENARIO2Parser.T__74 - 70)) | (1 << (OpenSCENARIO2Parser.T__82 - 70)) | (1 << (OpenSCENARIO2Parser.T__86 - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_BRACK - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_PAREN - 70)) | (1 << (OpenSCENARIO2Parser.StringLiteral - 70)) | (1 << (OpenSCENARIO2Parser.FloatLiteral - 70)) | (1 << (OpenSCENARIO2Parser.UintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 70)) | (1 << (OpenSCENARIO2Parser.BoolLiteral - 70)) | (1 << (OpenSCENARIO2Parser.Identifier - 70)))) != 0): + self.state = 936 + self.argumentList() + + self.state = 939 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 942 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__47]: + self.state = 940 + self.behaviorWithDeclaration() + pass + elif token in [OpenSCENARIO2Parser.NEWLINE]: + self.state = 941 + self.match(OpenSCENARIO2Parser.NEWLINE) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BehaviorWithDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def INDENT(self): + return self.getToken(OpenSCENARIO2Parser.INDENT, 0) + + def DEDENT(self): + return self.getToken(OpenSCENARIO2Parser.DEDENT, 0) + + def behaviorWithMember(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.BehaviorWithMemberContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.BehaviorWithMemberContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_behaviorWithDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorWithDeclaration"): + listener.enterBehaviorWithDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorWithDeclaration"): + listener.exitBehaviorWithDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorWithDeclaration"): + return visitor.visitBehaviorWithDeclaration(self) + else: + return visitor.visitChildren(self) + + def behaviorWithDeclaration(self): + + localctx = OpenSCENARIO2Parser.BehaviorWithDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 186, self.RULE_behaviorWithDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 944 + self.match(OpenSCENARIO2Parser.T__47) + self.state = 945 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 946 + self.match(OpenSCENARIO2Parser.NEWLINE) + self.state = 947 + self.match(OpenSCENARIO2Parser.INDENT) + self.state = 949 + self._errHandler.sync(self) + _la = self._input.LA(1) + while True: + self.state = 948 + self.behaviorWithMember() + self.state = 951 + self._errHandler.sync(self) + _la = self._input.LA(1) + if not (((((_la - 49)) & ~0x3f) == 0 and ((1 << (_la - 49)) & ((1 << (OpenSCENARIO2Parser.T__48 - 49)) | (1 << (OpenSCENARIO2Parser.T__51 - 49)) | (1 << (OpenSCENARIO2Parser.T__60 - 49)) | (1 << (OpenSCENARIO2Parser.Identifier - 49)))) != 0)): + break + + self.state = 953 + self.match(OpenSCENARIO2Parser.DEDENT) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class BehaviorWithMemberContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def constraintDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConstraintDeclarationContext, 0) + + def modifierInvocation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ModifierInvocationContext, 0) + + def untilDirective(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.UntilDirectiveContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_behaviorWithMember + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterBehaviorWithMember"): + listener.enterBehaviorWithMember(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitBehaviorWithMember"): + listener.exitBehaviorWithMember(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitBehaviorWithMember"): + return visitor.visitBehaviorWithMember(self) + else: + return visitor.visitChildren(self) + + def behaviorWithMember(self): + + localctx = OpenSCENARIO2Parser.BehaviorWithMemberContext(self, self._ctx, self.state) + self.enterRule(localctx, 188, self.RULE_behaviorWithMember) + try: + self.state = 958 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__48, OpenSCENARIO2Parser.T__51]: + self.enterOuterAlt(localctx, 1) + self.state = 955 + self.constraintDeclaration() + pass + elif token in [OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 2) + self.state = 956 + self.modifierInvocation() + pass + elif token in [OpenSCENARIO2Parser.T__60]: + self.enterOuterAlt(localctx, 3) + self.state = 957 + self.untilDirective() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class LabelNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_labelName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterLabelName"): + listener.enterLabelName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitLabelName"): + listener.exitLabelName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitLabelName"): + return visitor.visitLabelName(self) + else: + return visitor.visitChildren(self) + + def labelName(self): + + localctx = OpenSCENARIO2Parser.LabelNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 190, self.RULE_labelName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 960 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ActorExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def actorName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ActorNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_actorExpression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterActorExpression"): + listener.enterActorExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitActorExpression"): + listener.exitActorExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitActorExpression"): + return visitor.visitActorExpression(self) + else: + return visitor.visitChildren(self) + + def actorExpression(self): + + localctx = OpenSCENARIO2Parser.ActorExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 192, self.RULE_actorExpression) + try: + self.enterOuterAlt(localctx, 1) + self.state = 962 + self.actorName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class WaitDirectiveContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_waitDirective + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterWaitDirective"): + listener.enterWaitDirective(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitWaitDirective"): + listener.exitWaitDirective(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitWaitDirective"): + return visitor.visitWaitDirective(self) + else: + return visitor.visitChildren(self) + + def waitDirective(self): + + localctx = OpenSCENARIO2Parser.WaitDirectiveContext(self, self._ctx, self.state) + self.enterRule(localctx, 194, self.RULE_waitDirective) + try: + self.enterOuterAlt(localctx, 1) + self.state = 964 + self.match(OpenSCENARIO2Parser.T__57) + self.state = 965 + self.eventSpecification() + self.state = 966 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class EmitDirectiveContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_emitDirective + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterEmitDirective"): + listener.enterEmitDirective(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitEmitDirective"): + listener.exitEmitDirective(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitEmitDirective"): + return visitor.visitEmitDirective(self) + else: + return visitor.visitChildren(self) + + def emitDirective(self): + + localctx = OpenSCENARIO2Parser.EmitDirectiveContext(self, self._ctx, self.state) + self.enterRule(localctx, 196, self.RULE_emitDirective) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 968 + self.match(OpenSCENARIO2Parser.T__58) + self.state = 969 + self.eventName() + self.state = 974 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.OPEN_PAREN: + self.state = 970 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 971 + self.argumentList() + self.state = 972 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + + self.state = 976 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class CallDirectiveContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def methodInvocation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodInvocationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_callDirective + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCallDirective"): + listener.enterCallDirective(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCallDirective"): + listener.exitCallDirective(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCallDirective"): + return visitor.visitCallDirective(self) + else: + return visitor.visitChildren(self) + + def callDirective(self): + + localctx = OpenSCENARIO2Parser.CallDirectiveContext(self, self._ctx, self.state) + self.enterRule(localctx, 198, self.RULE_callDirective) + try: + self.enterOuterAlt(localctx, 1) + self.state = 978 + self.match(OpenSCENARIO2Parser.T__59) + self.state = 979 + self.methodInvocation() + self.state = 980 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class UntilDirectiveContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def eventSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventSpecificationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_untilDirective + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterUntilDirective"): + listener.enterUntilDirective(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitUntilDirective"): + listener.exitUntilDirective(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitUntilDirective"): + return visitor.visitUntilDirective(self) + else: + return visitor.visitChildren(self) + + def untilDirective(self): + + localctx = OpenSCENARIO2Parser.UntilDirectiveContext(self, self._ctx, self.state) + self.enterRule(localctx, 200, self.RULE_untilDirective) + try: + self.enterOuterAlt(localctx, 1) + self.state = 982 + self.match(OpenSCENARIO2Parser.T__60) + self.state = 983 + self.eventSpecification() + self.state = 984 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class MethodInvocationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_methodInvocation + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodInvocation"): + listener.enterMethodInvocation(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodInvocation"): + listener.exitMethodInvocation(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodInvocation"): + return visitor.visitMethodInvocation(self) + else: + return visitor.visitChildren(self) + + def methodInvocation(self): + + localctx = OpenSCENARIO2Parser.MethodInvocationContext(self, self._ctx, self.state) + self.enterRule(localctx, 202, self.RULE_methodInvocation) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 986 + self.postfixExp(0) + self.state = 987 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 989 + self._errHandler.sync(self) + _la = self._input.LA(1) + if ((((_la - 70)) & ~0x3f) == 0 and ((1 << (_la - 70)) & ((1 << (OpenSCENARIO2Parser.T__69 - 70)) | (1 << (OpenSCENARIO2Parser.T__74 - 70)) | (1 << (OpenSCENARIO2Parser.T__82 - 70)) | (1 << (OpenSCENARIO2Parser.T__86 - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_BRACK - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_PAREN - 70)) | (1 << (OpenSCENARIO2Parser.StringLiteral - 70)) | (1 << (OpenSCENARIO2Parser.FloatLiteral - 70)) | (1 << (OpenSCENARIO2Parser.UintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 70)) | (1 << (OpenSCENARIO2Parser.BoolLiteral - 70)) | (1 << (OpenSCENARIO2Parser.Identifier - 70)))) != 0): + self.state = 988 + self.argumentList() + + self.state = 991 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class MethodDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def methodName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodNameContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def methodImplementation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodImplementationContext, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def argumentListSpecification(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListSpecificationContext, 0) + + def returnType(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ReturnTypeContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_methodDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodDeclaration"): + listener.enterMethodDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodDeclaration"): + listener.exitMethodDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodDeclaration"): + return visitor.visitMethodDeclaration(self) + else: + return visitor.visitChildren(self) + + def methodDeclaration(self): + + localctx = OpenSCENARIO2Parser.MethodDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 204, self.RULE_methodDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 993 + self.match(OpenSCENARIO2Parser.T__61) + self.state = 994 + self.methodName() + self.state = 995 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 997 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.Identifier: + self.state = 996 + self.argumentListSpecification() + + self.state = 999 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 1002 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__62: + self.state = 1000 + self.match(OpenSCENARIO2Parser.T__62) + self.state = 1001 + self.returnType() + + self.state = 1004 + self.methodImplementation() + self.state = 1005 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ReturnTypeContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_returnType + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterReturnType"): + listener.enterReturnType(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitReturnType"): + listener.exitReturnType(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitReturnType"): + return visitor.visitReturnType(self) + else: + return visitor.visitChildren(self) + + def returnType(self): + + localctx = OpenSCENARIO2Parser.ReturnTypeContext(self, self._ctx, self.state) + self.enterRule(localctx, 206, self.RULE_returnType) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1007 + self.typeDeclarator() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class MethodImplementationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def structuredIdentifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.StructuredIdentifierContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def methodQualifier(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MethodQualifierContext, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_methodImplementation + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodImplementation"): + listener.enterMethodImplementation(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodImplementation"): + listener.exitMethodImplementation(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodImplementation"): + return visitor.visitMethodImplementation(self) + else: + return visitor.visitChildren(self) + + def methodImplementation(self): + + localctx = OpenSCENARIO2Parser.MethodImplementationContext(self, self._ctx, self.state) + self.enterRule(localctx, 208, self.RULE_methodImplementation) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1009 + self.match(OpenSCENARIO2Parser.T__3) + self.state = 1011 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__66: + self.state = 1010 + self.methodQualifier() + + self.state = 1024 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__63]: + self.state = 1013 + self.match(OpenSCENARIO2Parser.T__63) + self.state = 1014 + self.expression() + pass + elif token in [OpenSCENARIO2Parser.T__64]: + self.state = 1015 + self.match(OpenSCENARIO2Parser.T__64) + pass + elif token in [OpenSCENARIO2Parser.T__65]: + self.state = 1016 + self.match(OpenSCENARIO2Parser.T__65) + self.state = 1017 + self.structuredIdentifier(0) + self.state = 1018 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1020 + self._errHandler.sync(self) + _la = self._input.LA(1) + if ((((_la - 70)) & ~0x3f) == 0 and ((1 << (_la - 70)) & ((1 << (OpenSCENARIO2Parser.T__69 - 70)) | (1 << (OpenSCENARIO2Parser.T__74 - 70)) | (1 << (OpenSCENARIO2Parser.T__82 - 70)) | (1 << (OpenSCENARIO2Parser.T__86 - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_BRACK - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_PAREN - 70)) | (1 << (OpenSCENARIO2Parser.StringLiteral - 70)) | (1 << (OpenSCENARIO2Parser.FloatLiteral - 70)) | (1 << (OpenSCENARIO2Parser.UintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 70)) | (1 << (OpenSCENARIO2Parser.BoolLiteral - 70)) | (1 << (OpenSCENARIO2Parser.Identifier - 70)))) != 0): + self.state = 1019 + self.argumentList() + + self.state = 1022 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class MethodQualifierContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_methodQualifier + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodQualifier"): + listener.enterMethodQualifier(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodQualifier"): + listener.exitMethodQualifier(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodQualifier"): + return visitor.visitMethodQualifier(self) + else: + return visitor.visitChildren(self) + + def methodQualifier(self): + + localctx = OpenSCENARIO2Parser.MethodQualifierContext(self, self._ctx, self.state) + self.enterRule(localctx, 210, self.RULE_methodQualifier) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1026 + self.match(OpenSCENARIO2Parser.T__66) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class MethodNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_methodName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMethodName"): + listener.enterMethodName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMethodName"): + listener.exitMethodName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMethodName"): + return visitor.visitMethodName(self) + else: + return visitor.visitChildren(self) + + def methodName(self): + + localctx = OpenSCENARIO2Parser.MethodNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 212, self.RULE_methodName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1028 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class CoverageDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def coverDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverDeclarationContext, 0) + + def recordDeclaration(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RecordDeclarationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_coverageDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageDeclaration"): + listener.enterCoverageDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageDeclaration"): + listener.exitCoverageDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageDeclaration"): + return visitor.visitCoverageDeclaration(self) + else: + return visitor.visitChildren(self) + + def coverageDeclaration(self): + + localctx = OpenSCENARIO2Parser.CoverageDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 214, self.RULE_coverageDeclaration) + try: + self.state = 1032 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__67]: + self.enterOuterAlt(localctx, 1) + self.state = 1030 + self.coverDeclaration() + pass + elif token in [OpenSCENARIO2Parser.T__68]: + self.enterOuterAlt(localctx, 2) + self.state = 1031 + self.recordDeclaration() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class CoverDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def targetName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TargetNameContext, 0) + + def coverageArgumentList(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.CoverageArgumentListContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageArgumentListContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_coverDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverDeclaration"): + listener.enterCoverDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverDeclaration"): + listener.exitCoverDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverDeclaration"): + return visitor.visitCoverDeclaration(self) + else: + return visitor.visitChildren(self) + + def coverDeclaration(self): + + localctx = OpenSCENARIO2Parser.CoverDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 216, self.RULE_coverDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1034 + self.match(OpenSCENARIO2Parser.T__67) + self.state = 1035 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1037 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.Identifier: + self.state = 1036 + self.targetName() + + self.state = 1042 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 1039 + self.coverageArgumentList() + self.state = 1044 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 1045 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 1046 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class RecordDeclarationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def NEWLINE(self): + return self.getToken(OpenSCENARIO2Parser.NEWLINE, 0) + + def targetName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TargetNameContext, 0) + + def coverageArgumentList(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.CoverageArgumentListContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.CoverageArgumentListContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_recordDeclaration + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRecordDeclaration"): + listener.enterRecordDeclaration(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRecordDeclaration"): + listener.exitRecordDeclaration(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRecordDeclaration"): + return visitor.visitRecordDeclaration(self) + else: + return visitor.visitChildren(self) + + def recordDeclaration(self): + + localctx = OpenSCENARIO2Parser.RecordDeclarationContext(self, self._ctx, self.state) + self.enterRule(localctx, 218, self.RULE_recordDeclaration) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1048 + self.match(OpenSCENARIO2Parser.T__68) + self.state = 1049 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1051 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.Identifier: + self.state = 1050 + self.targetName() + + self.state = 1056 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 1053 + self.coverageArgumentList() + self.state = 1058 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 1059 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + self.state = 1060 + self.match(OpenSCENARIO2Parser.NEWLINE) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class CoverageArgumentListContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_coverageArgumentList + + def copyFrom(self, ctx: ParserRuleContext): + super().copyFrom(ctx) + + class CoverageEventContext(CoverageArgumentListContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + super().__init__(parser) + self.copyFrom(ctx) + + def eventName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EventNameContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageEvent"): + listener.enterCoverageEvent(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageEvent"): + listener.exitCoverageEvent(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageEvent"): + return visitor.visitCoverageEvent(self) + else: + return visitor.visitChildren(self) + + class CoverageEveryContext(CoverageArgumentListContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + super().__init__(parser) + self.copyFrom(ctx) + + def valueExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageEvery"): + listener.enterCoverageEvery(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageEvery"): + listener.exitCoverageEvery(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageEvery"): + return visitor.visitCoverageEvery(self) + else: + return visitor.visitChildren(self) + + class CoverageNameArgumentContext(CoverageArgumentListContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + super().__init__(parser) + self.copyFrom(ctx) + + def namedArgument(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.NamedArgumentContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageNameArgument"): + listener.enterCoverageNameArgument(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageNameArgument"): + listener.exitCoverageNameArgument(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageNameArgument"): + return visitor.visitCoverageNameArgument(self) + else: + return visitor.visitChildren(self) + + class CoverageExpressionContext(CoverageArgumentListContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + super().__init__(parser) + self.copyFrom(ctx) + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageExpression"): + listener.enterCoverageExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageExpression"): + listener.exitCoverageExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageExpression"): + return visitor.visitCoverageExpression(self) + else: + return visitor.visitChildren(self) + + class CoverageRangeContext(CoverageArgumentListContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + super().__init__(parser) + self.copyFrom(ctx) + + def rangeConstructor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RangeConstructorContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageRange"): + listener.enterCoverageRange(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageRange"): + listener.exitCoverageRange(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageRange"): + return visitor.visitCoverageRange(self) + else: + return visitor.visitChildren(self) + + class CoverageUnitContext(CoverageArgumentListContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.CoverageArgumentListContext + super().__init__(parser) + self.copyFrom(ctx) + + def unitName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCoverageUnit"): + listener.enterCoverageUnit(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCoverageUnit"): + listener.exitCoverageUnit(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCoverageUnit"): + return visitor.visitCoverageUnit(self) + else: + return visitor.visitChildren(self) + + def coverageArgumentList(self): + + localctx = OpenSCENARIO2Parser.CoverageArgumentListContext(self, self._ctx, self.state) + self.enterRule(localctx, 220, self.RULE_coverageArgumentList) + try: + self.state = 1084 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 101, self._ctx) + if la_ == 1: + localctx = OpenSCENARIO2Parser.CoverageExpressionContext(self, localctx) + self.enterOuterAlt(localctx, 1) + self.state = 1062 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1063 + self.match(OpenSCENARIO2Parser.T__63) + self.state = 1064 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1065 + self.expression() + pass + + elif la_ == 2: + localctx = OpenSCENARIO2Parser.CoverageUnitContext(self, localctx) + self.enterOuterAlt(localctx, 2) + self.state = 1066 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1067 + self.match(OpenSCENARIO2Parser.T__5) + self.state = 1068 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1069 + self.unitName() + pass + + elif la_ == 3: + localctx = OpenSCENARIO2Parser.CoverageRangeContext(self, localctx) + self.enterOuterAlt(localctx, 3) + self.state = 1070 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1071 + self.match(OpenSCENARIO2Parser.T__69) + self.state = 1072 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1073 + self.rangeConstructor() + pass + + elif la_ == 4: + localctx = OpenSCENARIO2Parser.CoverageEveryContext(self, localctx) + self.enterOuterAlt(localctx, 4) + self.state = 1074 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1075 + self.match(OpenSCENARIO2Parser.T__44) + self.state = 1076 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1077 + self.valueExp() + pass + + elif la_ == 5: + localctx = OpenSCENARIO2Parser.CoverageEventContext(self, localctx) + self.enterOuterAlt(localctx, 5) + self.state = 1078 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1079 + self.match(OpenSCENARIO2Parser.T__37) + self.state = 1080 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1081 + self.eventName() + pass + + elif la_ == 6: + localctx = OpenSCENARIO2Parser.CoverageNameArgumentContext(self, localctx) + self.enterOuterAlt(localctx, 6) + self.state = 1082 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1083 + self.namedArgument() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class TargetNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_targetName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTargetName"): + listener.enterTargetName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTargetName"): + listener.exitTargetName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTargetName"): + return visitor.visitTargetName(self) + else: + return visitor.visitChildren(self) + + def targetName(self): + + localctx = OpenSCENARIO2Parser.TargetNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 222, self.RULE_targetName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1086 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def implication(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImplicationContext, 0) + + def ternaryOpExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TernaryOpExpContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_expression + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterExpression"): + listener.enterExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitExpression"): + listener.exitExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitExpression"): + return visitor.visitExpression(self) + else: + return visitor.visitChildren(self) + + def expression(self): + + localctx = OpenSCENARIO2Parser.ExpressionContext(self, self._ctx, self.state) + self.enterRule(localctx, 224, self.RULE_expression) + try: + self.state = 1090 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 102, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 1088 + self.implication() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 1089 + self.ternaryOpExp() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class TernaryOpExpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def implication(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ImplicationContext, 0) + + def expression(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExpressionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_ternaryOpExp + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTernaryOpExp"): + listener.enterTernaryOpExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTernaryOpExp"): + listener.exitTernaryOpExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTernaryOpExp"): + return visitor.visitTernaryOpExp(self) + else: + return visitor.visitChildren(self) + + def ternaryOpExp(self): + + localctx = OpenSCENARIO2Parser.TernaryOpExpContext(self, self._ctx, self.state) + self.enterRule(localctx, 226, self.RULE_ternaryOpExp) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1092 + self.implication() + self.state = 1093 + self.match(OpenSCENARIO2Parser.T__70) + self.state = 1094 + self.expression() + self.state = 1095 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1096 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ImplicationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def disjunction(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.DisjunctionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.DisjunctionContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_implication + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterImplication"): + listener.enterImplication(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitImplication"): + listener.exitImplication(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitImplication"): + return visitor.visitImplication(self) + else: + return visitor.visitChildren(self) + + def implication(self): + + localctx = OpenSCENARIO2Parser.ImplicationContext(self, self._ctx, self.state) + self.enterRule(localctx, 228, self.RULE_implication) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1098 + self.disjunction() + self.state = 1103 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__71: + self.state = 1099 + self.match(OpenSCENARIO2Parser.T__71) + self.state = 1100 + self.disjunction() + self.state = 1105 + self._errHandler.sync(self) + _la = self._input.LA(1) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class DisjunctionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def conjunction(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ConjunctionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ConjunctionContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_disjunction + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterDisjunction"): + listener.enterDisjunction(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitDisjunction"): + listener.exitDisjunction(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitDisjunction"): + return visitor.visitDisjunction(self) + else: + return visitor.visitChildren(self) + + def disjunction(self): + + localctx = OpenSCENARIO2Parser.DisjunctionContext(self, self._ctx, self.state) + self.enterRule(localctx, 230, self.RULE_disjunction) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1106 + self.conjunction() + self.state = 1111 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__72: + self.state = 1107 + self.match(OpenSCENARIO2Parser.T__72) + self.state = 1108 + self.conjunction() + self.state = 1113 + self._errHandler.sync(self) + _la = self._input.LA(1) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ConjunctionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def inversion(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.InversionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.InversionContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_conjunction + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterConjunction"): + listener.enterConjunction(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitConjunction"): + listener.exitConjunction(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitConjunction"): + return visitor.visitConjunction(self) + else: + return visitor.visitChildren(self) + + def conjunction(self): + + localctx = OpenSCENARIO2Parser.ConjunctionContext(self, self._ctx, self.state) + self.enterRule(localctx, 232, self.RULE_conjunction) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1114 + self.inversion() + self.state = 1119 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__73: + self.state = 1115 + self.match(OpenSCENARIO2Parser.T__73) + self.state = 1116 + self.inversion() + self.state = 1121 + self._errHandler.sync(self) + _la = self._input.LA(1) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class InversionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def inversion(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.InversionContext, 0) + + def relation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_inversion + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterInversion"): + listener.enterInversion(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitInversion"): + listener.exitInversion(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitInversion"): + return visitor.visitInversion(self) + else: + return visitor.visitChildren(self) + + def inversion(self): + + localctx = OpenSCENARIO2Parser.InversionContext(self, self._ctx, self.state) + self.enterRule(localctx, 234, self.RULE_inversion) + try: + self.state = 1125 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__74]: + self.enterOuterAlt(localctx, 1) + self.state = 1122 + self.match(OpenSCENARIO2Parser.T__74) + self.state = 1123 + self.inversion() + pass + elif token in [OpenSCENARIO2Parser.T__69, OpenSCENARIO2Parser.T__82, OpenSCENARIO2Parser.T__86, OpenSCENARIO2Parser.OPEN_BRACK, OpenSCENARIO2Parser.OPEN_PAREN, OpenSCENARIO2Parser.StringLiteral, OpenSCENARIO2Parser.FloatLiteral, OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral, OpenSCENARIO2Parser.BoolLiteral, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 2) + self.state = 1124 + self.relation(0) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class RelationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_relation + + def copyFrom(self, ctx: ParserRuleContext): + super().copyFrom(ctx) + + class RelationExpContext(RelationContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.RelationContext + super().__init__(parser) + self.copyFrom(ctx) + + def relation(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationContext, 0) + + def relationalOp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RelationalOpContext, 0) + + def sumExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRelationExp"): + listener.enterRelationExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRelationExp"): + listener.exitRelationExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRelationExp"): + return visitor.visitRelationExp(self) + else: + return visitor.visitChildren(self) + + class SumExpContext(RelationContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.RelationContext + super().__init__(parser) + self.copyFrom(ctx) + + def sumExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterSumExp"): + listener.enterSumExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitSumExp"): + listener.exitSumExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitSumExp"): + return visitor.visitSumExp(self) + else: + return visitor.visitChildren(self) + + def relation(self, _p: int = 0): + _parentctx = self._ctx + _parentState = self.state + localctx = OpenSCENARIO2Parser.RelationContext(self, self._ctx, _parentState) + _prevctx = localctx + _startState = 236 + self.enterRecursionRule(localctx, 236, self.RULE_relation, _p) + try: + self.enterOuterAlt(localctx, 1) + localctx = OpenSCENARIO2Parser.SumExpContext(self, localctx) + self._ctx = localctx + _prevctx = localctx + + self.state = 1128 + self.sumExpression(0) + self._ctx.stop = self._input.LT(-1) + self.state = 1136 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 107, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + if self._parseListeners is not None: + self.triggerExitRuleEvent() + _prevctx = localctx + localctx = OpenSCENARIO2Parser.RelationExpContext( + self, OpenSCENARIO2Parser.RelationContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_relation) + self.state = 1130 + if not self.precpred(self._ctx, 1): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 1)") + self.state = 1131 + self.relationalOp() + self.state = 1132 + self.sumExpression(0) + self.state = 1138 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 107, self._ctx) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.unrollRecursionContexts(_parentctx) + return localctx + + class RelationalOpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_relationalOp + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRelationalOp"): + listener.enterRelationalOp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRelationalOp"): + listener.exitRelationalOp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRelationalOp"): + return visitor.visitRelationalOp(self) + else: + return visitor.visitChildren(self) + + def relationalOp(self): + + localctx = OpenSCENARIO2Parser.RelationalOpContext(self, self._ctx, self.state) + self.enterRule(localctx, 238, self.RULE_relationalOp) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1139 + _la = self._input.LA(1) + if not (((((_la - 23)) & ~0x3f) == 0 and ((1 << (_la - 23)) & ((1 << (OpenSCENARIO2Parser.T__22 - 23)) | (1 << (OpenSCENARIO2Parser.T__75 - 23)) | (1 << (OpenSCENARIO2Parser.T__76 - 23)) | (1 << (OpenSCENARIO2Parser.T__77 - 23)) | (1 << (OpenSCENARIO2Parser.T__78 - 23)) | (1 << (OpenSCENARIO2Parser.T__79 - 23)) | (1 << (OpenSCENARIO2Parser.T__80 - 23)))) != 0)): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class SumExpressionContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_sumExpression + + def copyFrom(self, ctx: ParserRuleContext): + super().copyFrom(ctx) + + class TermExpContext(SumExpressionContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.SumExpressionContext + super().__init__(parser) + self.copyFrom(ctx) + + def term(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTermExp"): + listener.enterTermExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTermExp"): + listener.exitTermExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTermExp"): + return visitor.visitTermExp(self) + else: + return visitor.visitChildren(self) + + class AdditiveExpContext(SumExpressionContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.SumExpressionContext + super().__init__(parser) + self.copyFrom(ctx) + + def sumExpression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.SumExpressionContext, 0) + + def additiveOp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.AdditiveOpContext, 0) + + def term(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterAdditiveExp"): + listener.enterAdditiveExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitAdditiveExp"): + listener.exitAdditiveExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitAdditiveExp"): + return visitor.visitAdditiveExp(self) + else: + return visitor.visitChildren(self) + + def sumExpression(self, _p: int = 0): + _parentctx = self._ctx + _parentState = self.state + localctx = OpenSCENARIO2Parser.SumExpressionContext(self, self._ctx, _parentState) + _prevctx = localctx + _startState = 240 + self.enterRecursionRule(localctx, 240, self.RULE_sumExpression, _p) + try: + self.enterOuterAlt(localctx, 1) + localctx = OpenSCENARIO2Parser.TermExpContext(self, localctx) + self._ctx = localctx + _prevctx = localctx + + self.state = 1142 + self.term(0) + self._ctx.stop = self._input.LT(-1) + self.state = 1150 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 108, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + if self._parseListeners is not None: + self.triggerExitRuleEvent() + _prevctx = localctx + localctx = OpenSCENARIO2Parser.AdditiveExpContext( + self, OpenSCENARIO2Parser.SumExpressionContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_sumExpression) + self.state = 1144 + if not self.precpred(self._ctx, 1): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 1)") + self.state = 1145 + self.additiveOp() + self.state = 1146 + self.term(0) + self.state = 1152 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 108, self._ctx) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.unrollRecursionContexts(_parentctx) + return localctx + + class AdditiveOpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_additiveOp + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterAdditiveOp"): + listener.enterAdditiveOp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitAdditiveOp"): + listener.exitAdditiveOp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitAdditiveOp"): + return visitor.visitAdditiveOp(self) + else: + return visitor.visitChildren(self) + + def additiveOp(self): + + localctx = OpenSCENARIO2Parser.AdditiveOpContext(self, self._ctx, self.state) + self.enterRule(localctx, 242, self.RULE_additiveOp) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1153 + _la = self._input.LA(1) + if not (_la == OpenSCENARIO2Parser.T__81 or _la == OpenSCENARIO2Parser.T__82): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class TermContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_term + + def copyFrom(self, ctx: ParserRuleContext): + super().copyFrom(ctx) + + class MultiplicativeExpContext(TermContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.TermContext + super().__init__(parser) + self.copyFrom(ctx) + + def term(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TermContext, 0) + + def multiplicativeOp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.MultiplicativeOpContext, 0) + + def factor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMultiplicativeExp"): + listener.enterMultiplicativeExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMultiplicativeExp"): + listener.exitMultiplicativeExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMultiplicativeExp"): + return visitor.visitMultiplicativeExp(self) + else: + return visitor.visitChildren(self) + + class FactorExpContext(TermContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.TermContext + super().__init__(parser) + self.copyFrom(ctx) + + def factor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFactorExp"): + listener.enterFactorExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFactorExp"): + listener.exitFactorExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFactorExp"): + return visitor.visitFactorExp(self) + else: + return visitor.visitChildren(self) + + def term(self, _p: int = 0): + _parentctx = self._ctx + _parentState = self.state + localctx = OpenSCENARIO2Parser.TermContext(self, self._ctx, _parentState) + _prevctx = localctx + _startState = 244 + self.enterRecursionRule(localctx, 244, self.RULE_term, _p) + try: + self.enterOuterAlt(localctx, 1) + localctx = OpenSCENARIO2Parser.FactorExpContext(self, localctx) + self._ctx = localctx + _prevctx = localctx + + self.state = 1156 + self.factor() + self._ctx.stop = self._input.LT(-1) + self.state = 1164 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 109, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + if self._parseListeners is not None: + self.triggerExitRuleEvent() + _prevctx = localctx + localctx = OpenSCENARIO2Parser.MultiplicativeExpContext( + self, OpenSCENARIO2Parser.TermContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_term) + self.state = 1158 + if not self.precpred(self._ctx, 1): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 1)") + self.state = 1159 + self.multiplicativeOp() + self.state = 1160 + self.factor() + self.state = 1166 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 109, self._ctx) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.unrollRecursionContexts(_parentctx) + return localctx + + class MultiplicativeOpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_multiplicativeOp + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterMultiplicativeOp"): + listener.enterMultiplicativeOp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitMultiplicativeOp"): + listener.exitMultiplicativeOp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitMultiplicativeOp"): + return visitor.visitMultiplicativeOp(self) + else: + return visitor.visitChildren(self) + + def multiplicativeOp(self): + + localctx = OpenSCENARIO2Parser.MultiplicativeOpContext(self, self._ctx, self.state) + self.enterRule(localctx, 246, self.RULE_multiplicativeOp) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1167 + _la = self._input.LA(1) + if not (((((_la - 84)) & ~0x3f) == 0 and ((1 << (_la - 84)) & ((1 << (OpenSCENARIO2Parser.T__83 - 84)) | (1 << (OpenSCENARIO2Parser.T__84 - 84)) | (1 << (OpenSCENARIO2Parser.T__85 - 84)))) != 0)): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class FactorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def factor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FactorContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_factor + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFactor"): + listener.enterFactor(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFactor"): + listener.exitFactor(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFactor"): + return visitor.visitFactor(self) + else: + return visitor.visitChildren(self) + + def factor(self): + + localctx = OpenSCENARIO2Parser.FactorContext(self, self._ctx, self.state) + self.enterRule(localctx, 248, self.RULE_factor) + try: + self.state = 1172 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__69, OpenSCENARIO2Parser.T__86, OpenSCENARIO2Parser.OPEN_BRACK, OpenSCENARIO2Parser.OPEN_PAREN, OpenSCENARIO2Parser.StringLiteral, OpenSCENARIO2Parser.FloatLiteral, OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral, OpenSCENARIO2Parser.BoolLiteral, OpenSCENARIO2Parser.Identifier]: + self.enterOuterAlt(localctx, 1) + self.state = 1169 + self.postfixExp(0) + pass + elif token in [OpenSCENARIO2Parser.T__82]: + self.enterOuterAlt(localctx, 2) + self.state = 1170 + self.match(OpenSCENARIO2Parser.T__82) + self.state = 1171 + self.factor() + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PostfixExpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_postfixExp + + def copyFrom(self, ctx: ParserRuleContext): + super().copyFrom(ctx) + + class PrimaryExpressionContext(PostfixExpContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + super().__init__(parser) + self.copyFrom(ctx) + + def primaryExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PrimaryExpContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPrimaryExpression"): + listener.enterPrimaryExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPrimaryExpression"): + listener.exitPrimaryExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPrimaryExpression"): + return visitor.visitPrimaryExpression(self) + else: + return visitor.visitChildren(self) + + class CastExpressionContext(PostfixExpContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + super().__init__(parser) + self.copyFrom(ctx) + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterCastExpression"): + listener.enterCastExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitCastExpression"): + listener.exitCastExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitCastExpression"): + return visitor.visitCastExpression(self) + else: + return visitor.visitChildren(self) + + class FunctionApplicationExpressionContext(PostfixExpContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + super().__init__(parser) + self.copyFrom(ctx) + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def argumentList(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentListContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFunctionApplicationExpression"): + listener.enterFunctionApplicationExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFunctionApplicationExpression"): + listener.exitFunctionApplicationExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFunctionApplicationExpression"): + return visitor.visitFunctionApplicationExpression(self) + else: + return visitor.visitChildren(self) + + class FieldAccessExpressionContext(PostfixExpContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + super().__init__(parser) + self.copyFrom(ctx) + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def fieldName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldAccessExpression"): + listener.enterFieldAccessExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldAccessExpression"): + listener.exitFieldAccessExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldAccessExpression"): + return visitor.visitFieldAccessExpression(self) + else: + return visitor.visitChildren(self) + + class ElementAccessExpressionContext(PostfixExpContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + super().__init__(parser) + self.copyFrom(ctx) + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def OPEN_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def CLOSE_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterElementAccessExpression"): + listener.enterElementAccessExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitElementAccessExpression"): + listener.exitElementAccessExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitElementAccessExpression"): + return visitor.visitElementAccessExpression(self) + else: + return visitor.visitChildren(self) + + class TypeTestExpressionContext(PostfixExpContext): + + def __init__(self, parser, ctx: ParserRuleContext): # actually a OpenSCENARIO2Parser.PostfixExpContext + super().__init__(parser) + self.copyFrom(ctx) + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterTypeTestExpression"): + listener.enterTypeTestExpression(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitTypeTestExpression"): + listener.exitTypeTestExpression(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitTypeTestExpression"): + return visitor.visitTypeTestExpression(self) + else: + return visitor.visitChildren(self) + + def postfixExp(self, _p: int = 0): + _parentctx = self._ctx + _parentState = self.state + localctx = OpenSCENARIO2Parser.PostfixExpContext(self, self._ctx, _parentState) + _prevctx = localctx + _startState = 250 + self.enterRecursionRule(localctx, 250, self.RULE_postfixExp, _p) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + localctx = OpenSCENARIO2Parser.PrimaryExpressionContext(self, localctx) + self._ctx = localctx + _prevctx = localctx + + self.state = 1175 + self.primaryExp() + self._ctx.stop = self._input.LT(-1) + self.state = 1207 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 113, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + if self._parseListeners is not None: + self.triggerExitRuleEvent() + _prevctx = localctx + self.state = 1205 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 112, self._ctx) + if la_ == 1: + localctx = OpenSCENARIO2Parser.CastExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) + self.state = 1177 + if not self.precpred(self._ctx, 5): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 5)") + self.state = 1178 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 1179 + self.match(OpenSCENARIO2Parser.T__40) + self.state = 1180 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1181 + self.typeDeclarator() + self.state = 1182 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + pass + + elif la_ == 2: + localctx = OpenSCENARIO2Parser.TypeTestExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) + self.state = 1184 + if not self.precpred(self._ctx, 4): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 4)") + self.state = 1185 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 1186 + self.match(OpenSCENARIO2Parser.T__3) + self.state = 1187 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1188 + self.typeDeclarator() + self.state = 1189 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + pass + + elif la_ == 3: + localctx = OpenSCENARIO2Parser.ElementAccessExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) + self.state = 1191 + if not self.precpred(self._ctx, 3): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 3)") + self.state = 1192 + self.match(OpenSCENARIO2Parser.OPEN_BRACK) + self.state = 1193 + self.expression() + self.state = 1194 + self.match(OpenSCENARIO2Parser.CLOSE_BRACK) + pass + + elif la_ == 4: + localctx = OpenSCENARIO2Parser.FunctionApplicationExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) + self.state = 1196 + if not self.precpred(self._ctx, 2): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 2)") + self.state = 1197 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1199 + self._errHandler.sync(self) + _la = self._input.LA(1) + if ((((_la - 70)) & ~0x3f) == 0 and ((1 << (_la - 70)) & ((1 << (OpenSCENARIO2Parser.T__69 - 70)) | (1 << (OpenSCENARIO2Parser.T__74 - 70)) | (1 << (OpenSCENARIO2Parser.T__82 - 70)) | (1 << (OpenSCENARIO2Parser.T__86 - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_BRACK - 70)) | (1 << (OpenSCENARIO2Parser.OPEN_PAREN - 70)) | (1 << (OpenSCENARIO2Parser.StringLiteral - 70)) | (1 << (OpenSCENARIO2Parser.FloatLiteral - 70)) | (1 << (OpenSCENARIO2Parser.UintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 70)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 70)) | (1 << (OpenSCENARIO2Parser.BoolLiteral - 70)) | (1 << (OpenSCENARIO2Parser.Identifier - 70)))) != 0): + self.state = 1198 + self.argumentList() + + self.state = 1201 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + pass + + elif la_ == 5: + localctx = OpenSCENARIO2Parser.FieldAccessExpressionContext( + self, OpenSCENARIO2Parser.PostfixExpContext(self, _parentctx, _parentState)) + self.pushNewRecursionContext(localctx, _startState, self.RULE_postfixExp) + self.state = 1202 + if not self.precpred(self._ctx, 1): + from antlr4.error.Errors import FailedPredicateException + raise FailedPredicateException(self, "self.precpred(self._ctx, 1)") + self.state = 1203 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 1204 + self.fieldName() + pass + + self.state = 1209 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 113, self._ctx) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.unrollRecursionContexts(_parentctx) + return localctx + + class FieldAccessContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def postfixExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PostfixExpContext, 0) + + def fieldName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_fieldAccess + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterFieldAccess"): + listener.enterFieldAccess(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitFieldAccess"): + listener.exitFieldAccess(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitFieldAccess"): + return visitor.visitFieldAccess(self) + else: + return visitor.visitChildren(self) + + def fieldAccess(self): + + localctx = OpenSCENARIO2Parser.FieldAccessContext(self, self._ctx, self.state) + self.enterRule(localctx, 252, self.RULE_fieldAccess) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1210 + self.postfixExp(0) + self.state = 1211 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 1212 + self.fieldName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PrimaryExpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def valueExp(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ValueExpContext, 0) + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_primaryExp + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPrimaryExp"): + listener.enterPrimaryExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPrimaryExp"): + listener.exitPrimaryExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPrimaryExp"): + return visitor.visitPrimaryExp(self) + else: + return visitor.visitChildren(self) + + def primaryExp(self): + + localctx = OpenSCENARIO2Parser.PrimaryExpContext(self, self._ctx, self.state) + self.enterRule(localctx, 254, self.RULE_primaryExp) + try: + self.state = 1221 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 114, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 1214 + self.valueExp() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 1215 + self.match(OpenSCENARIO2Parser.T__86) + pass + + elif la_ == 3: + self.enterOuterAlt(localctx, 3) + self.state = 1216 + self.match(OpenSCENARIO2Parser.Identifier) + pass + + elif la_ == 4: + self.enterOuterAlt(localctx, 4) + self.state = 1217 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1218 + self.expression() + self.state = 1219 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ValueExpContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def physicalLiteral(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.PhysicalLiteralContext, 0) + + def FloatLiteral(self): + return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) + + def integerLiteral(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) + + def BoolLiteral(self): + return self.getToken(OpenSCENARIO2Parser.BoolLiteral, 0) + + def StringLiteral(self): + return self.getToken(OpenSCENARIO2Parser.StringLiteral, 0) + + def identifierReference(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.IdentifierReferenceContext, 0) + + def enumValueReference(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.EnumValueReferenceContext, 0) + + def listConstructor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ListConstructorContext, 0) + + def rangeConstructor(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.RangeConstructorContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_valueExp + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterValueExp"): + listener.enterValueExp(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitValueExp"): + listener.exitValueExp(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitValueExp"): + return visitor.visitValueExp(self) + else: + return visitor.visitChildren(self) + + def valueExp(self): + + localctx = OpenSCENARIO2Parser.ValueExpContext(self, self._ctx, self.state) + self.enterRule(localctx, 256, self.RULE_valueExp) + try: + self.state = 1232 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 115, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 1223 + self.physicalLiteral() + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 1224 + self.match(OpenSCENARIO2Parser.FloatLiteral) + pass + + elif la_ == 3: + self.enterOuterAlt(localctx, 3) + self.state = 1225 + self.integerLiteral() + pass + + elif la_ == 4: + self.enterOuterAlt(localctx, 4) + self.state = 1226 + self.match(OpenSCENARIO2Parser.BoolLiteral) + pass + + elif la_ == 5: + self.enterOuterAlt(localctx, 5) + self.state = 1227 + self.match(OpenSCENARIO2Parser.StringLiteral) + pass + + elif la_ == 6: + self.enterOuterAlt(localctx, 6) + self.state = 1228 + self.identifierReference() + pass + + elif la_ == 7: + self.enterOuterAlt(localctx, 7) + self.state = 1229 + self.enumValueReference() + pass + + elif la_ == 8: + self.enterOuterAlt(localctx, 8) + self.state = 1230 + self.listConstructor() + pass + + elif la_ == 9: + self.enterOuterAlt(localctx, 9) + self.state = 1231 + self.rangeConstructor() + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ListConstructorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) + + def expression(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExpressionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, i) + + def CLOSE_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_listConstructor + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterListConstructor"): + listener.enterListConstructor(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitListConstructor"): + listener.exitListConstructor(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitListConstructor"): + return visitor.visitListConstructor(self) + else: + return visitor.visitChildren(self) + + def listConstructor(self): + + localctx = OpenSCENARIO2Parser.ListConstructorContext(self, self._ctx, self.state) + self.enterRule(localctx, 258, self.RULE_listConstructor) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1234 + self.match(OpenSCENARIO2Parser.OPEN_BRACK) + self.state = 1235 + self.expression() + self.state = 1240 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 1236 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1237 + self.expression() + self.state = 1242 + self._errHandler.sync(self) + _la = self._input.LA(1) + + self.state = 1243 + self.match(OpenSCENARIO2Parser.CLOSE_BRACK) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class RangeConstructorContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def OPEN_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_PAREN, 0) + + def expression(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ExpressionContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, i) + + def CLOSE_PAREN(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_PAREN, 0) + + def OPEN_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.OPEN_BRACK, 0) + + def CLOSE_BRACK(self): + return self.getToken(OpenSCENARIO2Parser.CLOSE_BRACK, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_rangeConstructor + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterRangeConstructor"): + listener.enterRangeConstructor(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitRangeConstructor"): + listener.exitRangeConstructor(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitRangeConstructor"): + return visitor.visitRangeConstructor(self) + else: + return visitor.visitChildren(self) + + def rangeConstructor(self): + + localctx = OpenSCENARIO2Parser.RangeConstructorContext(self, self._ctx, self.state) + self.enterRule(localctx, 260, self.RULE_rangeConstructor) + try: + self.state = 1258 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.T__69]: + self.enterOuterAlt(localctx, 1) + self.state = 1245 + self.match(OpenSCENARIO2Parser.T__69) + self.state = 1246 + self.match(OpenSCENARIO2Parser.OPEN_PAREN) + self.state = 1247 + self.expression() + self.state = 1248 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1249 + self.expression() + self.state = 1250 + self.match(OpenSCENARIO2Parser.CLOSE_PAREN) + pass + elif token in [OpenSCENARIO2Parser.OPEN_BRACK]: + self.enterOuterAlt(localctx, 2) + self.state = 1252 + self.match(OpenSCENARIO2Parser.OPEN_BRACK) + self.state = 1253 + self.expression() + self.state = 1254 + self.match(OpenSCENARIO2Parser.T__87) + self.state = 1255 + self.expression() + self.state = 1256 + self.match(OpenSCENARIO2Parser.CLOSE_BRACK) + pass + else: + raise NoViableAltException(self) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class IdentifierReferenceContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def fieldName(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.FieldNameContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.FieldNameContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_identifierReference + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterIdentifierReference"): + listener.enterIdentifierReference(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitIdentifierReference"): + listener.exitIdentifierReference(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitIdentifierReference"): + return visitor.visitIdentifierReference(self) + else: + return visitor.visitChildren(self) + + def identifierReference(self): + + localctx = OpenSCENARIO2Parser.IdentifierReferenceContext(self, self._ctx, self.state) + self.enterRule(localctx, 262, self.RULE_identifierReference) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1265 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 118, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + self.state = 1260 + self.fieldName() + self.state = 1261 + self.match(OpenSCENARIO2Parser.T__1) + self.state = 1267 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 118, self._ctx) + + self.state = 1268 + self.fieldName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ArgumentListSpecificationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def argumentSpecification(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.ArgumentSpecificationContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentSpecificationContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_argumentListSpecification + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentListSpecification"): + listener.enterArgumentListSpecification(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentListSpecification"): + listener.exitArgumentListSpecification(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentListSpecification"): + return visitor.visitArgumentListSpecification(self) + else: + return visitor.visitChildren(self) + + def argumentListSpecification(self): + + localctx = OpenSCENARIO2Parser.ArgumentListSpecificationContext(self, self._ctx, self.state) + self.enterRule(localctx, 264, self.RULE_argumentListSpecification) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1270 + self.argumentSpecification() + self.state = 1275 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 1271 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1272 + self.argumentSpecification() + self.state = 1277 + self._errHandler.sync(self) + _la = self._input.LA(1) + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ArgumentSpecificationContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def argumentName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentNameContext, 0) + + def typeDeclarator(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.TypeDeclaratorContext, 0) + + def defaultValue(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.DefaultValueContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_argumentSpecification + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentSpecification"): + listener.enterArgumentSpecification(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentSpecification"): + listener.exitArgumentSpecification(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentSpecification"): + return visitor.visitArgumentSpecification(self) + else: + return visitor.visitChildren(self) + + def argumentSpecification(self): + + localctx = OpenSCENARIO2Parser.ArgumentSpecificationContext(self, self._ctx, self.state) + self.enterRule(localctx, 266, self.RULE_argumentSpecification) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1278 + self.argumentName() + self.state = 1279 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1280 + self.typeDeclarator() + self.state = 1283 + self._errHandler.sync(self) + _la = self._input.LA(1) + if _la == OpenSCENARIO2Parser.T__20: + self.state = 1281 + self.match(OpenSCENARIO2Parser.T__20) + self.state = 1282 + self.defaultValue() + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ArgumentNameContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def Identifier(self): + return self.getToken(OpenSCENARIO2Parser.Identifier, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_argumentName + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentName"): + listener.enterArgumentName(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentName"): + listener.exitArgumentName(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentName"): + return visitor.visitArgumentName(self) + else: + return visitor.visitChildren(self) + + def argumentName(self): + + localctx = OpenSCENARIO2Parser.ArgumentNameContext(self, self._ctx, self.state) + self.enterRule(localctx, 268, self.RULE_argumentName) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1285 + self.match(OpenSCENARIO2Parser.Identifier) + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class ArgumentListContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def positionalArgument(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.PositionalArgumentContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.PositionalArgumentContext, i) + + def namedArgument(self, i: int = None): + if i is None: + return self.getTypedRuleContexts(OpenSCENARIO2Parser.NamedArgumentContext) + else: + return self.getTypedRuleContext(OpenSCENARIO2Parser.NamedArgumentContext, i) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_argumentList + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterArgumentList"): + listener.enterArgumentList(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitArgumentList"): + listener.exitArgumentList(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitArgumentList"): + return visitor.visitArgumentList(self) + else: + return visitor.visitChildren(self) + + def argumentList(self): + + localctx = OpenSCENARIO2Parser.ArgumentListContext(self, self._ctx, self.state) + self.enterRule(localctx, 270, self.RULE_argumentList) + self._la = 0 # Token type + try: + self.state = 1310 + self._errHandler.sync(self) + la_ = self._interp.adaptivePredict(self._input, 124, self._ctx) + if la_ == 1: + self.enterOuterAlt(localctx, 1) + self.state = 1287 + self.positionalArgument() + self.state = 1292 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 121, self._ctx) + while _alt != 2 and _alt != ATN.INVALID_ALT_NUMBER: + if _alt == 1: + self.state = 1288 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1289 + self.positionalArgument() + self.state = 1294 + self._errHandler.sync(self) + _alt = self._interp.adaptivePredict(self._input, 121, self._ctx) + + self.state = 1299 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 1295 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1296 + self.namedArgument() + self.state = 1301 + self._errHandler.sync(self) + _la = self._input.LA(1) + + pass + + elif la_ == 2: + self.enterOuterAlt(localctx, 2) + self.state = 1302 + self.namedArgument() + self.state = 1307 + self._errHandler.sync(self) + _la = self._input.LA(1) + while _la == OpenSCENARIO2Parser.T__7: + self.state = 1303 + self.match(OpenSCENARIO2Parser.T__7) + self.state = 1304 + self.namedArgument() + self.state = 1309 + self._errHandler.sync(self) + _la = self._input.LA(1) + + pass + + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PositionalArgumentContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_positionalArgument + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPositionalArgument"): + listener.enterPositionalArgument(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPositionalArgument"): + listener.exitPositionalArgument(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPositionalArgument"): + return visitor.visitPositionalArgument(self) + else: + return visitor.visitChildren(self) + + def positionalArgument(self): + + localctx = OpenSCENARIO2Parser.PositionalArgumentContext(self, self._ctx, self.state) + self.enterRule(localctx, 272, self.RULE_positionalArgument) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1312 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class NamedArgumentContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def argumentName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ArgumentNameContext, 0) + + def expression(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.ExpressionContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_namedArgument + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterNamedArgument"): + listener.enterNamedArgument(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitNamedArgument"): + listener.exitNamedArgument(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitNamedArgument"): + return visitor.visitNamedArgument(self) + else: + return visitor.visitChildren(self) + + def namedArgument(self): + + localctx = OpenSCENARIO2Parser.NamedArgumentContext(self, self._ctx, self.state) + self.enterRule(localctx, 274, self.RULE_namedArgument) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1314 + self.argumentName() + self.state = 1315 + self.match(OpenSCENARIO2Parser.T__8) + self.state = 1316 + self.expression() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class PhysicalLiteralContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def unitName(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.UnitNameContext, 0) + + def FloatLiteral(self): + return self.getToken(OpenSCENARIO2Parser.FloatLiteral, 0) + + def integerLiteral(self): + return self.getTypedRuleContext(OpenSCENARIO2Parser.IntegerLiteralContext, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_physicalLiteral + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterPhysicalLiteral"): + listener.enterPhysicalLiteral(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitPhysicalLiteral"): + listener.exitPhysicalLiteral(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitPhysicalLiteral"): + return visitor.visitPhysicalLiteral(self) + else: + return visitor.visitChildren(self) + + def physicalLiteral(self): + + localctx = OpenSCENARIO2Parser.PhysicalLiteralContext(self, self._ctx, self.state) + self.enterRule(localctx, 276, self.RULE_physicalLiteral) + try: + self.enterOuterAlt(localctx, 1) + self.state = 1320 + self._errHandler.sync(self) + token = self._input.LA(1) + if token in [OpenSCENARIO2Parser.FloatLiteral]: + self.state = 1318 + self.match(OpenSCENARIO2Parser.FloatLiteral) + pass + elif token in [OpenSCENARIO2Parser.UintLiteral, OpenSCENARIO2Parser.HexUintLiteral, OpenSCENARIO2Parser.IntLiteral]: + self.state = 1319 + self.integerLiteral() + pass + else: + raise NoViableAltException(self) + + self.state = 1322 + self.unitName() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + class IntegerLiteralContext(ParserRuleContext): + + def __init__(self, parser, parent: ParserRuleContext = None, invokingState: int = -1): + super().__init__(parent, invokingState) + self.parser = parser + + def UintLiteral(self): + return self.getToken(OpenSCENARIO2Parser.UintLiteral, 0) + + def HexUintLiteral(self): + return self.getToken(OpenSCENARIO2Parser.HexUintLiteral, 0) + + def IntLiteral(self): + return self.getToken(OpenSCENARIO2Parser.IntLiteral, 0) + + def getRuleIndex(self): + return OpenSCENARIO2Parser.RULE_integerLiteral + + def enterRule(self, listener: ParseTreeListener): + if hasattr(listener, "enterIntegerLiteral"): + listener.enterIntegerLiteral(self) + + def exitRule(self, listener: ParseTreeListener): + if hasattr(listener, "exitIntegerLiteral"): + listener.exitIntegerLiteral(self) + + def accept(self, visitor: ParseTreeVisitor): + if hasattr(visitor, "visitIntegerLiteral"): + return visitor.visitIntegerLiteral(self) + else: + return visitor.visitChildren(self) + + def integerLiteral(self): + + localctx = OpenSCENARIO2Parser.IntegerLiteralContext(self, self._ctx, self.state) + self.enterRule(localctx, 278, self.RULE_integerLiteral) + self._la = 0 # Token type + try: + self.enterOuterAlt(localctx, 1) + self.state = 1324 + _la = self._input.LA(1) + if not (((((_la - 99)) & ~0x3f) == 0 and ((1 << (_la - 99)) & ((1 << (OpenSCENARIO2Parser.UintLiteral - 99)) | (1 << (OpenSCENARIO2Parser.HexUintLiteral - 99)) | (1 << (OpenSCENARIO2Parser.IntLiteral - 99)))) != 0)): + self._errHandler.recoverInline(self) + else: + self._errHandler.reportMatch(self) + self.consume() + except RecognitionException as re: + localctx.exception = re + self._errHandler.reportError(self, re) + self._errHandler.recover(self, re) + finally: + self.exitRule() + return localctx + + def sempred(self, localctx: RuleContext, ruleIndex: int, predIndex: int): + if self._predicates == None: + self._predicates = dict() + self._predicates[4] = self.structuredIdentifier_sempred + self._predicates[118] = self.relation_sempred + self._predicates[120] = self.sumExpression_sempred + self._predicates[122] = self.term_sempred + self._predicates[125] = self.postfixExp_sempred + pred = self._predicates.get(ruleIndex, None) + if pred is None: + raise Exception("No predicate with index:" + str(ruleIndex)) + else: + return pred(localctx, predIndex) + + def structuredIdentifier_sempred(self, localctx: StructuredIdentifierContext, predIndex: int): + if predIndex == 0: + return self.precpred(self._ctx, 1) + + def relation_sempred(self, localctx: RelationContext, predIndex: int): + if predIndex == 1: + return self.precpred(self._ctx, 1) + + def sumExpression_sempred(self, localctx: SumExpressionContext, predIndex: int): + if predIndex == 2: + return self.precpred(self._ctx, 1) + + def term_sempred(self, localctx: TermContext, predIndex: int): + if predIndex == 3: + return self.precpred(self._ctx, 1) + + def postfixExp_sempred(self, localctx: PostfixExpContext, predIndex: int): + if predIndex == 4: + return self.precpred(self._ctx, 5) + + if predIndex == 5: + return self.precpred(self._ctx, 4) + + if predIndex == 6: + return self.precpred(self._ctx, 3) + + if predIndex == 7: + return self.precpred(self._ctx, 2) + + if predIndex == 8: + return self.precpred(self._ctx, 1) diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Visitor.py b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Visitor.py new file mode 100644 index 00000000..e306c079 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/OpenSCENARIO2Visitor.py @@ -0,0 +1,642 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +# Generated from OpenSCENARIO2.g4 by ANTLR 4.7.2 +from antlr4 import * +if __name__ is not None and "." in __name__: + from .OpenSCENARIO2Parser import OpenSCENARIO2Parser +else: + from OpenSCENARIO2Parser import OpenSCENARIO2Parser + +# This class defines a complete generic visitor for a parse tree produced by OpenSCENARIO2Parser. + + +class OpenSCENARIO2Visitor(ParseTreeVisitor): + + # Visit a parse tree produced by OpenSCENARIO2Parser#osc_file. + def visitOsc_file(self, ctx: OpenSCENARIO2Parser.Osc_fileContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#preludeStatement. + def visitPreludeStatement(self, ctx: OpenSCENARIO2Parser.PreludeStatementContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#importStatement. + def visitImportStatement(self, ctx: OpenSCENARIO2Parser.ImportStatementContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#importReference. + def visitImportReference(self, ctx: OpenSCENARIO2Parser.ImportReferenceContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#structuredIdentifier. + def visitStructuredIdentifier(self, ctx: OpenSCENARIO2Parser.StructuredIdentifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#oscDeclaration. + def visitOscDeclaration(self, ctx: OpenSCENARIO2Parser.OscDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#physicalTypeDeclaration. + def visitPhysicalTypeDeclaration(self, ctx: OpenSCENARIO2Parser.PhysicalTypeDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#physicalTypeName. + def visitPhysicalTypeName(self, ctx: OpenSCENARIO2Parser.PhysicalTypeNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#baseUnitSpecifier. + def visitBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.BaseUnitSpecifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#sIBaseUnitSpecifier. + def visitSIBaseUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SIBaseUnitSpecifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#unitDeclaration. + def visitUnitDeclaration(self, ctx: OpenSCENARIO2Parser.UnitDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#unitSpecifier. + def visitUnitSpecifier(self, ctx: OpenSCENARIO2Parser.UnitSpecifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#unitName. + def visitUnitName(self, ctx: OpenSCENARIO2Parser.UnitNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#siBaseExponentList. + def visitSiBaseExponentList(self, ctx: OpenSCENARIO2Parser.SiBaseExponentListContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#siBaseExponent. + def visitSiBaseExponent(self, ctx: OpenSCENARIO2Parser.SiBaseExponentContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#siUnitSpecifier. + def visitSiUnitSpecifier(self, ctx: OpenSCENARIO2Parser.SiUnitSpecifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#siFactor. + def visitSiFactor(self, ctx: OpenSCENARIO2Parser.SiFactorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#siOffset. + def visitSiOffset(self, ctx: OpenSCENARIO2Parser.SiOffsetContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#siBaseUnitName. + def visitSiBaseUnitName(self, ctx: OpenSCENARIO2Parser.SiBaseUnitNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumDeclaration. + def visitEnumDeclaration(self, ctx: OpenSCENARIO2Parser.EnumDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumMemberDecl. + def visitEnumMemberDecl(self, ctx: OpenSCENARIO2Parser.EnumMemberDeclContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumMemberValue. + def visitEnumMemberValue(self, ctx: OpenSCENARIO2Parser.EnumMemberValueContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumName. + def visitEnumName(self, ctx: OpenSCENARIO2Parser.EnumNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumMemberName. + def visitEnumMemberName(self, ctx: OpenSCENARIO2Parser.EnumMemberNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumValueReference. + def visitEnumValueReference(self, ctx: OpenSCENARIO2Parser.EnumValueReferenceContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#inheritsCondition. + def visitInheritsCondition(self, ctx: OpenSCENARIO2Parser.InheritsConditionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#structDeclaration. + def visitStructDeclaration(self, ctx: OpenSCENARIO2Parser.StructDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#structInherits. + def visitStructInherits(self, ctx: OpenSCENARIO2Parser.StructInheritsContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#structMemberDecl. + def visitStructMemberDecl(self, ctx: OpenSCENARIO2Parser.StructMemberDeclContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#fieldName. + def visitFieldName(self, ctx: OpenSCENARIO2Parser.FieldNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#structName. + def visitStructName(self, ctx: OpenSCENARIO2Parser.StructNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actorDeclaration. + def visitActorDeclaration(self, ctx: OpenSCENARIO2Parser.ActorDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actorInherits. + def visitActorInherits(self, ctx: OpenSCENARIO2Parser.ActorInheritsContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actorMemberDecl. + def visitActorMemberDecl(self, ctx: OpenSCENARIO2Parser.ActorMemberDeclContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actorName. + def visitActorName(self, ctx: OpenSCENARIO2Parser.ActorNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#scenarioDeclaration. + def visitScenarioDeclaration(self, ctx: OpenSCENARIO2Parser.ScenarioDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#scenarioInherits. + def visitScenarioInherits(self, ctx: OpenSCENARIO2Parser.ScenarioInheritsContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#scenarioMemberDecl. + def visitScenarioMemberDecl(self, ctx: OpenSCENARIO2Parser.ScenarioMemberDeclContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#qualifiedBehaviorName. + def visitQualifiedBehaviorName(self, ctx: OpenSCENARIO2Parser.QualifiedBehaviorNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorName. + def visitBehaviorName(self, ctx: OpenSCENARIO2Parser.BehaviorNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actionDeclaration. + def visitActionDeclaration(self, ctx: OpenSCENARIO2Parser.ActionDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actionInherits. + def visitActionInherits(self, ctx: OpenSCENARIO2Parser.ActionInheritsContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#modifierDeclaration. + def visitModifierDeclaration(self, ctx: OpenSCENARIO2Parser.ModifierDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#modifierName. + def visitModifierName(self, ctx: OpenSCENARIO2Parser.ModifierNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#typeExtension. + def visitTypeExtension(self, ctx: OpenSCENARIO2Parser.TypeExtensionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#enumTypeExtension. + def visitEnumTypeExtension(self, ctx: OpenSCENARIO2Parser.EnumTypeExtensionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#structuredTypeExtension. + def visitStructuredTypeExtension(self, ctx: OpenSCENARIO2Parser.StructuredTypeExtensionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#extendableTypeName. + def visitExtendableTypeName(self, ctx: OpenSCENARIO2Parser.ExtendableTypeNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#extensionMemberDecl. + def visitExtensionMemberDecl(self, ctx: OpenSCENARIO2Parser.ExtensionMemberDeclContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#globalParameterDeclaration. + def visitGlobalParameterDeclaration(self, ctx: OpenSCENARIO2Parser.GlobalParameterDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#typeDeclarator. + def visitTypeDeclarator(self, ctx: OpenSCENARIO2Parser.TypeDeclaratorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#nonAggregateTypeDeclarator. + def visitNonAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.NonAggregateTypeDeclaratorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#aggregateTypeDeclarator. + def visitAggregateTypeDeclarator(self, ctx: OpenSCENARIO2Parser.AggregateTypeDeclaratorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#listTypeDeclarator. + def visitListTypeDeclarator(self, ctx: OpenSCENARIO2Parser.ListTypeDeclaratorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#primitiveType. + def visitPrimitiveType(self, ctx: OpenSCENARIO2Parser.PrimitiveTypeContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#typeName. + def visitTypeName(self, ctx: OpenSCENARIO2Parser.TypeNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventDeclaration. + def visitEventDeclaration(self, ctx: OpenSCENARIO2Parser.EventDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventSpecification. + def visitEventSpecification(self, ctx: OpenSCENARIO2Parser.EventSpecificationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventReference. + def visitEventReference(self, ctx: OpenSCENARIO2Parser.EventReferenceContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventFieldDecl. + def visitEventFieldDecl(self, ctx: OpenSCENARIO2Parser.EventFieldDeclContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventFieldName. + def visitEventFieldName(self, ctx: OpenSCENARIO2Parser.EventFieldNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventName. + def visitEventName(self, ctx: OpenSCENARIO2Parser.EventNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventPath. + def visitEventPath(self, ctx: OpenSCENARIO2Parser.EventPathContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#eventCondition. + def visitEventCondition(self, ctx: OpenSCENARIO2Parser.EventConditionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#riseExpression. + def visitRiseExpression(self, ctx: OpenSCENARIO2Parser.RiseExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#fallExpression. + def visitFallExpression(self, ctx: OpenSCENARIO2Parser.FallExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#elapsedExpression. + def visitElapsedExpression(self, ctx: OpenSCENARIO2Parser.ElapsedExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#everyExpression. + def visitEveryExpression(self, ctx: OpenSCENARIO2Parser.EveryExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#boolExpression. + def visitBoolExpression(self, ctx: OpenSCENARIO2Parser.BoolExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#durationExpression. + def visitDurationExpression(self, ctx: OpenSCENARIO2Parser.DurationExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#fieldDeclaration. + def visitFieldDeclaration(self, ctx: OpenSCENARIO2Parser.FieldDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#parameterDeclaration. + def visitParameterDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#variableDeclaration. + def visitVariableDeclaration(self, ctx: OpenSCENARIO2Parser.VariableDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#sampleExpression. + def visitSampleExpression(self, ctx: OpenSCENARIO2Parser.SampleExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#defaultValue. + def visitDefaultValue(self, ctx: OpenSCENARIO2Parser.DefaultValueContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#parameterWithDeclaration. + def visitParameterWithDeclaration(self, ctx: OpenSCENARIO2Parser.ParameterWithDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#parameterWithMember. + def visitParameterWithMember(self, ctx: OpenSCENARIO2Parser.ParameterWithMemberContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#constraintDeclaration. + def visitConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.ConstraintDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#keepConstraintDeclaration. + def visitKeepConstraintDeclaration(self, ctx: OpenSCENARIO2Parser.KeepConstraintDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#constraintQualifier. + def visitConstraintQualifier(self, ctx: OpenSCENARIO2Parser.ConstraintQualifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#constraintExpression. + def visitConstraintExpression(self, ctx: OpenSCENARIO2Parser.ConstraintExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#removeDefaultDeclaration. + def visitRemoveDefaultDeclaration(self, ctx: OpenSCENARIO2Parser.RemoveDefaultDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#parameterReference. + def visitParameterReference(self, ctx: OpenSCENARIO2Parser.ParameterReferenceContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#modifierInvocation. + def visitModifierInvocation(self, ctx: OpenSCENARIO2Parser.ModifierInvocationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorExpression. + def visitBehaviorExpression(self, ctx: OpenSCENARIO2Parser.BehaviorExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorSpecification. + def visitBehaviorSpecification(self, ctx: OpenSCENARIO2Parser.BehaviorSpecificationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#onDirective. + def visitOnDirective(self, ctx: OpenSCENARIO2Parser.OnDirectiveContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#onMember. + def visitOnMember(self, ctx: OpenSCENARIO2Parser.OnMemberContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#doDirective. + def visitDoDirective(self, ctx: OpenSCENARIO2Parser.DoDirectiveContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#doMember. + def visitDoMember(self, ctx: OpenSCENARIO2Parser.DoMemberContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#composition. + def visitComposition(self, ctx: OpenSCENARIO2Parser.CompositionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#compositionOperator. + def visitCompositionOperator(self, ctx: OpenSCENARIO2Parser.CompositionOperatorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorInvocation. + def visitBehaviorInvocation(self, ctx: OpenSCENARIO2Parser.BehaviorInvocationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorWithDeclaration. + def visitBehaviorWithDeclaration(self, ctx: OpenSCENARIO2Parser.BehaviorWithDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#behaviorWithMember. + def visitBehaviorWithMember(self, ctx: OpenSCENARIO2Parser.BehaviorWithMemberContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#labelName. + def visitLabelName(self, ctx: OpenSCENARIO2Parser.LabelNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#actorExpression. + def visitActorExpression(self, ctx: OpenSCENARIO2Parser.ActorExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#waitDirective. + def visitWaitDirective(self, ctx: OpenSCENARIO2Parser.WaitDirectiveContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#emitDirective. + def visitEmitDirective(self, ctx: OpenSCENARIO2Parser.EmitDirectiveContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#callDirective. + def visitCallDirective(self, ctx: OpenSCENARIO2Parser.CallDirectiveContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#untilDirective. + def visitUntilDirective(self, ctx: OpenSCENARIO2Parser.UntilDirectiveContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#methodInvocation. + def visitMethodInvocation(self, ctx: OpenSCENARIO2Parser.MethodInvocationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#methodDeclaration. + def visitMethodDeclaration(self, ctx: OpenSCENARIO2Parser.MethodDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#returnType. + def visitReturnType(self, ctx: OpenSCENARIO2Parser.ReturnTypeContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#methodImplementation. + def visitMethodImplementation(self, ctx: OpenSCENARIO2Parser.MethodImplementationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#methodQualifier. + def visitMethodQualifier(self, ctx: OpenSCENARIO2Parser.MethodQualifierContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#methodName. + def visitMethodName(self, ctx: OpenSCENARIO2Parser.MethodNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageDeclaration. + def visitCoverageDeclaration(self, ctx: OpenSCENARIO2Parser.CoverageDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverDeclaration. + def visitCoverDeclaration(self, ctx: OpenSCENARIO2Parser.CoverDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#recordDeclaration. + def visitRecordDeclaration(self, ctx: OpenSCENARIO2Parser.RecordDeclarationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageExpression. + def visitCoverageExpression(self, ctx: OpenSCENARIO2Parser.CoverageExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageUnit. + def visitCoverageUnit(self, ctx: OpenSCENARIO2Parser.CoverageUnitContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageRange. + def visitCoverageRange(self, ctx: OpenSCENARIO2Parser.CoverageRangeContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageEvery. + def visitCoverageEvery(self, ctx: OpenSCENARIO2Parser.CoverageEveryContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageEvent. + def visitCoverageEvent(self, ctx: OpenSCENARIO2Parser.CoverageEventContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#coverageNameArgument. + def visitCoverageNameArgument(self, ctx: OpenSCENARIO2Parser.CoverageNameArgumentContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#targetName. + def visitTargetName(self, ctx: OpenSCENARIO2Parser.TargetNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#expression. + def visitExpression(self, ctx: OpenSCENARIO2Parser.ExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#ternaryOpExp. + def visitTernaryOpExp(self, ctx: OpenSCENARIO2Parser.TernaryOpExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#implication. + def visitImplication(self, ctx: OpenSCENARIO2Parser.ImplicationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#disjunction. + def visitDisjunction(self, ctx: OpenSCENARIO2Parser.DisjunctionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#conjunction. + def visitConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#inversion. + def visitInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#relationExp. + def visitRelationExp(self, ctx: OpenSCENARIO2Parser.RelationExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#sumExp. + def visitSumExp(self, ctx: OpenSCENARIO2Parser.SumExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#relationalOp. + def visitRelationalOp(self, ctx: OpenSCENARIO2Parser.RelationalOpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#termExp. + def visitTermExp(self, ctx: OpenSCENARIO2Parser.TermExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#additiveExp. + def visitAdditiveExp(self, ctx: OpenSCENARIO2Parser.AdditiveExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#additiveOp. + def visitAdditiveOp(self, ctx: OpenSCENARIO2Parser.AdditiveOpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#multiplicativeExp. + def visitMultiplicativeExp(self, ctx: OpenSCENARIO2Parser.MultiplicativeExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#factorExp. + def visitFactorExp(self, ctx: OpenSCENARIO2Parser.FactorExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#multiplicativeOp. + def visitMultiplicativeOp(self, ctx: OpenSCENARIO2Parser.MultiplicativeOpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#factor. + def visitFactor(self, ctx: OpenSCENARIO2Parser.FactorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#primaryExpression. + def visitPrimaryExpression(self, ctx: OpenSCENARIO2Parser.PrimaryExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#castExpression. + def visitCastExpression(self, ctx: OpenSCENARIO2Parser.CastExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#functionApplicationExpression. + def visitFunctionApplicationExpression(self, ctx: OpenSCENARIO2Parser.FunctionApplicationExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#fieldAccessExpression. + def visitFieldAccessExpression(self, ctx: OpenSCENARIO2Parser.FieldAccessExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#elementAccessExpression. + def visitElementAccessExpression(self, ctx: OpenSCENARIO2Parser.ElementAccessExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#typeTestExpression. + def visitTypeTestExpression(self, ctx: OpenSCENARIO2Parser.TypeTestExpressionContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#fieldAccess. + def visitFieldAccess(self, ctx: OpenSCENARIO2Parser.FieldAccessContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#primaryExp. + def visitPrimaryExp(self, ctx: OpenSCENARIO2Parser.PrimaryExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#valueExp. + def visitValueExp(self, ctx: OpenSCENARIO2Parser.ValueExpContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#listConstructor. + def visitListConstructor(self, ctx: OpenSCENARIO2Parser.ListConstructorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#rangeConstructor. + def visitRangeConstructor(self, ctx: OpenSCENARIO2Parser.RangeConstructorContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#identifierReference. + def visitIdentifierReference(self, ctx: OpenSCENARIO2Parser.IdentifierReferenceContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#argumentListSpecification. + def visitArgumentListSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentListSpecificationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#argumentSpecification. + def visitArgumentSpecification(self, ctx: OpenSCENARIO2Parser.ArgumentSpecificationContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#argumentName. + def visitArgumentName(self, ctx: OpenSCENARIO2Parser.ArgumentNameContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#argumentList. + def visitArgumentList(self, ctx: OpenSCENARIO2Parser.ArgumentListContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#positionalArgument. + def visitPositionalArgument(self, ctx: OpenSCENARIO2Parser.PositionalArgumentContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#namedArgument. + def visitNamedArgument(self, ctx: OpenSCENARIO2Parser.NamedArgumentContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#physicalLiteral. + def visitPhysicalLiteral(self, ctx: OpenSCENARIO2Parser.PhysicalLiteralContext): + return self.visitChildren(ctx) + + # Visit a parse tree produced by OpenSCENARIO2Parser#integerLiteral. + def visitIntegerLiteral(self, ctx: OpenSCENARIO2Parser.IntegerLiteralContext): + return self.visitChildren(ctx) + + +del OpenSCENARIO2Parser diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/README.md b/scenario_execution_base/scenario_execution_base/osc2_parsing/README.md new file mode 100644 index 00000000..17bbca9e --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/README.md @@ -0,0 +1,3 @@ +# generate antlr parser + +antlr4 -Dlanguage=Python3 -visitor -listener OpenSCENARIO2.g4 \ No newline at end of file diff --git a/scenario_execution_base/scenario_execution_base/osc2_parsing/__init__.py b/scenario_execution_base/scenario_execution_base/osc2_parsing/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/osc2_parsing/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_base/scenario_execution_base/scenario_execution.py b/scenario_execution_base/scenario_execution_base/scenario_execution.py new file mode 100644 index 00000000..3ac9abe0 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/scenario_execution.py @@ -0,0 +1,315 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import sys +import time +import argparse +from datetime import datetime, timedelta +import py_trees +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from scenario_execution_base.model.model_file_loader import ModelFileLoader + + +class LastSnapshotVisitor(py_trees.visitors.DisplaySnapshotVisitor): + + def __init__(self): + self.last_snapshot = "" + super().__init__() + + def finalise(self) -> None: + if self.root is not None: + self.last_snapshot = py_trees.display.unicode_tree( + root=self.root, + show_only_visited=self.display_only_visited_behaviours, + show_status=False, + visited=self.visited, + previously_visited=self.previously_visited + ) + + +class ScenarioExecution(object): + """ + Base class for scenario execution. + Override method run() and method setup_behaviour_tree() to adapt to other middlewares. + This class can also be executed standalone + """ + + def __init__(self, + debug: bool, + log_model: bool, + live_tree: bool, + scenario: str, + test_output: str, + setup_timeout=py_trees.common.Duration.INFINITE, + tick_tock_period: float = 0.1) -> None: + self.debug = debug + self.log_model = log_model + self.live_tree = live_tree + self.scenario = scenario + self.test_output = test_output + self.logger = self._get_logger() + + if self.debug: + py_trees.logging.level = py_trees.logging.Level.DEBUG + self.setup_timeout = setup_timeout + self.tick_tock_period = tick_tock_period + self.scenarios = None + self.blackboard = None + self.behaviour_tree = None + self.last_snapshot_visitor = None + self.shutdown_requested = False + self.results = [] + + def _get_logger(self): + """ + Create a logger + This method could be overriden by child classes and defined according to the middleware. + + return: + A logger which has three logging levels: info, warning, error + """ + return Logger('scenario_execution') + + def setup(self, tree: py_trees.behaviour.Behaviour, **kwargs) -> bool: + """ + Setup each scenario before ticking + + Args: + tree [py_trees.behavior.Behavior]: root of the tree + + return: + True if the scenario is setup without errors + """ + self.shutdown_requested = False + self.blackboard = tree.attach_blackboard_client( + name="MainBlackboardClient", + namespace=tree.name + ) + + self.blackboard.register_key("end", access=py_trees.common.Access.READ) + self.blackboard.register_key("fail", access=py_trees.common.Access.READ) + + # Initialize end and fail events + self.blackboard.register_key("end", access=py_trees.common.Access.WRITE) + self.blackboard.register_key("fail", access=py_trees.common.Access.WRITE) + self.blackboard.end = False + self.blackboard.fail = False + self.behaviour_tree = self.setup_behaviour_tree(tree) # Get the behaviour_tree + self.behaviour_tree.add_pre_tick_handler(self.pre_tick_handler) + self.behaviour_tree.add_post_tick_handler(self.post_tick_handler) + self.last_snapshot_visitor = LastSnapshotVisitor() + self.behaviour_tree.add_visitor(self.last_snapshot_visitor) + if self.debug: + self.behaviour_tree.add_visitor(py_trees.visitors.DebugVisitor()) + if self.live_tree: + self.behaviour_tree.add_visitor( + py_trees.visitors.DisplaySnapshotVisitor( + display_blackboard=True + )) + try: + self.behaviour_tree.setup(timeout=self.setup_timeout, logger=self.logger, **kwargs) + return True + except RuntimeError: + self.logger.error('Setup Timeout exceeded. Aborting...') + return False + except Exception as e: # pylint: disable=broad-except + self.logger.error(f"Error while setting up tree: {e}") + return False + + def setup_behaviour_tree(self, tree): + """ + Setup the behaviour tree. + + For other middleware, a subclass of behaviour_tree might be needed for additional support. + Override this to adapt to other middleware. + + Args: + tree [py_trees.behaviour.Behaviour]: root of the behaviour tree + + return: + py_trees.trees.BehaviourTree + """ + return py_trees.trees.BehaviourTree(tree) + + def parse(self): + """ + Parse the OpenScenario2 file + + return: + True if no errors occured during parsing + """ + file_extension = os.path.splitext(self.scenario)[1] + if file_extension == '.osc': + parser = OpenScenario2Parser(self.logger) + elif file_extension == '.sce': + parser = ModelFileLoader(self.logger) + else: + self.logger.error(f"File '{self.scenario}' has unknown extension '{file_extension}'. Allowed [.osc, .sce]") + return False + + start = datetime.now() + self.scenarios = parser.process_file(self.scenario, self.log_model, self.debug) + if self.scenarios is None: + self.add_result((f'Parsing of {self.scenario}', True, "parsing failed", "", datetime.now() - start)) + return self.scenarios is not None + + def run(self) -> bool: + """ + Run all scenarios + + return: + True if all scenarios are executed successfully + """ + if not self.scenarios: + self.logger.info("No scenarios to execute.") + + failure = False + for tree in self.scenarios: + start = datetime.now() + if not tree: + self.logger.error(f'Scenario {tree.name} has no executables.') + continue + if not self.setup(tree): + failure = True + self.logger.error(f'Scenario {tree.name} failed to setup.') + continue + while not self.shutdown_requested: + try: + self.behaviour_tree.tick() + time.sleep(self.tick_tock_period) + if self.live_tree: + self.logger.debug(py_trees.display.unicode_tree( + root=self.behaviour_tree.root, show_status=True)) + except KeyboardInterrupt: + self.behaviour_tree.interrupt() + self.blackboard.fail = True + break + if self.blackboard.fail: + self.logger.error(f'Scenario {tree.name} failed.') + failure = failure or self.blackboard.fail + self.add_result((tree.name, self.blackboard.fail, "execution failed", "", datetime.now()-start)) + self.cleanup_behaviours(tree) + return not failure + + def add_result(self, result): + self.results.append(result) + + def report_results(self): + if self.test_output and self.results: + self.logger.info(f"Writing results to {self.test_output}...") + failures = 0 + overall_time = timedelta(0) + for result in self.results: + if result[1]: + failures += 1 + overall_time += result[4] + try: + with open(self.test_output, 'w') as out: + out.write('\n') + out.write( + f'\n') + for result in self.results: + out.write(f' \n') + if result[1]: + out.write(f' {result[3]}\n') + out.write(f' \n') + out.write("\n") + except Exception as e: # pylint: disable=broad-except + self.logger.error(f"Could not write junitxml {self.test_output}: {e}") + + def pre_tick_handler(self, behaviour_tree): + """ + Things to do before a round of ticking + """ + if self.live_tree: + self.logger.debug( + f"--------- Scenario {behaviour_tree.root.name}: Run {behaviour_tree.count} ---------") + + def post_tick_handler(self, behaviour_tree): + """ + Things to do after a round of ticking + """ + # Shut down if the root is failed + if self.behaviour_tree.root.status == py_trees.common.Status.FAILURE: + self.blackboard.fail = True + if self.behaviour_tree.root.status == py_trees.common.Status.SUCCESS: + self.blackboard.end = True + self.shutdown_requested = self.blackboard.fail or self.blackboard.end + + def cleanup_behaviours(self, tree): + """ + Run cleanup functions in all behaviors + """ + class CleanupVisitor(py_trees.visitors.VisitorBase): + """ + Helper class to call cleanup functions in all behaviors + """ + + def __init__(self): + super(CleanupVisitor, self).__init__(full=False) + + def run(self, behaviour): + """ + call cleanup method + """ + method = getattr(behaviour, 'cleanup', None) + if callable(method): + method() + + cleanup_visitor = CleanupVisitor() + + for node in tree.iterate(): + cleanup_visitor.run(node) + + @staticmethod + def parse_args(args): + parser = argparse.ArgumentParser() + parser.add_argument('-d', '--debug', action='store_true', help='debugging output') + parser.add_argument('-o', '--log-model', action='store_true', + help='Produce tree output of parsed openscenario2 content') + parser.add_argument('-t', '--live-tree', action='store_true', + help='For debugging: Show current state of py tree') + parser.add_argument('-j', '--test-output', type=str, help='Write test output to file.') + parser.add_argument('scenario', type=str, help='scenario file to execute', nargs='?') + args = parser.parse_args(args) + return args + + +def main(): + """ + main function + """ + args = ScenarioExecution.parse_args(sys.argv[1:]) + scenario_execution = ScenarioExecution(debug=args.debug, + log_model=args.log_model, + live_tree=args.live_tree, + scenario=args.scenario, + test_output=args.test_output) + + result = scenario_execution.parse() + if result: + result = scenario_execution.run() + scenario_execution.report_results() + if result: + sys.exit(0) + else: + sys.exit(1) + + +if __name__ == '__main__': + main() diff --git a/scenario_execution_base/scenario_execution_base/utils/__init__.py b/scenario_execution_base/scenario_execution_base/utils/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/utils/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_base/scenario_execution_base/utils/logging.py b/scenario_execution_base/scenario_execution_base/utils/logging.py new file mode 100644 index 00000000..16a074d6 --- /dev/null +++ b/scenario_execution_base/scenario_execution_base/utils/logging.py @@ -0,0 +1,110 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +class BaseLogger(object): + """ + Base class for logger for scenario execution + For different middleware that does not have logger, inherit from this class + and override the virtual methods + + Args: + name [str]: name of the logger + """ + + def __init__(self, name: str) -> None: + self.name = name + + def info(self, msg: str) -> None: + """ + Virtual method to log info + + Args: + msg [str]: msg to print + """ + raise NotImplementedError + + def debug(self, msg: str) -> None: + """ + virtual method to log debug info + + Args: + msg [str]: msg to print + """ + raise NotImplementedError + + def warning(self, msg: str) -> None: + """ + Virtual method to log warning + + Args: + msg [str]: msg to print + """ + raise NotImplementedError + + def error(self, msg: str) -> None: + """ + Virtual method to log error + + Args: + msg [str]: msg to print + """ + raise NotImplementedError + + +class Logger(BaseLogger): + """ + Class for logger for scenario execution + + Args: + name [str]: name of the logger + """ + + def info(self, msg: str) -> None: + """ + Print a info with logger name and "[INFO]" in the front. + + Args: + msg [str]: msg to print + """ + print(f'[{self.name}] [INFO] {msg}') + + def debug(self, msg: str) -> None: + """ + Print debug info with logger name and "[DEBUG]" in the front. + + Args: + msg [str]: msg to print + """ + print(f'[{self.name}] [DEBUG] {msg}') + + def warning(self, msg: str) -> None: + """ + Print a warning in yellow color with logger name and "[WARN]" in the front. + + Args: + msg [str]: msg to print + """ + print(f'\033[33m[{self.name}] [WARN] {msg}\033[0m') + + def error(self, msg: str) -> None: + """ + Print a warning in red color with logger name and "[ERROR]" in the front. + + Args: + msg [str]: msg to print + """ + print(f'\033[31m[{self.name}] [ERROR] {msg}\033[0m') diff --git a/scenario_execution_base/setup.cfg b/scenario_execution_base/setup.cfg new file mode 100644 index 00000000..77c4ce28 --- /dev/null +++ b/scenario_execution_base/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/scenario_execution_base +[install] +install_scripts=$base/lib/scenario_execution_base diff --git a/scenario_execution_base/setup.py b/scenario_execution_base/setup.py new file mode 100644 index 00000000..a9eb1f6a --- /dev/null +++ b/scenario_execution_base/setup.py @@ -0,0 +1,56 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +"""Setup python package""" +from glob import glob +import os +from setuptools import find_packages, setup + +PACKAGE_NAME = 'scenario_execution_base' + +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=find_packages(), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'launch'), glob('launch/*launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + include_package_data=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Robotics Scenario Execution', + license='Apache License 2.0', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'scenario_execution_base = scenario_execution_base.scenario_execution:main', + ], + 'scenario_execution.actions': [ + 'log = scenario_execution_base.actions.log:Log', + 'run_external_process = scenario_execution_base.actions.run_external_process:RunExternalProcess', + ], + 'scenario_execution.osc_libraries': [ + 'helpers = scenario_execution_base.get_osc_library:get_helpers_library', + 'standard = scenario_execution_base.get_osc_library:get_standard_library', + 'robotics = scenario_execution_base.get_osc_library:get_robotics_library', + ] + }, +) diff --git a/scenario_execution_base/test/test_expression.py b/scenario_execution_base/test/test_expression.py new file mode 100644 index 00000000..d5ca8240 --- /dev/null +++ b/scenario_execution_base/test/test_expression.py @@ -0,0 +1,153 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestExpression(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + """ + Unit test for expression parsing + """ + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + @unittest.skip(reason="requires porting") + def test_add(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) +unit ms of time is SI(s: 1, factor: 0.001) + +global test1: float = 2.0 + 1.1 +global test2: time = 2.0s + 1.1s +global test3: time = 2.0s + 1ms +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[3].get_resolved_value(), 3.1) + self.assertEqual(model._ModelElement__children[4].get_resolved_value(), 3.1) + self.assertEqual(model._ModelElement__children[5].get_resolved_value(), 2.001) + + @unittest.skip(reason="requires porting") + def test_substract(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) +unit ms of time is SI(s: 1, factor: 0.001) + +global test1: float = 2.0 - 1.1 +global test2: time = 2.0s - 1.1s +global test3: time = 2.0s - 1ms +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[3].get_resolved_value(), 0.9) + self.assertEqual(model._ModelElement__children[4].get_resolved_value(), 0.9) + self.assertEqual(model._ModelElement__children[5].get_resolved_value(), 1.999) + + @unittest.skip(reason="requires porting") + def test_multiply(self): + scenario_content = """ +type time is SI(s: 1) +unit ms of time is SI(s: 1, factor: 0.001) + +global test1: float = 2.0 * 1.1 +global test2: time = 2.0ms * 1.1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[3].get_resolved_value(), 2.2) + self.assertEqual(model._ModelElement__children[4].get_resolved_value(), 0.0022) + + @unittest.skip(reason="requires porting") + def test_divide(self): + scenario_content = """ +type time is SI(s: 1) +unit ms of time is SI(s: 1, factor: 0.001) + +global test1: float = 5.0 / 2.0 +global test2: time = 5.0ms / 2.0 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[3].get_resolved_value(), 2.5) + self.assertEqual(model._ModelElement__children[4].get_resolved_value(), 0.0025) + + @unittest.skip(reason="requires porting") + def test_relation(self): + scenario_content = """ +type time is SI(s: 1) +unit ms of time is SI(s: 1, factor: 0.001) + +global test1: bool = 5.0 > 2.0 +global test2: bool = 5 > 2 +global test3: bool = 5 < 2 +global test4: bool = 5 == 2 +global test5: bool = 5 != 2 +global test6: bool = 5 >= 2 +global test7: bool = 5 <= 2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[3].get_resolved_value(), True) + self.assertEqual(model._ModelElement__children[4].get_resolved_value(), True) + self.assertEqual(model._ModelElement__children[5].get_resolved_value(), False) + self.assertEqual(model._ModelElement__children[6].get_resolved_value(), False) + self.assertEqual(model._ModelElement__children[7].get_resolved_value(), True) + self.assertEqual(model._ModelElement__children[8].get_resolved_value(), True) + self.assertEqual(model._ModelElement__children[9].get_resolved_value(), False) + + @unittest.skip(reason="requires porting") + def test_negation(self): + scenario_content = """ +global test1: bool = not True +global test1: bool = not 5 > 2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[0].get_resolved_value(), False) + self.assertEqual(model._ModelElement__children[1].get_resolved_value(), False) + + @unittest.skip(reason="requires porting") + def test_compound_expression(self): + scenario_content = """ +global test1: bool = 2 > 1 and 3 >= 2 +global test1: bool = 2 > 1 or 3 < 2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[0].get_resolved_value(), True) + self.assertEqual(model._ModelElement__children[1].get_resolved_value(), True) diff --git a/scenario_execution_base/test/test_model_ser_deser.py b/scenario_execution_base/test/test_model_ser_deser.py new file mode 100644 index 00000000..4e24c4b7 --- /dev/null +++ b/scenario_execution_base/test/test_model_ser_deser.py @@ -0,0 +1,126 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test for Intermediate Scenario model Serialization and Deserialization +""" +import unittest + +from scenario_coverage.scenario_variation import ScenarioVariation +from scenario_execution_base.model.model_file_loader import ModelFileLoader +from scenario_execution_base.utils.logging import BaseLogger, Logger +from scenario_execution_base.model.types import print_tree +import tempfile +import os + + +class DebugLogger(BaseLogger): + + def __init__(self, name): + super().__init__(name) + self.logs = [] + + def info(self, msg: str) -> None: + self.logs.append(msg) + + def debug(self, msg: str) -> None: + self.logs.append(msg) + + def warning(self, msg: str) -> None: + self.logs.append(msg) + + def error(self, msg: str) -> None: + self.logs.append(msg) + + def count_lines(self): + return len(self.logs) + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + def setUp(self) -> None: + self.tmpdir = tempfile.TemporaryDirectory() + + def run_coverage(self, scenario_content): + fp = tempfile.NamedTemporaryFile(suffix='.osc', mode='w', delete=False) + fp.write(scenario_content) + fp.close() + coverage = ScenarioVariation(self.tmpdir.name, fp.name, False, False) + model = coverage.load_model() + del fp + return model, coverage + + def test_serialize(self): + scenario_content = """ +import osc.standard + +action log: + msg: string + +scenario test: + do serial: + log() with: + keep(it.msg in ["foo", "bar"]) + emit end +""" + # serialize + model, coverage = self.run_coverage(scenario_content) + self.assertIsNotNone(model) + models = coverage.generate_concrete_models(model) + self.assertIsNotNone(models) + self.assertEqual(2, len(models)) + result = coverage.save_resulting_scenarios(models) + self.assertTrue(result) + + # deserialize + dir_content = os.listdir(self.tmpdir.name) + scenarios = [] + for entry in dir_content: + if entry.endswith(".sce"): + scenarios.append(os.path.join(self.tmpdir.name, entry)) + self.assertEqual(2, len(scenarios)) + print(scenarios) + scenario0 = None + scenario1 = None + for scenario in scenarios: + if scenario.endswith("0.sce"): + scenario0 = scenario + if scenario.endswith("1.sce"): + scenario1 = scenario + parser = ModelFileLoader(Logger('test')) + models_deserialized = [] + model0 = parser.load_file(scenario0, False) + models_deserialized.append(model0) + model1 = parser.load_file(scenario1, False) + models_deserialized.append(model1) + self.assertIsNotNone(models_deserialized) + self.assertEqual(2, len(models_deserialized)) + + # validate models + deserialize_model_0 = DebugLogger('deserialize_model_0') + base_model_0 = DebugLogger('base_model_0') + print_tree(models_deserialized[0], deserialize_model_0) + print_tree(models[0], base_model_0) + self.assertListEqual(deserialize_model_0.logs, base_model_0.logs) + + deserialize_model_1 = DebugLogger('deserialize_model_1') + base_model_1 = DebugLogger('base_model_1') + print_tree(models_deserialized[1], deserialize_model_1) + print_tree(models[1], base_model_1) + self.assertListEqual(deserialize_model_1.logs, base_model_1.logs) + + # test model lines + self.assertGreater(deserialize_model_0.count_lines(), 0) diff --git a/scenario_execution_base/test/test_osc2_parser_action.py b/scenario_execution_base/test/test_osc2_parser_action.py new file mode 100644 index 00000000..4891b23e --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_action.py @@ -0,0 +1,63 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test action parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_action_valid(self): + scenario_content = """ +action test_action: + param1: string = "value1" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + def test_action_unknown_actor(self): + scenario_content = """ +action UNKNOWN.test_action: + param1: string = "value1" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_action_valid_actor(self): + scenario_content = """ +actor base + +action base.test_action: + param1: string = "value1" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_actor.py b/scenario_execution_base/test/test_osc2_parser_actor.py new file mode 100644 index 00000000..fc2da241 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_actor.py @@ -0,0 +1,73 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test actor parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_actor(self): + scenario_content = """ +actor base: + param1: string = "value1" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[0].actor, "base") + self.assertEqual(model._ModelElement__children[0]._ModelElement__children[0].get_resolved_value(), "value1") + + def test_actor_inheritance(self): + scenario_content = """ +actor base: + param1: string = "value1" +actor derived inherits base: + param2: string = "value2" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[0]._ModelElement__children[0].get_resolved_value(), "value1") + self.assertEqual(model._ModelElement__children[1]._ModelElement__children[1].get_resolved_value(), "value2") + + def test_actor_inheritance_override(self): # TODO: expected? + scenario_content = """ +actor base: + param1: string = "value1" +actor derived inherits base: + param1: string = "OVERRIDE" + param2: string = "value2" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + params = model._ModelElement__children[1].get_resolved_value() + self.assertEqual({'param1': 'OVERRIDE', 'param2': 'value2'}, params) diff --git a/scenario_execution_base/test/test_osc2_parser_behavior_invocation.py b/scenario_execution_base/test/test_osc2_parser_behavior_invocation.py new file mode 100644 index 00000000..682aa8fe --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_behavior_invocation.py @@ -0,0 +1,416 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test behavior invocation parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_behavior_invocation_param_override(self): + scenario_content = """ +actor osc_object: + name: string = 'amr' + model_file: string = 'amr' + +struct pose_3d: + x: string = 'x_val' + +action osc_object.spawn: + spawn_pose: pose_3d + world_name: string = 'default' + namespace: string = '' + entity_name: string = '' + model_file: string = '' + xacro_arguments: string = '' # comma-separated list of argument key:=value pairs + +scenario test: + test_obstacle1: osc_object with: + keep(it.name == 'test_obstacle1') + keep(it.model_file == 'test_model') + do parallel: + test_drive: serial: + spawn_it: test_obstacle1.spawn() with: + keep(it.namespace == 'bll') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + behavior = model._ModelElement__children[3]._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + params = behavior.get_resolved_value() + self.assertEqual({'spawn_pose': {'x': 'x_val'}, 'world_name': 'default', + 'namespace': 'bll', 'entity_name': '', 'model_file': '', 'xacro_arguments': ''}, params) + + def test_behavior_named_arg(self): + scenario_content = """ +actor osc_object + +action osc_object.spawn: + param1: string = 'val1' + param2: string = 'val2' + +scenario test: + test_obstacle1: osc_object + do parallel: + spawn_it: test_obstacle1.spawn(param1: 'override1') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + behavior = model._ModelElement__children[2]._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0] + params = behavior.get_resolved_value() + self.assertEqual(params, {'param1': 'override1', 'param2': 'val2'}) + + def test_behavior_from_base_actor(self): + scenario_content = """ +actor osc_object + +action osc_object.spawn: + param1: string + +actor robot inherits osc_object + +scenario test: + test_obstacle1: robot + do parallel: + spawn_it: test_obstacle1.spawn(param1: 'override1') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + def test_behavior_invalid_param_name(self): + scenario_content = """ +actor osc_object + +action osc_object.spawn: + name: string = 'NOTALLOWED' + +scenario test: + test_obstacle1: osc_object + do parallel: + spawn_it: test_obstacle1.spawn(param1: 'override1') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_behavior_invalid_param_associated_actor(self): + scenario_content = """ +actor osc_object + +action osc_object.spawn: + associated_actor: string = 'NOTALLOWED' + param1: string + +scenario test: + test_obstacle1: osc_object + do parallel: + spawn_it: test_obstacle1.spawn(param1: 'override1') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_behavior_positional_arg(self): + scenario_content = """ +action test: + param1: string = 'base' + +scenario test: + do parallel: + spawn_it: test('override1') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + behavior = model._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + params = behavior.get_resolved_value() + self.assertEqual(params, {'param1': 'override1'}) + + @unittest.skip(reason="requires porting") + def test_behavior_empty_args(self): + scenario_content = """ +action test: + param1: string + param2: string + +scenario test: + do parallel: + spawn_it: test() +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + @unittest.skip(reason="requires porting") + def test_behavior_partially_defined_args(self): + scenario_content = """ +action test: + param1: string = 'val1' + param2: string + +scenario test: + do parallel: + spawn_it: test() +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + @unittest.skip(reason="requires porting") + def test_behavior_partially_overridden_positional_args(self): + scenario_content = """ +action test: + param1: string + param2: string + +scenario test: + do parallel: + spawn_it: test('override1') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + @unittest.skip(reason="requires porting") + def test_behavior_partially_overridden_named_args(self): + scenario_content = """ +action test: + param1: string + param2: string + +scenario test: + do parallel: + spawn_it: test(param2: 'override2') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_behavior_too_many_named_args(self): + scenario_content = """ +action test: + param1: string + param2: string + +scenario test: + do parallel: + spawn_it: test(param1: 'override1', param2: 'override2', param3: 'override3') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_behavior_too_many_positional_args(self): + scenario_content = """ +action test: + param1: string + param2: string + +scenario test: + do parallel: + spawn_it: test('override1', 'override2', 'override3') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_behavior_unknown_named_args(self): + scenario_content = """ +action test: + param1: string + param2: string + +scenario test: + do parallel: + spawn_it: test(param1: 'override1', UNKNOWN: 'override2') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + @unittest.skip(reason="requires porting") + def test_behavior_struct_param_named_override(self): + scenario_content = """ +struct test_struct: + param1: string = "val1" + param2: string = "val2" + +action test_action: + struct_param: test_struct + +scenario test: + do serial: + test_action() with: + keep(it.struct_param == test_struct(param2: 'OVERRIDE')) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + behavior = model._ModelElement__children[2]._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[1] + params = behavior.get_resolved_value() + self.assertEqual(params, {'struct_param': {'param1': 'val1', 'param2': 'OVERRIDE'}}) + + def test_behavior_struct_param_positional_override(self): + scenario_content = """ +struct test_struct: + param1: string = "val1" + param2: string = "val2" + +action test_action: + struct_param: test_struct + +scenario test: + do serial: + test_action() with: + keep(it.struct_param == test_struct('OVERRIDE')) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + behavior = model._ModelElement__children[2]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + params = behavior.get_resolved_value() + self.assertEqual(params, {'struct_param': {'param1': 'OVERRIDE', 'param2': 'val2'}}) + + def test_behavior_struct_param_partially_named_positional_override(self): + scenario_content = """ +struct test_struct: + param1: string = "val1" + param2: string = "val2" + param3: string = "val3" + +action test_action: + struct_param: test_struct + +scenario test: + do serial: + test_action() with: + keep(it.struct_param == test_struct('OVERRIDE1', param3: 'OVERRIDE3')) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + behavior = model._ModelElement__children[2]._ModelElement__children[0]._ModelElement__children[0]._ModelElement__children[0] + params = behavior.get_resolved_value() + self.assertEqual(params, {'struct_param': {'param1': 'OVERRIDE1', + 'param2': 'val2', 'param3': 'OVERRIDE3'}}) + + @unittest.skip(reason="requires porting") + def test_behavior_struct_param_spec_incomplete(self): + scenario_content = """ +struct test_struct: + param1: string = "val1" + param2: string + +action test_action: + struct_param: test_struct + +scenario test: + do serial: + test_action() with: + keep(it.struct_param == test_struct('OVERRIDE1')) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_base_vals(self): + scenario_content = """ +type length is SI(m: 1) +unit m of length is SI(m: 1, factor: 1) +type angle is SI(rad: 1) +unit rad of angle is SI(rad: 1, factor: 1) + +actor osc_object: + model: string + +struct position_3d: + x: length = 0m + y: length = 0m + z: length = 0m + +struct orientation_3d: + roll: angle = 0rad + pitch: angle = 0rad + yaw: angle = 0rad + +struct pose_3d: + position: position_3d + orientation: orientation_3d + +action osc_object.spawn: + spawn_pose: pose_3d + +actor differential_drive_robot inherits osc_object: + namespace: string = '' + +scenario nav2_simulation_nav_to_pose: + turtlebot4: differential_drive_robot with: + keep(it.model == 'topic:///robot_description') + do parallel: + turtlebot4.spawn() with: # spawn the robot + keep(it.spawn_pose.position.x == 0.0m) + keep(it.spawn_pose.position.y == 0.0m) + keep(it.spawn_pose.position.z == 0.1m) + keep(it.spawn_pose.orientation.yaw == 0.0rad) + keep(it.spawn_pose.orientation.roll == 1.0rad) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + pose_struct = model._ModelElement__children[7].get_resolved_value() + self.assertEqual({'position': {'x': 0., 'y': 0., 'z': 0.}, 'orientation': { + 'roll': 0., 'pitch': 0., 'yaw': 0.}}, pose_struct) + + behavior = model._ModelElement__children[10]._ModelElement__children[1]._ModelElement__children[0]._ModelElement__children[0].get_resolved_value( + ) + self.assertEqual({'spawn_pose': {'position': {'x': 0., 'y': 0., 'z': 0.1}, + 'orientation': {'roll': 1., 'pitch': 0., 'yaw': 0.}}}, behavior) diff --git a/scenario_execution_base/test/test_osc2_parser_enum.py b/scenario_execution_base/test/test_osc2_parser_enum.py new file mode 100644 index 00000000..8d640294 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_enum.py @@ -0,0 +1,152 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test enum parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + """ + Unit test for osc2_parser + """ + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_enum_ref(self): + scenario_content = """ +enum test_enum: [ + val1, + val2 +] +struct test: + param1: test_enum = test_enum!val1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[1] + self.assertEqual(test_struct.get_resolved_value(), {'param1': ('val1', 0)}) + + def test_enum_ref_invalid(self): + scenario_content = """ +enum test_enum: [ + val1, + val2 +] +struct test: + param1: test_enum = test_enum!UNKNOWN +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_enum_ref_invalid_type(self): + scenario_content = """ +enum test_enum: [ + val1, + val2 +] +struct test: + param1: test_enum = UNKNOWN!val1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_enum_ref_other_enum_type(self): + scenario_content = """ +enum other_enum: [ + val1, + val2 +] + +enum test_enum: [ + val1, + val2 +] + +struct test: + param1: test_enum = other_enum!val1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_enum_val_non_numeric(self): + scenario_content = """ +enum test_enum: [ + val1, + val2 +] + +struct test: + param1: test_enum = test_enum!val1 + param2: test_enum = test_enum!val2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[1] + self.assertEqual(test_struct.get_resolved_value(), {'param1': ('val1', 0), 'param2': ('val2', 1)}) + + def test_enum_partially_numeric(self): + scenario_content = """ +enum test_enum: [ + val1 = 4, + val2 +] + +struct test: + param1: test_enum = test_enum!val1 + param2: test_enum = test_enum!val2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[1] + self.assertEqual(test_struct.get_resolved_value(), {'param1': ('val1', 4), 'param2': ('val2', 5)}) + + def test_enum_fully_numeric(self): + scenario_content = """ +enum test_enum: [ + val1 = 4, + val2 = 19 +] + +struct test: + param1: test_enum = test_enum!val1 + param2: test_enum = test_enum!val2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[1] + self.assertEqual(test_struct.get_resolved_value(), {'param1': ('val1', 4), 'param2': ('val2', 19)}) diff --git a/scenario_execution_base/test/test_osc2_parser_event.py b/scenario_execution_base/test/test_osc2_parser_event.py new file mode 100644 index 00000000..e3acb307 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_event.py @@ -0,0 +1,53 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test event parsing +""" +import unittest +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestScenarioExectionSuccess(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_unknown_event(self): + scenario_content = """ +scenario test: + do serial: + emit UNKNOWN +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_event_success(self): + scenario_content = """ +scenario test: + event test1 + do serial: + emit test1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_keep.py b/scenario_execution_base/test/test_osc2_parser_keep.py new file mode 100644 index 00000000..b870c0b6 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_keep.py @@ -0,0 +1,49 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test keep parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_keep_override(self): + scenario_content = """ +actor osc_object + +actor differential_drive_robot inherits osc_object: + namespace: string = '' + +scenario nav2_simulation_nav_to_pose: + turtlebot4: differential_drive_robot with: + keep(it.namespace == 'test') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + robot = model._ModelElement__children[2]._ModelElement__children[0].get_resolved_value() + self.assertEqual({'namespace': 'test'}, robot) diff --git a/scenario_execution_base/test/test_osc2_parser_list.py b/scenario_execution_base/test/test_osc2_parser_list.py new file mode 100644 index 00000000..fcc4c716 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_list.py @@ -0,0 +1,143 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test list parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + """ + Unit test for osc2_parser + """ + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_invalid_listof(self): + scenario_content = """ +struct listoffoo + +global test: listoffoo +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_string_list(self): + scenario_content = """ +global test: list of string = ["foo", "bar"] +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + test_list = model._ModelElement__children[0].get_resolved_value() + self.assertEqual(["foo", "bar"], test_list) + + def test_empty_list(self): + scenario_content = """ +global test: list of string = [ ] +""" + _, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 1) + + def test_mixed_basetypes_list(self): + scenario_content = """ +global test: list of string = ["foo", 3] +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_struct_list(self): + scenario_content = """ +struct test_struct: + member: string +global test: list of test_struct = [test_struct('val1'), test_struct('val2')] +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + test_list = model._ModelElement__children[1].get_resolved_value() + self.assertEqual([{'member': 'val1'}, {'member': 'val2'}], test_list) + + def test_different_structs_in_list(self): + scenario_content = """ +struct test_struct: + member: string +struct second_struct: + member2: string +global test: list of test_struct = [test_struct('val1'), second_struct('invalid')] +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_assign_struct_list(self): + scenario_content = """ +struct test_struct: + member: string + +global test1: list of test_struct = [test_struct('val1'), test_struct('val2')] +global test2: list of test_struct = test1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + test1 = model._ModelElement__children[1].get_resolved_value() + test2 = model._ModelElement__children[2].get_resolved_value() + self.assertEqual([{'member': 'val1'}, {'member': 'val2'}], test1) + self.assertEqual([{'member': 'val1'}, {'member': 'val2'}], test2) + + def test_assign_basetype_list(self): + scenario_content = """ +global test1: list of float = [2.1, 4.3] +global test2: list of float = test1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + test1 = model._ModelElement__children[0].get_resolved_value() + test2 = model._ModelElement__children[1].get_resolved_value() + self.assertEqual([2.1, 4.3], test1) + self.assertEqual([2.1, 4.3], test2) + + def test_assign_wrong_basetype_list(self): + scenario_content = """ +global test1: list of float = [2.1, 4.3] +global test2: list of string = test1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_not_supported.py b/scenario_execution_base/test/test_osc2_parser_not_supported.py new file mode 100644 index 00000000..7caef966 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_not_supported.py @@ -0,0 +1,274 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test parsing error reporting for features that are not yet supported +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable, too-many-public-methods + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_method(self): + scenario_content = """ +actor test: + def get_value() -> float is external TEST() +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_cover(self): + scenario_content = """ +scenario test: + cover() +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_lt_expr(self): + scenario_content = """ +actor car: + current_position: float + keep(current_position < 100.0) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_gt_expr(self): + scenario_content = """ +actor car: + current_position: float + keep(current_position > 100.0) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_le_expr(self): + scenario_content = """ +actor car: + current_position: float + keep(current_position <= 100.0) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_ge_expr(self): + scenario_content = """ +actor car: + current_position: float + keep(current_position >= 100.0) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_range(self): + scenario_content = """ +global test: float = range(0,1) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_element_access(self): + scenario_content = """ +global foo: list of float +global test: float = foo[2] +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_type_test(self): + scenario_content = """ +global foo: float +global test: bool = foo.is(float) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_cast(self): + scenario_content = """ +global foo: float +global test: int = foo.as(int) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_sample(self): + scenario_content = """ +import osc.standard + +scenario simple_drive: + environment: environment + var sim_start_time: time = sample(environment.datetime, @root_phase.start) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_every(self): + scenario_content = """ +scenario test: + event test is every(1) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_rise(self): + scenario_content = """ +scenario test: + event test is rise(true) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_fall(self): + scenario_content = """ +scenario test: + event test is fall(true) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_modifier(self): + scenario_content = """ +modifier test +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_modifier_application(self): + scenario_content = """ +modifier test_modifier: + param1: string + +action test_action: + param2: string + +scenario test: + do serial: + test_action() with: + test_modifier(6) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_until(self): + scenario_content = """ +scenario test: + event ev + do serial: + test_action() with: + until @ev +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_call(self): + scenario_content = """ +scenario test: + do serial: + call log(true) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_remove_default(self): + scenario_content = """ +struct base: + param_base: string = "base" + +struct test: + param1: base = base with: + remove_default(it.param_base) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_record(self): + scenario_content = """ +scenario test: + record() +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_enum_extend(self): + scenario_content = """ +enum test: [a, b] +extend test: [c] +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_conditional_inheritance(self): + scenario_content = """ +struct vehicle: + is_electric: bool + +actor electric_vehicle inherits vehicle(is_electric == true) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_parameter.py b/scenario_execution_base/test/test_osc2_parser_parameter.py new file mode 100644 index 00000000..d2e2f710 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_parameter.py @@ -0,0 +1,522 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test parameter parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable, too-many-public-methods + """ + Unit test for osc2_parser + """ + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_invalid(self): + scenario_content = """ +invalid +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 1) + + def test_empty(self): + scenario_content = "" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertEqual([None], scenarios) + + def test_global_var(self): + scenario_content = """ +global level1: string = "hey!" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + param = model._ModelElement__children[0].get_resolved_value() + self.assertEqual(param, "hey!") + + def test_global_var_indirect_1(self): + scenario_content = """ +global level1: string = "hey!" +global level2: string = level1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(len(model._ModelElement__children), 2) + glob_param1 = model._ModelElement__children[0] + val1 = glob_param1.get_resolved_value() + self.assertEqual(val1, "hey!") + glob_param2 = model._ModelElement__children[1] + val2 = glob_param2.get_resolved_value() + self.assertEqual(val2, "hey!") + + def test_global_var_indirect_2(self): + scenario_content = """ +global level1: string = "hey!" +global level2: string = level1 +global level3: string = level2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[0].get_resolved_value(), 'hey!') + self.assertEqual(model._ModelElement__children[1].get_resolved_value(), 'hey!') + self.assertEqual(model._ModelElement__children[2].get_resolved_value(), 'hey!') + + def test_global_var_indirect_2_wrong_type(self): + scenario_content = """ +global level1: string = "hey!" +global level2: int = level1 +global level3: string = level2 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_global_var_indirect_3(self): + scenario_content = """ +global level1: string = "hey!" +global level2: string = level1 +global level3: string = level2 + +scenario test: + var test_var: string = level3 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual(model._ModelElement__children[0].get_resolved_value(), 'hey!') + self.assertEqual(model._ModelElement__children[1].get_resolved_value(), 'hey!') + self.assertEqual(model._ModelElement__children[2].get_resolved_value(), 'hey!') + self.assertEqual(model._ModelElement__children[3]._ModelElement__children[0].get_resolved_value(), 'hey!') + + def test_global_var_indirect_not_found(self): + scenario_content = """ +global level1: string = "hey!" +global level2: int = levelUNKNOWN +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_global_var_indirect_in_struct(self): + scenario_content = """ +global z_param: string = "z_global" +struct test_struct: + z: string = z_param +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual({'z': 'z_global'}, model._ModelElement__children[1].get_resolved_value()) + + def test_global_var_indirect_in_actor(self): + scenario_content = """ +global z_param: string = "z_global" +actor test_struct: + z: string = z_param +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual({'z': 'z_global'}, model._ModelElement__children[1].get_resolved_value()) + + def test_var_instance_unknown_type(self): + scenario_content = """ +scenario test: + test_pose: unknownType +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_var_instance_keep_not_it(self): + scenario_content = """ +struct pose3d: + z: string = "base" +scenario network_drop_straight: + test_pose: pose3d with: + keep(NO.z == "override") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_var_instance_keep_unknown_member(self): + scenario_content = """ +struct pose3d: + z: string = "base" +scenario network_drop_straight: + test_pose: pose3d with: + keep(it.UNKNOWN == "override") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_var_instance_keep_success(self): + scenario_content = """ +struct pose3d: + z: string = "base" +scenario network_drop_straight: + test_pose: pose3d with: + keep(it.z == "override") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + def test_var_instance_keep_not_equal(self): + scenario_content = """ +struct pose3d: + z: string = "base" +scenario network_drop_straight: + test_pose: pose3d with: + keep(it.z <= "override") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_struct_inheritance(self): + scenario_content = """ +struct base: + x: string = "base" + +struct derived inherits base: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual({'x': 'base', 'y': 'derived'}, + model._ModelElement__children[1].get_resolved_value()) + + def test_actor_inheritance(self): + scenario_content = """ +actor base: + x: string = "base" + +actor derived inherits base: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual({'x': 'base', 'y': 'derived'}, + model._ModelElement__children[1].get_resolved_value()) + + def test_actor_inheritance_invalid(self): + scenario_content = """ +actor derived inherits UNKNOWN: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + scenario_content = """ +action base: + x: string = "base" + +action derived inherits base: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + self.assertEqual({'x': 'base', 'y': 'derived'}, + model._ModelElement__children[1].get_resolved_value()) + + def test_action_inheritance_invalid(self): + scenario_content = """ +action derived inherits UNKNOWN: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_scenario_inheritance(self): + scenario_content = """ +scenario base: + x: string = "base" + +scenario derived inherits base: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + derived = model._ModelElement__children[1] + self.assertEqual({'x': 'base', 'y': 'derived'}, derived.get_resolved_value()) + + def test_scenario_inheritance_invalid(self): + scenario_content = """ +scenario derived inherits UNKNOWN: + y: string = "derived" +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_parameter_to_dict(self): + scenario_content = """ +struct test_struct: + x: string = "value_x" + y: string = "value_y" + +scenario test: + foo: test_struct with: + keep(it.x == "override_x") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + param = model._ModelElement__children[1]._ModelElement__children[0] + values = param.get_resolved_value() + self.assertEqual({"x": "override_x", "y": "value_y"}, values) + + def test_struct_with_keep(self): + scenario_content = """ +struct test_struct: + x: string = "value_x" + y: string = "value_y" + +global foo: test_struct with: + keep(it.x == "override_x") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + param = model._ModelElement__children[1] + values = param.get_resolved_value() + self.assertEqual({"x": "override_x", "y": "value_y"}, values) + + @unittest.skip(reason="requires porting") + def test_struct_with_keep_member_unknown(self): + scenario_content = """ +struct test_struct: + x: string = "value_x" + y: string = "value_y" + +global foo: test_struct with: + keep(it.UNKNOWN == "override_x") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + param = model._ModelElement__children[1] + values = param.get_resolved_value() # parse should already fail! + + def test_parameter_to_dict_two_level(self): + scenario_content = """ +struct base_struct: + x: string = "base_x" + y: string = "base_y" + +struct test_struct inherits base_struct: + z: string = "value_z" + +scenario test: + foo: test_struct with: + keep(it.x == "override_x") +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + param = model._ModelElement__children[2]._ModelElement__children[0] + values = param.get_resolved_value() + self.assertEqual({"x": "override_x", "y": "base_y", "z": "value_z"}, values) + + def test_parameter_struct_in_struct(self): + scenario_content = """ +struct base_struct: + a: string = "base_a" + b: string = "base_b" + +struct test_struct: + x: string = "value_x" + y: base_struct +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + base_struct = model._ModelElement__children[0] + + values = base_struct.get_resolved_value() + self.assertEqual({"a": "base_a", "b": "base_b"}, values) + test_struct = model._ModelElement__children[1] + values = test_struct.get_resolved_value() + self.assertEqual({"x": "value_x", "y": {"a": "base_a", "b": "base_b"}}, values) + + def test_parameter_struct_in_struct_in_struct(self): + scenario_content = """ +struct base_struct: + a: string = "base_a" + +struct l1_struct: + b: string = "value_x" + c: base_struct + +struct l2_struct: + d: string = "value_x" + e: l1_struct +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + base_struct = model._ModelElement__children[0] + self.assertEqual({"a": "base_a"}, base_struct.get_resolved_value()) + l1_struct = model._ModelElement__children[1] + self.assertEqual({'b': 'value_x', 'c': {'a': 'base_a'}}, l1_struct.get_resolved_value()) + l2_struct = model._ModelElement__children[2] + self.assertEqual({'d': 'value_x', 'e': {'b': 'value_x', 'c': { + 'a': 'base_a'}}}, l2_struct.get_resolved_value()) + + def test_unknown_type(self): + scenario_content = """ +type length is SI(m: 1) +unit cm of length is SI(m: 1, factor: 0.01) + +global val1: UNKNOWN +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) + + def test_struct_param_default(self): + scenario_content = """ +struct test_struct: + param1: string = "val1" + param2: string = "val2" + +global test_struct1: test_struct = test_struct(param2: 'OVERRIDE') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct1 = model._ModelElement__children[1] + self.assertEqual({'param1': 'val1', 'param2': 'OVERRIDE'}, + test_struct1.get_resolved_value()) + + def test_struct_param_function_wrong_type(self): + scenario_content = """ +struct other_type: + param2: string = "val2" + +struct test_struct: + param1: string = "val1" + param2: string = "val2" + +global test_struct1: test_struct = other_type(param2: 'OVERRIDE') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_struct_assigned_empty(self): + scenario_content = """ +struct base_struct: + base_param1: string = "base1" + +struct test_struct: + param_base_struct: base_struct = base_struct() +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[1] + self.assertEqual({'param_base_struct': {'base_param1': 'base1'}}, + test_struct.get_resolved_value()) + + def test_struct_assigned_with_params(self): + scenario_content = """ +struct base_struct: + base_param1: string = "base1" + +struct test_struct: + param_base_struct: base_struct = base_struct('OVERRIDE') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[1] + self.assertEqual({'param_base_struct': {'base_param1': 'OVERRIDE'}}, + test_struct.get_resolved_value()) + + def test_struct_assigned_by_var(self): + scenario_content = """ +struct base_struct: + base_param1: string = "base1" + +global test_struct1: base_struct = base_struct(base_param1: 'OVERRIDE') + +struct test_struct: + param_base_struct: base_struct = test_struct1 +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + test_struct = model._ModelElement__children[2] + self.assertEqual({'param_base_struct': {'base_param1': 'OVERRIDE'}}, + test_struct.get_resolved_value()) diff --git a/scenario_execution_base/test/test_osc2_parser_physical_type.py b/scenario_execution_base/test/test_osc2_parser_physical_type.py new file mode 100644 index 00000000..1643d7cc --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_physical_type.py @@ -0,0 +1,65 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test physical type parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_success(self): + scenario_content = """ + +type length is SI(m: 1) +unit m of length is SI(m: 1, factor: 1) +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +action odometry_distance_traveled: + distance: length = 3m +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + action = model._ModelElement__children[4].get_resolved_value() + self.assertEqual({'distance': 3.0}, action) + + def test_wrong_type(self): + scenario_content = """ + +type length is SI(m: 1) +unit m of length is SI(m: 1, factor: 1) +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +action odometry_distance_traveled: + distance: length = 3s +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_si.py b/scenario_execution_base/test/test_osc2_parser_si.py new file mode 100644 index 00000000..21781cdc --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_si.py @@ -0,0 +1,81 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test si parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_si_invalid_type(self): + scenario_content = """ +type length is SI(m: 1) +unit cm of length is SI(m: 1, factor: 0.01) + +global val1: string = 3.2cm +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) + + def test_si(self): + scenario_content = """ +type length is SI(m: 1) +unit cm of length is SI(m: 1, factor: 0.01) + +global val1: length = 3.2cm +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + param = model._ModelElement__children[2] + self.assertEqual(param.get_resolved_value(), 0.032) + + def test_si_naming(self): + scenario_content = """ +type length is SI(m: 1) +unit m of length is SI(m: 1, factor: 1) +global val1: length = 3.2m +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + param = model._ModelElement__children[2] + self.assertEqual(param.get_resolved_value(), 3.2) + + def test_si_unknown_type(self): + scenario_content = """ +type length is SI(m: 1) +unit m of UNKNOWN is SI(m: 1, factor: 1) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc") + self.assertIsNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_struct.py b/scenario_execution_base/test/test_osc2_parser_struct.py new file mode 100644 index 00000000..04967960 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_struct.py @@ -0,0 +1,178 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test struct parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_all_struct_def(self): + scenario_content = """ +global level1: string = "hey!" +global level2: string = level1 +global override: string = "override" + +struct base_struct: + base_param1: string = level2 + +struct struct1a: + struct_param: base_struct + +struct struct1b: + struct_param: base_struct = base_struct() + +struct struct1c: + struct_param: base_struct = base_struct + +struct struct2a: + struct_param: base_struct = base_struct(base_param1: "override") + +struct struct2b: + struct_param: base_struct = base_struct(base_param1: override) + +struct struct2c: + struct_param: base_struct = base_struct("override") + +struct struct2d: + struct_param: base_struct = base_struct(override) + +scenario test: + struct2e: struct1a with: + keep(it.struct_param == base_struct('override')) + + struct2f: struct1a with: + keep(it.struct_param == base_struct(base_param1: 'override')) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + struct1a = model._ModelElement__children[4].get_resolved_value() + struct1b = model._ModelElement__children[5].get_resolved_value() + struct1c = model._ModelElement__children[6].get_resolved_value() + struct2a = model._ModelElement__children[7].get_resolved_value() + struct2b = model._ModelElement__children[8].get_resolved_value() + struct2c = model._ModelElement__children[9].get_resolved_value() + struct2d = model._ModelElement__children[10].get_resolved_value() + struct2e = model._ModelElement__children[11]._ModelElement__children[0].get_resolved_value() + struct2f = model._ModelElement__children[11]._ModelElement__children[1].get_resolved_value() + self.assertEqual({'struct_param': {'base_param1': 'hey!'}}, struct1a) + self.assertEqual({'struct_param': {'base_param1': 'hey!'}}, struct1b) + self.assertEqual({'struct_param': {'base_param1': 'hey!'}}, struct1c) + self.assertEqual({'struct_param': {'base_param1': 'override'}}, struct2a) + self.assertEqual({'struct_param': {'base_param1': 'override'}}, struct2b) + self.assertEqual({'struct_param': {'base_param1': 'override'}}, struct2c) + self.assertEqual({'struct_param': {'base_param1': 'override'}}, struct2d) + self.assertEqual({'struct_param': {'base_param1': 'override'}}, struct2e) + self.assertEqual({'struct_param': {'base_param1': 'override'}}, struct2f) + + def test_multi_layer(self): + scenario_content = """ +struct base_struct: + param1: string = 'test' + +struct l1_struct: + base: base_struct + +struct l2_struct: + l1: l1_struct + +scenario test: + struct1: l2_struct with: + keep(it.l1 == l1_struct(base: base_struct)) + + struct2: l2_struct with: + keep(it.l1 == l1_struct(base: base_struct('override'))) + + struct3: l2_struct with: + keep(it.l1 == l1_struct(base_struct('override'))) + + struct4: l2_struct with: + keep(it.l1.base.param1 == 'override') + + struct5: l2_struct with: + keep(it.l1.base == base_struct('override')) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + struct1 = model._ModelElement__children[3]._ModelElement__children[0].get_resolved_value() + struct2 = model._ModelElement__children[3]._ModelElement__children[1].get_resolved_value() + struct3 = model._ModelElement__children[3]._ModelElement__children[2].get_resolved_value() + struct4 = model._ModelElement__children[3]._ModelElement__children[3].get_resolved_value() + struct5 = model._ModelElement__children[3]._ModelElement__children[4].get_resolved_value() + self.assertEqual({'l1': {'base': {'param1': 'test'}}}, struct1) + self.assertEqual({'l1': {'base': {'param1': 'override'}}}, struct2) + self.assertEqual({'l1': {'base': {'param1': 'override'}}}, struct3) + self.assertEqual({'l1': {'base': {'param1': 'override'}}}, struct4) + self.assertEqual({'l1': {'base': {'param1': 'override'}}}, struct5) + + def test_sub_struct_assignment(self): + scenario_content = """ +struct base_struct: + param1: string = 'test' + +struct l1_struct: + base: base_struct + +struct l2_struct: + l1: l1_struct + +scenario test: + struct4: l2_struct with: + keep(it.l1.base.param1 == 'override') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + struct1 = model._ModelElement__children[3]._ModelElement__children[0].get_resolved_value() + self.assertEqual({'l1': {'base': {'param1': 'override'}}}, struct1) + + def test_sub_struct_invalid_membername(self): + scenario_content = """ +struct base_struct: + param1: string = 'test' + +struct l1_struct: + base: base_struct + +struct l2_struct: + l1: l1_struct + +scenario test: + struct4: l2_struct with: + keep(it.l1.UNKNOWN.param1 == 'override') +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNone(model) diff --git a/scenario_execution_base/test/test_osc2_parser_wait.py b/scenario_execution_base/test/test_osc2_parser_wait.py new file mode 100644 index 00000000..cb5dbf3a --- /dev/null +++ b/scenario_execution_base/test/test_osc2_parser_wait.py @@ -0,0 +1,93 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test wait parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_wait_success(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +scenario test: + do serial: + wait elapsed(1s) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + model = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(model) + + def test_wait_invalid(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +scenario test: + do serial: + wait(1s) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNone(scenarios) + + def test_wait_invalid_literal(self): + scenario_content = """ +scenario test: + do serial: + wait(1) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + model = create_py_tree(model, self.parser.logger) + self.assertIsNone(model) + + def test_wait_invalid_literal2(self): + scenario_content = """ +scenario test: + do serial: + wait elapsed(1) +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + + model = create_py_tree(model, self.parser.logger) + self.assertIsNone(model) diff --git a/scenario_execution_base/test/test_osc2_standard_osc.py b/scenario_execution_base/test/test_osc2_standard_osc.py new file mode 100644 index 00000000..0ffdd670 --- /dev/null +++ b/scenario_execution_base/test/test_osc2_standard_osc.py @@ -0,0 +1,40 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test standard.osc parsing +""" +import unittest + +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + + def test_standard_osc(self): + scenario_content = """ +import osc.standard +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) diff --git a/scenario_execution_base/test/test_run_external_process.py b/scenario_execution_base/test/test_run_external_process.py new file mode 100644 index 00000000..f087e3bf --- /dev/null +++ b/scenario_execution_base/test/test_run_external_process.py @@ -0,0 +1,89 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import unittest +import rclpy +from scenario_execution import ROSScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestScenarioExecutionSuccess(unittest.TestCase): + # pylint: disable=missing-function-docstring + + @classmethod + def setUpClass(cls): + rclpy.init() + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ROSScenarioExecution() + + def test_failure(self): + scenario_content = """ +import osc.standard +import osc.helpers + +scenario test_run_external_process: + do parallel: + serial: + run_external_process() with: + keep(it.command == 'false') + emit end + time_out: serial: + wait elapsed(10s) + time_out_shutdown: emit fail +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertFalse(ret) + + def test_success(self): + scenario_content = """ +import osc.standard +import osc.helpers + +scenario test_run_external_process: + do parallel: + serial: + run_external_process() with: + keep(it.command == 'true') + emit end + time_out: serial: + wait elapsed(10s) + time_out_shutdown: emit fail +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) diff --git a/scenario_execution_base/test/test_scenario_events.py b/scenario_execution_base/test/test_scenario_events.py new file mode 100644 index 00000000..7fa627fc --- /dev/null +++ b/scenario_execution_base/test/test_scenario_events.py @@ -0,0 +1,92 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test predefined events +""" +import unittest +from scenario_execution_base import ScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ScenarioExecution(debug=True, log_model=True, live_tree=True, scenario='test.osc', test_output="") + + def test_failure(self): + scenario_content = """ +scenario test: + do serial: + emit fail +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertFalse(ret) + + def test_success(self): + scenario_content = """ +scenario test: + do serial: + emit end +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) + + def test_wait_for_event(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +scenario test: + event test + do parallel: + serial: + wait elapsed(1s) + emit test + wait elapsed(10s) + emit fail + serial: + wait @test + emit end +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) diff --git a/scenario_execution_base/test/test_scenario_oneof.py b/scenario_execution_base/test/test_scenario_oneof.py new file mode 100644 index 00000000..466d48dc --- /dev/null +++ b/scenario_execution_base/test/test_scenario_oneof.py @@ -0,0 +1,63 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test oneof parsing +""" +import unittest +from datetime import datetime + +from scenario_execution_base.scenario_execution import ScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ScenarioExecution(debug=True, log_model=True, live_tree=True, scenario='test.osc', test_output="") + + def test_oneof(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +scenario test: + do serial: + one_of: + wait elapsed(120s) + wait elapsed(5s) + emit end +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + + start_time = datetime.now() + ret = self.scenario_execution.run() + end_time = datetime.now() + self.assertTrue(ret) + + delta = end_time - start_time + self.assertLess(delta.total_seconds(), 15.) diff --git a/scenario_execution_base/test/test_scenario_parallel.py b/scenario_execution_base/test/test_scenario_parallel.py new file mode 100644 index 00000000..bc4ac96f --- /dev/null +++ b/scenario_execution_base/test/test_scenario_parallel.py @@ -0,0 +1,63 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Test parallel parsing +""" +import unittest + +from scenario_execution_base.scenario_execution import ScenarioExecution +from scenario_execution_base.model.osc2_parser import OpenScenario2Parser +from scenario_execution_base.model.model_to_py_tree import create_py_tree +from scenario_execution_base.utils.logging import Logger +from antlr4.InputStream import InputStream + + +class TestOSC2Parser(unittest.TestCase): + # pylint: disable=missing-function-docstring, protected-access, no-member, unused-variable + """ + Unit test for osc2_parser + """ + + def setUp(self) -> None: + self.parser = OpenScenario2Parser(Logger('test')) + self.scenario_execution = ScenarioExecution(debug=True, log_model=True, live_tree=True, scenario='test.osc', test_output="") + + def test_parallel(self): + scenario_content = """ +type time is SI(s: 1) +unit s of time is SI(s: 1, factor: 1) + +scenario test: + do serial: + parallel: + serial: + wait elapsed(5s) + emit end + serial: + wait elapsed(1s) + wait elapsed(1s) + emit fail +""" + parsed_tree, errors = self.parser.parse_input_stream(InputStream(scenario_content)) + self.assertEqual(errors, 0) + model = self.parser.create_internal_model(parsed_tree, "test.osc", True) + self.assertIsNotNone(model) + scenarios = create_py_tree(model, self.parser.logger) + self.assertIsNotNone(scenarios) + self.scenario_execution.scenarios = scenarios + ret = self.scenario_execution.run() + self.assertTrue(ret) diff --git a/scenario_execution_control/CMakeLists.txt b/scenario_execution_control/CMakeLists.txt new file mode 100644 index 00000000..973ed60f --- /dev/null +++ b/scenario_execution_control/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 2.8.3) +project(scenario_execution_control) + +find_package(ament_cmake REQUIRED) +find_package(rclpy REQUIRED) +ament_export_dependencies(rclpy) + +# Install launch files. +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + +ament_package() diff --git a/scenario_execution_control/README.md b/scenario_execution_control/README.md new file mode 100644 index 00000000..0238390f --- /dev/null +++ b/scenario_execution_control/README.md @@ -0,0 +1,4 @@ +# Scenario Execution Control + +The `scenario_execution_control` package provides code to control scenarios (in ROS2) from another application such as RViz. + diff --git a/scenario_execution_control/launch/scenario_execution_control_launch.py b/scenario_execution_control/launch/scenario_execution_control_launch.py new file mode 100644 index 00000000..647086c1 --- /dev/null +++ b/scenario_execution_control/launch/scenario_execution_control_launch.py @@ -0,0 +1,50 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + + launch.actions.DeclareLaunchArgument( + 'scenario_dir', description='Directory containing osc2 scenario files'), + + launch_ros.actions.Node( + package='scenario_execution_control', + executable='scenario_execution_control', + name='scenario_execution_control', + output='screen', + emulate_tty='True', + on_exit=launch.actions.Shutdown(), + ), + launch_ros.actions.Node( + package='scenario_execution_control', + executable='scenario_list_publisher', + name='scenario_list_publisher', + output='screen', + on_exit=launch.actions.Shutdown(), + parameters=[ + {'directory': launch.substitutions.LaunchConfiguration('scenario_dir')}, + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/scenario_execution_control/package.xml b/scenario_execution_control/package.xml new file mode 100644 index 00000000..f0d48cb5 --- /dev/null +++ b/scenario_execution_control/package.xml @@ -0,0 +1,19 @@ + + + scenario_execution_control + 1.0.0 + Scenario Execution Control + Intel Labs + Intel Labs + Apache-2.0 + + scenario_execution_interfaces + std_srvs + scenario_execution + + rclpy + + + ament_python + + diff --git a/scenario_execution_control/resource/scenario_execution_control b/scenario_execution_control/resource/scenario_execution_control new file mode 100644 index 00000000..e69de29b diff --git a/scenario_execution_control/setup.cfg b/scenario_execution_control/setup.cfg new file mode 100644 index 00000000..af6d2832 --- /dev/null +++ b/scenario_execution_control/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/scenario_execution_control +[install] +install_scripts=$base/lib/scenario_execution_control \ No newline at end of file diff --git a/scenario_execution_control/setup.py b/scenario_execution_control/setup.py new file mode 100644 index 00000000..8bda59b4 --- /dev/null +++ b/scenario_execution_control/setup.py @@ -0,0 +1,48 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Setup for scenario_execution_control +""" +import os +from glob import glob + +from setuptools import setup + +PACKAGE_NAME = 'scenario_execution_control' +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=[PACKAGE_NAME], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + PACKAGE_NAME]), + (os.path.join('share', PACKAGE_NAME), ['package.xml']), + (os.path.join('share', PACKAGE_NAME), glob('launch/*launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Scenario Execution Control', + license='Apache License 2.0', + entry_points={ + 'console_scripts': [ + 'scenario_execution_control = scenario_execution_control.scenario_execution_control_node:main', + 'scenario_list_publisher = scenario_execution_control.scenario_list_publisher:main' + ], + }, + package_dir={'': 'src'}, +) diff --git a/scenario_execution_control/src/scenario_execution_control/__init__.py b/scenario_execution_control/src/scenario_execution_control/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_control/src/scenario_execution_control/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_control/src/scenario_execution_control/application_runner.py b/scenario_execution_control/src/scenario_execution_control/application_runner.py new file mode 100755 index 00000000..2b2c5bd9 --- /dev/null +++ b/scenario_execution_control/src/scenario_execution_control/application_runner.py @@ -0,0 +1,167 @@ +#!/usr/bin/env python +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +""" +Execute an application. +""" +from enum import Enum +from threading import Thread, Event +from datetime import datetime, timedelta +import pexpect # pylint: disable=import-error + + +class ApplicationStatus(Enum): + """ + States of an application + """ + STOPPED = 0 + STARTING = 1 + RUNNING = 2 + SHUTTINGDOWN = 3 + ERROR = 4 + + +class ApplicationRunner(object): + + """ + Execute application + """ + + def __init__(self, status_updated_fct, log_fct, ready_string=""): + """ + Constructor + """ + self._app_thread = None + self._status_updated_fct = status_updated_fct + self._log_fct = log_fct + self._shutdown_requested_event = Event() + self._ready_string = ready_string + + def execute(self, cmdline, env=None, cwd=None): + """ + Starts a thread to execute the application + """ + if self.is_running(): + self._log_fct("Application already running!") + return False + + self._shutdown_requested_event.clear() + self._app_thread = Thread(target=self.start_and_run, args=(cmdline, + env, + cwd, + self._shutdown_requested_event, + self._ready_string, + self._status_updated_fct, + self._log_fct,)) + self._app_thread.start() + + return True + + def start_and_run(self, cmdline, env, cwd, shutdown_requested_event, ready_string, # pylint: disable=too-many-arguments + status_updated_fct, log_fct): + """ + thread function + """ + status_updated_fct(ApplicationStatus.STARTING) + try: + process = self.start_process(cmdline, log_fct, env=env, cwd=cwd) + self.run(process, shutdown_requested_event, ready_string, status_updated_fct, log_fct) + except (KeyError, pexpect.ExceptionPexpect) as e: + self._log_fct("Error while starting process: {}".format(e)) + status_updated_fct(ApplicationStatus.ERROR) + + def is_running(self): + """ + returns if the application is still running + """ + if self._app_thread is None: + return False + + return self._app_thread.is_alive() + + def shutdown(self): + """ + Shut down the application thread + """ + if not self.is_running(): + return + self._log_fct("Requesting shutdown...") + self._status_updated_fct(ApplicationStatus.SHUTTINGDOWN) + self._shutdown_requested_event.set() + if self._app_thread: + self._app_thread.join() + self._log_fct("Shutdown finished.") + + def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: disable=no-self-use + """ + Starts a process. + """ + if not argument_list: + raise KeyError("No arguments given!") + if not isinstance(argument_list, str): + executable = " ".join(argument_list) + else: + executable = argument_list + + log_fct("Executing: " + executable) + process = pexpect.spawn(executable, env=env, cwd=cwd, encoding='utf-8') + # process.logfile_read = sys.stdout + + return process + + def run(self, process, shutdown_requested_event, ready_string, status_updated_fct, log_fct): # pylint: disable=no-self-use,too-many-arguments + """ + Threaded application execution + + :return: + """ + shutting_down_trigger_time = None + signaled_running = False + while True: + if shutdown_requested_event.is_set(): + if shutting_down_trigger_time is None: + shutting_down_trigger_time = datetime.now() + log_fct("Shutdown requested while process is still running. Sending SIGHUP/SIGINT...") + process.terminate(force=False) + else: + if (datetime.now() - shutting_down_trigger_time) > timedelta(seconds=8): + log_fct("Waited 8s for application to exit. Forcing Shutdown. \ + Sending SIGKILL") + process.terminate(force=True) + try: + process.expect(".*\n", timeout=0.1) + log_fct(process.after.strip()) + if not signaled_running: + if str(process.after).find(ready_string) != -1: + status_updated_fct(ApplicationStatus.RUNNING) + log_fct("Application is ready.") + signaled_running = True + except pexpect.EOF: + # application exited + log_fct(process.before.strip()) + log_fct("Application exited. Exiting run loop") + break + except pexpect.TIMEOUT: + # no output received + pass + + process.close() + if process.exitstatus == 0: + status_updated_fct(ApplicationStatus.STOPPED) + else: + status_updated_fct(ApplicationStatus.ERROR) diff --git a/scenario_execution_control/src/scenario_execution_control/scenario_execution_control_node.py b/scenario_execution_control/src/scenario_execution_control/scenario_execution_control_node.py new file mode 100755 index 00000000..dbc18884 --- /dev/null +++ b/scenario_execution_control/src/scenario_execution_control/scenario_execution_control_node.py @@ -0,0 +1,165 @@ +#!/usr/bin/env python +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Execute scenarios via ros service +""" + +import os +import rclpy +from rclpy.node import Node +from rclpy.qos import QoSProfile, DurabilityPolicy + +from scenario_execution_control.application_runner import ApplicationStatus # pylint: disable=relative-import +from scenario_execution_control.scenario_execution_runner import ScenarioExecutionRunner # pylint: disable=relative-import + +from std_srvs.srv import Empty +from scenario_execution_interfaces.srv import ExecuteScenario +from scenario_execution_interfaces.msg import ScenarioExecutionStatus + + +class ScenarioExecutionControl(Node): + """ + Execute scenarios via ros service + """ + + def __init__(self): + """ + Constructor + """ + super(ScenarioExecutionControl, self).__init__('scenario_execution_control') + self.shutdown_requested = False + self._status_publisher = self.create_publisher( + ScenarioExecutionStatus, + "/scenario_execution_control/status", + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) + self.scenario_execution_status_updated(ApplicationStatus.STOPPED) + self._scenario_execution = ScenarioExecutionRunner( + self.scenario_execution_status_updated, + self.scenario_execution_log) + self._execute_scenario_service = self.create_service( + ExecuteScenario, + '/scenario_execution_control/execute_scenario', + self.execute_scenario) + self._stop_scenario_service = self.create_service( + Empty, + '/scenario_execution_control/stop_scenario', + self.stop_scenario) + + def scenario_execution_log(self, log): # pylint: disable=no-self-use + """ + Callback for application logs + """ + self.get_logger().warn(f"[SC]{log}") + + def scenario_execution_status_updated(self, status): + """ + Executed from application runner whenever the status changed + """ + self.get_logger().info(f"Status updated to {status}") + val = ScenarioExecutionStatus.STOPPED + if status == ApplicationStatus.STOPPED: + val = ScenarioExecutionStatus.STOPPED + elif status == ApplicationStatus.STARTING: + val = ScenarioExecutionStatus.STARTING + elif status == ApplicationStatus.RUNNING: + val = ScenarioExecutionStatus.RUNNING + elif status == ApplicationStatus.SHUTTINGDOWN: + val = ScenarioExecutionStatus.SHUTTINGDOWN + else: + if self.shutdown_requested: + val = ScenarioExecutionStatus.STOPPED + else: + val = ScenarioExecutionStatus.ERROR + status = ScenarioExecutionStatus() + status.status = val + self._status_publisher.publish(status) + + def execute_scenario(self, req, response=None): + """ + Execute a scenario + """ + self.get_logger().info(f"Scenario Execution requested ({req.scenario.scenario_file})...") + + response = ExecuteScenario.Response() + response.result = True + if not os.path.isfile(req.scenario.scenario_file): + self.get_logger().warn( + f"Requested scenario file not existing {req.scenario.scenario_file}") + response.result = False + else: + self.executor.create_task(self.run, req.scenario) + return response + + def stop_scenario(self, _, response=None): + """ + Stop current scenario + """ + response = Empty.Response() + + if self._scenario_execution.is_running(): + self.get_logger().info(f"Scenario Stop requested...") + self.shutdown_requested = True + self._scenario_execution.shutdown() + self.get_logger().info("Scenario Execution stopped.") + else: + self.get_logger().info("Scenario Stop requested, but not Scenario running.") + return response + + def run(self, task): + current_req = task + if self._scenario_execution.is_running(): + self.get_logger().info("Scenario Execution currently running. Shutting down.") + self._scenario_execution.shutdown() + self.get_logger().info("Scenario Execution stopped.") + self.get_logger().info(f"Executing scenario ({current_req.scenario_file})...") + + # execute scenario + self.shutdown_requested = False + scenario_executed = self._scenario_execution.execute_scenario(current_req.scenario_file) + if not scenario_executed: + self.get_logger().warn("Unable to execute scenario.") + + +def main(args=None): + """ + + main function + + :return: + """ + rclpy.init(args=args) + scenario_execution_control = ScenarioExecutionControl() + + executor = rclpy.executors.MultiThreadedExecutor() + executor.add_node(scenario_execution_control) + + try: + executor.spin() + except KeyboardInterrupt: + scenario_execution_control.get_logger().info("User requested shut down.") + finally: + if scenario_execution_control._scenario_execution.is_running(): # pylint: disable=protected-access + scenario_execution_control.get_logger().info("Scenario Execution still running. Shutting down.") + scenario_execution_control._scenario_execution.shutdown() # pylint: disable=protected-access + del scenario_execution_control + + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/scenario_execution_control/src/scenario_execution_control/scenario_execution_runner.py b/scenario_execution_control/src/scenario_execution_control/scenario_execution_runner.py new file mode 100755 index 00000000..38013745 --- /dev/null +++ b/scenario_execution_control/src/scenario_execution_control/scenario_execution_runner.py @@ -0,0 +1,43 @@ +#!/usr/bin/env python +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Run scenario execution +""" +import os + +from scenario_execution_control.application_runner import ApplicationRunner # pylint: disable=relative-import + + +class ScenarioExecutionRunner(ApplicationRunner): + """ + Executes scenario execution + """ + + def __init__(self, status_updated_fct, log_fct): # pylint: disable=too-many-arguments + super(ScenarioExecutionRunner, self).__init__( + status_updated_fct, + log_fct, + "Executing scenario ") + + def execute_scenario(self, scenario_file): + """ + Executes scenario + """ + cmdline = ["ros2", "run", "scenario_execution", "scenario_execution", scenario_file] + + return self.execute(cmdline, env=os.environ) diff --git a/scenario_execution_control/src/scenario_execution_control/scenario_list_publisher.py b/scenario_execution_control/src/scenario_execution_control/scenario_list_publisher.py new file mode 100755 index 00000000..b5845d8e --- /dev/null +++ b/scenario_execution_control/src/scenario_execution_control/scenario_list_publisher.py @@ -0,0 +1,67 @@ +#!/usr/bin/env python3 +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +import os +import rclpy +from rclpy.qos import QoSProfile, QoSDurabilityPolicy, QoSHistoryPolicy, QoSReliabilityPolicy +from rclpy.node import Node + +from scenario_execution_interfaces.msg import ScenarioList, Scenario + + +class ScenarioListPublisher(Node): + + def __init__(self): + super().__init__('scenario_list_publisher') + + transient_local_qos = QoSProfile( + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + reliability=QoSReliabilityPolicy.RELIABLE, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1) + self.publisher = self.create_publisher( + ScenarioList, '/scenario_execution_control/available_scenarios', transient_local_qos) + + self.declare_parameter('directory', '.') + scenario_dir = self.get_parameter('directory').value + + scenarios = ScenarioList() + for f in os.listdir(scenario_dir): + path = os.path.join(scenario_dir, f) + if os.path.isfile(path) and path.endswith('.osc'): + name = os.path.splitext(os.path.basename(path))[0] + scenarios.scenarios.append(Scenario(name=name, scenario_file=path)) + self.publisher.publish(scenarios) + + +def main(args=None): + rclpy.init(args=args) + + node = ScenarioListPublisher() + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + + node.destroy_node() + # rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/scenario_execution_gazebo/README.md b/scenario_execution_gazebo/README.md new file mode 100644 index 00000000..6580cd49 --- /dev/null +++ b/scenario_execution_gazebo/README.md @@ -0,0 +1,8 @@ +# Scenario Execution Library for Gazebo + +The `scenario_execution_gazebo` package provides actions to interact with the Gazebo simulator. + +It provides the following scenario execution library: + +- `gazebo.osc`: Gazebo specific actions to interact with the simulation + diff --git a/scenario_execution_gazebo/package.xml b/scenario_execution_gazebo/package.xml new file mode 100644 index 00000000..eaeeab03 --- /dev/null +++ b/scenario_execution_gazebo/package.xml @@ -0,0 +1,28 @@ + + + + scenario_execution_gazebo + 1.0.0 + Scenario Execution library for Gazebo + Intel Labs + Intel Labs + Apache-2.0 + + scenario_execution + + rclpy + py_trees + nav2_bringup + turtlebot4_navigation + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + ignition-fortress + + + ament_python + + diff --git a/scenario_execution_gazebo/resource/scenario_execution_gazebo b/scenario_execution_gazebo/resource/scenario_execution_gazebo new file mode 100644 index 00000000..e69de29b diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/__init__.py b/scenario_execution_gazebo/scenario_execution_gazebo/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/actions/__init__.py b/scenario_execution_gazebo/scenario_execution_gazebo/actions/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/actions/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py new file mode 100644 index 00000000..64cc294d --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_actor_exists.py @@ -0,0 +1,99 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from scenario_execution_base.actions import RunExternalProcess + +import py_trees +from enum import Enum +import json + + +class ActorExistsActionState(Enum): + """ + States for executing a entity check in ignition + """ + IDLE = 1 + WAITING_FOR_ACTOR = 2 + DONE = 3 + FAILURE = 4 + + +class GazeboActorExists(RunExternalProcess): + """ + Class to check existance of an entity in Ignition + + """ + + def __init__(self, entity_name: str, world_name: str): + """ + init + """ + super().__init__('GazeboActorExistsAction') + self.entity_name = entity_name + self.node = None + self.set_command(["ign", "topic", "-t", "/world/" + + world_name + "/pose/info", "-e", "--json-output"]) + self.current_state = ActorExistsActionState.IDLE + + def on_executed(self): + """ + Hook when process gets executed + """ + self.feedback_message = f"Waiting for entity '{self.entity_name}'" # pylint: disable= attribute-defined-outside-init + self.current_state = ActorExistsActionState.WAITING_FOR_ACTOR + + def get_logger_stdout(self): + """ + get logger for stderr messages + """ + return None + + def check_running_process(self): + """ + hook to check running process + + return: + py_trees.common.Status + """ + if self.current_state == ActorExistsActionState.WAITING_FOR_ACTOR: + while True: + try: + line = self.output.popleft() + pose_state = json.loads(line) + for pose in pose_state['pose']: + if pose['name'] == self.entity_name: + self.feedback_message = f"Found entity '{self.entity_name}'" # pylint: disable= attribute-defined-outside-init + self.current_state = ActorExistsActionState.DONE + return py_trees.common.Status.SUCCESS + except IndexError: + break + return py_trees.common.Status.RUNNING + else: + self.current_state = ActorExistsActionState.FAILURE + return py_trees.common.Status.FAILURE + + def on_process_finished(self, _): + """ + check result of process + + return: + py_trees.common.Status + """ + if self.current_state == ActorExistsActionState.WAITING_FOR_ACTOR: + self.current_state = ActorExistsActionState.FAILURE + return py_trees.common.Status.FAILURE + else: + return py_trees.common.Status.INVALID diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py new file mode 100644 index 00000000..e9fa29ac --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_delete_actor.py @@ -0,0 +1,84 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +import py_trees +from enum import Enum + +from scenario_execution_base.actions import RunExternalProcess + + +class DeleteActionState(Enum): + """ + States for executing a delete-entity in gazebo + """ + IDLE = 1 + WAITING_FOR_RESPONSE = 2 + DONE = 3 + FAILURE = 4 + + +class GazeboDeleteActor(RunExternalProcess): + """ + Class to delete an entity in Ignition + + """ + + def __init__(self, name, entity_name: str, world_name: str): + """ + init + """ + super().__init__(name) + self.entity_name = entity_name + self.node = None + self.set_command(["ign", "service", "-s", "/world/" + world_name + "/remove", + "--reqtype", "ignition.msgs.Entity", + "--reptype", "ignition.msgs.Boolean", + "--timeout", "1000", "--req", "name: \"" + self.entity_name + "\" type: MODEL"]) + self.current_state = DeleteActionState.IDLE + + def on_executed(self): + """ + Hook when process gets executed + """ + self.current_state = DeleteActionState.WAITING_FOR_RESPONSE + + def on_process_finished(self, ret): + """ + check result of process + + return: + py_trees.common.Status + """ + if self.current_state == DeleteActionState.WAITING_FOR_RESPONSE: + if ret == 0: + while True: + try: + line = self.output.popleft() + line = line.lower() + if 'error' in line or 'timed out' in line: + self.feedback_message = f"Found error output while executing '{self.get_command()}'" # pylint: disable= attribute-defined-outside-init + self.current_state = DeleteActionState.FAILURE + return py_trees.common.Status.FAILURE + except IndexError: + break + self.current_state = DeleteActionState.DONE + return py_trees.common.Status.SUCCESS + else: + self.current_state = DeleteActionState.FAILURE + return py_trees.common.Status.FAILURE + else: + return py_trees.common.Status.INVALID diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py new file mode 100644 index 00000000..4ded795d --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_spawn_actor.py @@ -0,0 +1,190 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import subprocess # nosec B404 +from enum import Enum + +from transforms3d.taitbryan import euler2quat +from std_msgs.msg import String + +from rclpy.qos import QoSProfile, QoSDurabilityPolicy, QoSHistoryPolicy, QoSReliabilityPolicy +from rclpy.logging import get_logger +from rclpy.node import Node +import py_trees +from scenario_execution_base.actions import RunExternalProcess +from .utils import SpawnUtils + + +class SpawnActionState(Enum): + """ + States for executing a spawn-entity in gazebo + """ + WAITING_FOR_TOPIC = 1 + MODEL_AVAILABLE = 2 + WAITING_FOR_RESPONSE = 3 + DONE = 4 + FAILURE = 5 + + +class GazeboSpawnActor(RunExternalProcess): + """ + Class to spawn an entity into simulation + + """ + + def __init__(self, name, associated_actor, spawn_pose: list, world_name: str, xacro_arguments: list, model: str, **kwargs): + """ + init + """ + super().__init__(name, "") + self.entity_name = associated_actor["name"] + self.model_file = model + self.spawn_pose = spawn_pose + self.world_name = world_name + self.xacro_arguments = xacro_arguments + self.current_state = SpawnActionState.WAITING_FOR_TOPIC + self.node = None + self.logger = None + self.model_sub = None + self.sdf = None + self.utils = None + + def setup(self, **kwargs): + """ + Setup ROS2 node and model + + """ + try: + self.node: Node = kwargs['node'] + except KeyError as e: + error_message = "didn't find 'node' in setup's kwargs [{}][{}]".format( + self.name, self.__class__.__name__) + raise KeyError(error_message) from e + + self.logger = get_logger(self.name) + self.utils = SpawnUtils(logger=self.logger) + + if self.model_file.startswith('topic://'): + transient_local_qos = QoSProfile( + durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, + reliability=QoSReliabilityPolicy.RELIABLE, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1) + topic = self.model_file.replace('topic://', '', 1) + self.current_state = SpawnActionState.WAITING_FOR_TOPIC + self.feedback_message = f"Waiting for model on topic {topic}" # pylint: disable= attribute-defined-outside-init + self.model_sub = self.node.create_subscription( + String, topic, self.topic_callback, transient_local_qos) + else: + sdf = self.utils.parse_model_file( + self.model_file, self.entity_name, self.xacro_arguments) + + if sdf: + self.set_command(sdf) + else: + raise ValueError(f'Invalid model specified ({self.model_file})') + + def update(self) -> py_trees.common.Status: + """ + Send request + """ + if self.current_state == SpawnActionState.WAITING_FOR_TOPIC: + return py_trees.common.Status.RUNNING + else: + return super().update() + + def on_executed(self): + """ + Hook when process gets executed + """ + self.current_state = SpawnActionState.WAITING_FOR_RESPONSE + self.feedback_message = f"Executed spawning, waiting for response..." # pylint: disable= attribute-defined-outside-init + + def cleanup(self): + """ + Cleanup on shutdown + """ + self.logger.info(f"Deleting entity '{self.entity_name}' from simulation.") + if self.current_state in [SpawnActionState.WAITING_FOR_TOPIC, SpawnActionState.MODEL_AVAILABLE]: + return + + subprocess.run(["ign", "service", "-s", "/world/" + self.world_name + "/remove", # pylint: disable=subprocess-run-check + "--reqtype", "ignition.msgs.Entity", + "--reptype", "ignition.msgs.Boolean", + "--timeout", "1000", "--req", "name: \"" + self.entity_name + "\" type: MODEL"]) + + def on_process_finished(self, ret): + """ + check result of process + + return: + py_trees.common.Status + """ + if self.current_state == SpawnActionState.WAITING_FOR_RESPONSE: + if ret == 0: + while True: + try: + line = self.output.popleft() + line = line.lower() + if 'error' in line or 'timed out' in line: + self.logger.warn(line) + self.feedback_message = f"Found error output while executing '{self.command}'" # pylint: disable= attribute-defined-outside-init + self.current_state = SpawnActionState.FAILURE + return py_trees.common.Status.FAILURE + except IndexError: + break + self.current_state = SpawnActionState.DONE + return py_trees.common.Status.SUCCESS + else: + self.current_state = SpawnActionState.FAILURE + return py_trees.common.Status.FAILURE + else: + return py_trees.common.Status.INVALID + + def set_command(self, command): + """ + Set execution command + """ + # euler2quat() requires "zyx" convention, + # while in YAML, we define as pitch-roll-yaw (xyz), since it's more intuitive. + try: + quaternion = euler2quat(self.spawn_pose["orientation"]["yaw"], + self.spawn_pose["orientation"]["roll"], + self.spawn_pose["orientation"]["pitch"]) + pose = '{ position: {' \ + f' x: {self.spawn_pose["position"]["x"]} y: {self.spawn_pose["position"]["y"]} z: {self.spawn_pose["position"]["z"]}' \ + ' } orientation: {' \ + f' w: {quaternion[0]} x: {quaternion[1]} y: {quaternion[2]} z: {quaternion[3]}' \ + ' } }' + except KeyError as e: + raise ValueError("Could not get values") from e + super().set_command(["ign", "service", "-s", "/world/" + self.world_name + "/create", + "--reqtype", "ignition.msgs.EntityFactory", + "--reptype", "ignition.msgs.Boolean", + "--timeout", "30000", "--req", "pose: " + pose + " name: \"" + self.entity_name + "\" allow_renaming: false sdf: \"" + command + "\""]) + + self.logger.info(f'Command: {" ".join(self.get_command())}') + self.current_state = SpawnActionState.MODEL_AVAILABLE + + def topic_callback(self, msg): + ''' + Callback to receive model description from topic + ''' + + self.feedback_message = f"Model received from topic." # pylint: disable= attribute-defined-outside-init + self.logger.info("Received robot_description.") + self.node.destroy_subscription(self.model_sub) + self.set_command(msg.data.replace("\"", "\\\"").replace("\n", "")) diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py new file mode 100644 index 00000000..097ea082 --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/actions/gazebo_wait_for_sim.py @@ -0,0 +1,72 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import py_trees +from enum import Enum + +from scenario_execution_base.actions import RunExternalProcess + + +class WaitForSimulationActionState(Enum): + """ + States for waiting for the simulation + """ + IDLE = 1 + WAITING_FOR_SIM = 2 + DONE = 3 + FAILURE = 4 + + +class GazeboWaitForSim(RunExternalProcess): + """ + Class to wait for the simulation to become active + """ + + def __init__(self, name, world_name: str, **kwargs): + self.node = None + self.world_name = world_name + command = ["ign", "topic", "-t", "/world/" + + world_name + "/clock", "-e", "--json-output", "-n", "1"] + super().__init__(name, command) + self.current_state = WaitForSimulationActionState.IDLE + + def on_executed(self): + """ + Hook when process gets executed + """ + self.feedback_message = f"Waiting for simulation of world '{self.world_name}'" # pylint: disable= attribute-defined-outside-init + self.current_state = WaitForSimulationActionState.WAITING_FOR_SIM + + def get_logger_stdout(self): + """ + get logger for stderr messages + """ + return None + + def on_process_finished(self, _): + """ + check result of process + + return: + py_trees.common.Status + """ + if self.current_state == WaitForSimulationActionState.WAITING_FOR_SIM: + self.feedback_message = f"Simulation is running" # pylint: disable= attribute-defined-outside-init + self.current_state = WaitForSimulationActionState.DONE + return py_trees.common.Status.SUCCESS + else: + self.current_state = WaitForSimulationActionState.FAILURE + return py_trees.common.Status.FAILURE diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py b/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py new file mode 100644 index 00000000..d4e0a469 --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/actions/utils.py @@ -0,0 +1,245 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os +import subprocess # nosec B404 +import glob + +import defusedxml.ElementTree +from ament_index_python import get_package_share_directory +from pathlib import Path + + +class SpawnUtils(object): + + """Utils such as reading/parsing xml/sdf/urdf/xacro files for spawning + actors""" + + def __init__(self, logger=None): + """Initialize SpawnUtils class + + :logger: variable for using a ROS logger inside the SpawnUtils class + + """ + self.logger = logger + self.ign_gazebo_resource_paths = [] + if "IGN_GAZEBO_RESOURCE_PATH" in os.environ: + self.ign_gazebo_resource_paths = os.environ["IGN_GAZEBO_RESOURCE_PATH"].split(':') + + def parse_model_file(self, model_file: str, entity_name: str, xacro_arguments: str) -> str: + """ + Parse model file to str: + + Args: + model_file [str]: path to the model file + + return: + str of the content of model file in urdf format + """ + if '://' in model_file: + if model_file.startswith('https://fuel'): + return '' + model_file + '' + elif model_file.startswith('file://'): + # specifying sdf_filename seems to be broken, therefore load sdf + model_file = model_file.replace('file://', '', 1) + return self.read_model_file(model_file) + elif model_file.lower().endswith('.xacro'): + return self._xacro_to_urdf( + self.get_packaged_model_file_path(model_file), + xacro_arguments, entity_name) + elif model_file.lower().endswith(('.sdf', '.urdf')): + return self._parse_xml( + self.get_packaged_model_file_path(model_file), + entity_name) + elif model_file.startswith('model://'): + # search gazebo model paths for model + model_file = model_file.replace('model://', '', 1) + for path in self.ign_gazebo_resource_paths: + if not os.path.isdir(path): + continue + subfolders = [f.path for f in os.scandir(path) if f.is_dir()] + for folder in subfolders: + basename = os.path.basename(folder) + if basename == model_file: + path = os.path.join(folder, 'model.sdf') + if self.logger is not None: + self.logger.info( + f"Found model dir for {model_file}: {folder}") + else: + print(f"Found model dir for {model_file}: {folder}") + + return self.read_model_file(path) + self.logger.error( + f"Could not find {model_file} in IGN_GAZEBO_RESOURCE_PATHS") + else: + if self.logger is not None: + self.logger.error( + f'[{entity_name}] unrecognized model file definition: {model_file}') + else: + print(f'[{entity_name}] unrecognized model file definition: {model_file}') + return None + + def _parse_xml(self, xml: str, entity_name: str) -> str: + ''' + Parse xml file to str. + + Args: + xml [str]: path to xml file + entity_name [str]: name of the spawned entity + + return: + str of content of xml file + ''' + if self.logger is not None: + self.logger.info(f'[{entity_name}] Parsing xml: [{xml}]') + else: + print(f'[{entity_name}] Parsing xml: [{xml}]') + try: + tree = defusedxml.ElementTree.parse(xml) + root = tree.getroot() + except FileNotFoundError as e: + if self.logger is not None: + self.logger.error(f'Parsing xml {entity_name} failed: {e}') + else: + print(f'Parsing xml {entity_name} failed: {e}') + return defusedxml.ElementTree.tostring(root).decode().replace("\"", "\\\"").replace("\n", "") + + @staticmethod + def get_packaged_model_file_path(model_path): + """ + get path of a packaged model file + """ + model_file = model_path.split('://') + if len(model_file) != 2: + raise ValueError( + f'scenario_execution_amr_plugin:spawn: Invalid model file path: {model_path}." \ + " Expected format ://.') + model_file_path = os.path.join(get_package_share_directory( + model_file[0]), model_file[1]) + if not os.path.exists(model_file_path): + raise ValueError( + f'scenario_execution_amr_plugin:spawn: Model file not existing: {model_file_path}.') + return model_file_path + + def _xacro_to_urdf(self, path_to_xacro, xacro_arguments, entity_name: str) -> str: + """ + function to covert the xacro file to urdf file + + Args: + path_to_xacro [str]: path to xacro file + entity_name [str]: name of the spawned entity + + return: + str of content of coverted xacro file + """ + if self.logger is not None: + self.logger.info( + f'[{entity_name}] Parsing xacro: {path_to_xacro}, args: {xacro_arguments}') + else: + print(f'[{entity_name}] Parsing xacro: {path_to_xacro}, args: {xacro_arguments}') + + arg_list = xacro_arguments.split(',') + try: + with subprocess.Popen(['xacro', path_to_xacro] + arg_list, stdout=subprocess.PIPE, + stderr=subprocess.PIPE, text=True) as process: + stdout, stderr = process.communicate() + if stderr: + if self.logger is not None: + self.logger.warn(f'Parsing xacro {entity_name} has stderr: {stderr}') + else: + print(f'Parsing xacro {entity_name} has stderr: {stderr}') + except subprocess.CalledProcessError as e: + stdout = None + if self.logger is not None: + self.logger.error(f'Parsing xacro {entity_name} failed: {e.output}') + else: + print(f'Parsing xacro {entity_name} failed: {e.output}') + return stdout.replace("\"", "\\\"").replace("\n", "") + + def read_model_file(self, model_file): + ''' + read model from file + ''' + try: + f = open(model_file, 'r') + xml = f.read().replace("\"", "\\\"").replace("\n", "") + f.close() + return xml + except FileNotFoundError as e: + if self.logger is not None: + self.logger.error(f'Parsing xml {model_file} failed: {e}') + else: + print(f'Parsing xml {model_file} failed: {e}') + return None + + def find_mesh(self, mesh_name: str, entity_name: str) -> str: + """find the mesh given by a certain name. + + :mesh_name: Name of the mesh + :returns: file path to the mesh + + """ + if '://' in mesh_name: + if mesh_name.startswith('https://fuel'): + return mesh_name + elif mesh_name.startswith('file://'): + # make sure we have an absolute mesh filepath + try: + mesh_file = str(Path(mesh_name.replace('file://', '', 1)).resolve()) + except FileNotFoundError as e: + if self.logger is not None: + self.logger.error(f'Could not find mesh {mesh_name} for {entity_name}: {e}') + else: + print(f'Could not find mesh {mesh_name} for {entity_name}: {e}') + return mesh_file + elif mesh_name.startswith('model://'): + # search gazebo model paths for mesh + mesh_file = mesh_name.replace('model://', '', 1) + if not mesh_file.endswith('.dae'): + mesh_file += '.dae' + + for path in self.ign_gazebo_resource_paths: + if not os.path.isdir(path): + continue + for filename in glob.iglob(path + '**/**', recursive=True): + path = Path(filename) + if str(path.name) == mesh_file: + if self.logger is not None: + self.logger.info( + f"Found mesh dir for {mesh_file}: {path.parent}") + else: + print(f"Found mesh dir for {mesh_file}: {path.parent}") + return str(path.resolve()) + + self.logger.error( + f"Could not find {mesh_name} in IGN_GAZEBO_RESOURCE_PATHS") + elif mesh_name.endswith('.dae'): + try: + mesh_file = self.get_packaged_model_file_path(mesh_name) + return mesh_file + except FileNotFoundError as e: + if self.logger is not None: + self.logger.error(f'Could not find mesh {mesh_name} for {entity_name}: {e}') + else: + print(f'Could not find mesh {mesh_name} for {entity_name}: {e}') + + else: + if self.logger is not None: + self.logger.error( + f'[{entity_name}] unrecognized model file definition: {mesh_name}') + else: + print(f'[{entity_name}] unrecognized model file definition: {mesh_name}') + return None diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/get_osc_library.py b/scenario_execution_gazebo/scenario_execution_gazebo/get_osc_library.py new file mode 100644 index 00000000..6e73d6a3 --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/get_osc_library.py @@ -0,0 +1,19 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +def get_gazebo_library(): + return 'scenario_execution_gazebo', 'gazebo.osc' diff --git a/scenario_execution_gazebo/scenario_execution_gazebo/lib_osc/gazebo.osc b/scenario_execution_gazebo/scenario_execution_gazebo/lib_osc/gazebo.osc new file mode 100644 index 00000000..26e9f2f4 --- /dev/null +++ b/scenario_execution_gazebo/scenario_execution_gazebo/lib_osc/gazebo.osc @@ -0,0 +1,22 @@ +import osc.standard +import osc.robotics + +action wait_for_sim: + # Wait for simulation to become active + world_name: string = 'default' # simulation world name + +action actor_exists: + # report success if an actor with a specific name exists + entity_name: string # name of the actor within simulation + world_name: string = 'default' # simulation world name + +action osc_object.spawn: + # Spawn a simulation entity, uses namespace of entity + spawn_pose: pose_3d # position at which the object gets spawned + world_name: string = 'default' # simulation world name + model: string # model definition + xacro_arguments: string = '' # comma-separated list of argument key:=value pairs + +action osc_object.delete: + # Delete an actor from simulation + world_name: string = 'default' # simulation world name diff --git a/scenario_execution_gazebo/setup.cfg b/scenario_execution_gazebo/setup.cfg new file mode 100644 index 00000000..05085b89 --- /dev/null +++ b/scenario_execution_gazebo/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/scenario_execution_gazebo +[install] +install_scripts=$base/lib/scenario_execution_gazebo diff --git a/scenario_execution_gazebo/setup.py b/scenario_execution_gazebo/setup.py new file mode 100644 index 00000000..4d316c6c --- /dev/null +++ b/scenario_execution_gazebo/setup.py @@ -0,0 +1,60 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Setup python package """ +from glob import glob +import os +from setuptools import setup + +PACKAGE_NAME = 'scenario_execution_gazebo' + +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=[PACKAGE_NAME], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'scenarios'), glob('scenarios/*.osc')), + (os.path.join('share', PACKAGE_NAME, 'launch'), glob('launch/*launch.py')), + (os.path.join('share', PACKAGE_NAME, 'params'), glob('params/*.yaml')), + (os.path.join('share', PACKAGE_NAME, 'models'), glob('models/*.sdf*')), + (os.path.join('share', PACKAGE_NAME, 'models'), glob('models/*.dae*')), + (os.path.join('share', PACKAGE_NAME, 'models'), glob('models/*.png*')), + (os.path.join('share', PACKAGE_NAME, 'worlds'), glob('worlds/*.world')), + (os.path.join('share', PACKAGE_NAME, 'worlds'), glob('worlds/*.model')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Scenario Execution library for Gazebo', + license='Apache License 2.0', + tests_require=['pytest'], + entry_points={ + 'scenario_execution.actions': [ + 'osc_object.spawn = scenario_execution_gazebo.actions.gazebo_spawn_actor:GazeboSpawnActor', + 'actor_exists = scenario_execution_gazebo.actions.gazebo_actor_exists:GazeboActorExists', + 'osc_object.delete = scenario_execution_gazebo.actions.gazebo_delete_actor:GazeboDeleteActor', + 'wait_for_sim = scenario_execution_gazebo.actions.gazebo_wait_for_sim:GazeboWaitForSim', + ], + 'scenario_execution.osc_libraries': [ + 'gazebo = ' + 'scenario_execution_gazebo.get_osc_library:get_gazebo_library', + ] + }, +) diff --git a/scenario_execution_interfaces/CMakeLists.txt b/scenario_execution_interfaces/CMakeLists.txt new file mode 100644 index 00000000..89e50d8e --- /dev/null +++ b/scenario_execution_interfaces/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 3.8) +project(scenario_execution_interfaces) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(builtin_interfaces REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + msg/ScenarioStatus.msg + msg/Scenario.msg + msg/ScenarioList.msg + msg/ScenarioExecutionStatus.msg + srv/ExecuteScenario.srv + DEPENDENCIES + builtin_interfaces + ) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/scenario_execution_interfaces/README.md b/scenario_execution_interfaces/README.md new file mode 100644 index 00000000..e3f08c86 --- /dev/null +++ b/scenario_execution_interfaces/README.md @@ -0,0 +1,3 @@ +# Scenario Execution Interfaces + +The `scenario_execution_interfaces` package provides ROS2 messages and services, which are used to interface with the [scenario execution control package](../scenario_execution_control/README.md) diff --git a/scenario_execution_interfaces/msg/Scenario.msg b/scenario_execution_interfaces/msg/Scenario.msg new file mode 100644 index 00000000..c2626f38 --- /dev/null +++ b/scenario_execution_interfaces/msg/Scenario.msg @@ -0,0 +1,18 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +string name +string scenario_file diff --git a/scenario_execution_interfaces/msg/ScenarioExecutionStatus.msg b/scenario_execution_interfaces/msg/ScenarioExecutionStatus.msg new file mode 100644 index 00000000..fde94aab --- /dev/null +++ b/scenario_execution_interfaces/msg/ScenarioExecutionStatus.msg @@ -0,0 +1,24 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +uint8 STOPPED = 0 +uint8 STARTING = 1 +uint8 RUNNING = 2 +uint8 SHUTTINGDOWN = 3 +uint8 ERROR = 4 + +uint8 status + diff --git a/scenario_execution_interfaces/msg/ScenarioList.msg b/scenario_execution_interfaces/msg/ScenarioList.msg new file mode 100644 index 00000000..376a9e8c --- /dev/null +++ b/scenario_execution_interfaces/msg/ScenarioList.msg @@ -0,0 +1,18 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +Scenario[] scenarios + diff --git a/scenario_execution_interfaces/msg/ScenarioStatus.msg b/scenario_execution_interfaces/msg/ScenarioStatus.msg new file mode 100644 index 00000000..78ead9c3 --- /dev/null +++ b/scenario_execution_interfaces/msg/ScenarioStatus.msg @@ -0,0 +1,20 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +builtin_interfaces/Time system_time +builtin_interfaces/Time ros_time + +string data diff --git a/scenario_execution_interfaces/package.xml b/scenario_execution_interfaces/package.xml new file mode 100644 index 00000000..2eeac5c1 --- /dev/null +++ b/scenario_execution_interfaces/package.xml @@ -0,0 +1,25 @@ + + + + scenario_execution_interfaces + 1.0.0 + ROS2 Interfaces for Scenario Execution + Intel Labs + Intel Labs + Apache-2.0 + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + geometry_msgs + rosidl_interface_packages + + builtin_interfaces + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/scenario_execution_interfaces/srv/ExecuteScenario.srv b/scenario_execution_interfaces/srv/ExecuteScenario.srv new file mode 100644 index 00000000..04ebb58b --- /dev/null +++ b/scenario_execution_interfaces/srv/ExecuteScenario.srv @@ -0,0 +1,4 @@ +Scenario scenario +--- +bool result + diff --git a/scenario_execution_rviz/CMakeLists.txt b/scenario_execution_rviz/CMakeLists.txt new file mode 100644 index 00000000..8a9a428f --- /dev/null +++ b/scenario_execution_rviz/CMakeLists.txt @@ -0,0 +1,55 @@ +cmake_minimum_required(VERSION 3.3) +project(scenario_execution_rviz) + +set(CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 14) + +add_compile_options(-Wall -Wextra -Werror -flto -fvisibility=hidden -z noexecstac -fPIC -D_FORTIFY_SOURCE=2 -Wl,-z,relro,-z,now -fstack-protector-strong) + +find_package(ament_cmake REQUIRED) +find_package(rviz_common REQUIRED) +find_package(nav_msgs COMPONENTS) +find_package(std_srvs COMPONENTS) +find_package(scenario_execution_interfaces COMPONENTS) +find_package(py_trees_ros_interfaces COMPONENTS) +find_package(pluginlib REQUIRED) +find_package(rviz_ogre_vendor REQUIRED) + +set(CMAKE_AUTOMOC ON) + +find_package(Qt5 REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) + +set(SRC_FILES src/indicator_widget.cpp + src/control_panel.cpp) + +qt5_add_resources(SRC_FILES scenario_execution_rviz.qrc) + +add_library(${PROJECT_NAME} SHARED ${SRC_FILES}) + +target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} + rviz_ogre_vendor::OgreMain) + +target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_14) + +pluginlib_export_plugin_description_file(rviz_common + plugin_description.xml) + +ament_target_dependencies(scenario_execution_rviz rclcpp nav_msgs std_srvs + scenario_execution_interfaces py_trees_ros_interfaces rviz_common) + +ament_export_libraries(${PROJECT_NAME}) + +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin) + +install(FILES plugin_description.xml DESTINATION "share/${PROJECT_NAME}") + +install(DIRECTORY icons/ DESTINATION "share/${PROJECT_NAME}") + +ament_package() + diff --git a/scenario_execution_rviz/LICENSE_MIT b/scenario_execution_rviz/LICENSE_MIT new file mode 100644 index 00000000..7e145886 --- /dev/null +++ b/scenario_execution_rviz/LICENSE_MIT @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2020 Intel Corporation + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. \ No newline at end of file diff --git a/scenario_execution_rviz/README.md b/scenario_execution_rviz/README.md new file mode 100644 index 00000000..febd4a4c --- /dev/null +++ b/scenario_execution_rviz/README.md @@ -0,0 +1,3 @@ +# Scenario Execution Rviz + +The `scenario_execution_rviz` package provides [rviz](https://github.com/ros2/rviz) plugins for visualizing and controlling the scenario when working with [ROS 2](https://docs.ros.org/en/rolling/index.html). diff --git a/scenario_execution_rviz/icons/check-o.png b/scenario_execution_rviz/icons/check-o.png new file mode 100755 index 0000000000000000000000000000000000000000..b2982c8b4accf9bc3187c4c7f817ab9a7b1992cf GIT binary patch literal 1277 zcmeAS@N?(olHy`uVBq!ia0vp^1|ZDA3?vioaBgK_V4NM`6XFWwfgV~rQP%#iSp^`u@vPdIX7MXN{%q*;I>|8v&Lc$`V(uzvTDynMg8d?U1M#d(l=9X60Hm+{& z9-dx)0f9jwp<&?>kx|hx35m(6>6wkqEv;?s9aE-Gn?7Uq+<6NYE?%;9+42=DSFPT# zant5)+js2TwR_Lrv**rVxODCMjhnac+`Iqq(UYeyU%h_w_T7h%pFV&6_Wj4tU%&tS z-P~)d33L);lDE4{M|PT66axcOt*47)h{y4x(=weeI|#JhZ&1*X6Jc4p;6$j4;Kndk z5sm4gfjdPQ867R3hIHN0b+7%mO+Lu$mdexF@20=oSD9vIY<;u$%X{~Cd(T}w`u6eT zx2+TVZr%BuvH06##c6`FpCn)YXtT^o-gZw^f6k#oA2Ey1jkTYD22J1pq$n&bu5*9& z&5&<@{4TOHTKo*i3w{6XC_~2P)TBL354;m!H80|1s0z|;Vqo|6TWIFa5EcB0{l*6? z^>8t^44+l!?KT8H3EQ{GV8iQ;8o>t|uh-U}T6EyY&0mTR!MkL087n5NxFBONabNne zhMSkYt}>~&o_ny>=ks<8wkt=D`X8vCp7+zT;@})!2Igm9E-41QJLG(45mUz#6{V=6 zC;5MvD)Q8JF@<9OYHCw)a zYZY~wRF}>8$(L|8{k#5Drq7d>2tM$PG5ycHyZ)u7fsW^^4S6w#l%|GrWK382*^sJy z^w2Ts)eciDXShwCrN8)kXSixXg4z7G2D?bzH+$L|{{6Vaendyz;hC{@z45e+u#-R7 ze3sR_E^nOavgj+r*_S`W8A{V%dnyDyJ9od6DOqe`0zb!Yxs;=`5BTj1{lwgozxxM2 zvx!P~F2hB!<3AQN=m(o`VsBV~bX%1l^M%y?0a1({U&ABvm=+g(;P?Bd>e;(H?e^Lh zrh9wdywP6TcwyDbHzpS9&n3(Ei5y?I``Yh+J+lAfrhiLXFWC|C(xZNB;l1Myex(H! ob+2D!WY_K3tM%NzX7?Xf%T|Z>rs$$nV5(&BboFyt=akR{0Ev#=5&!@I literal 0 HcmV?d00001 diff --git a/scenario_execution_rviz/icons/chevron-right-o.png b/scenario_execution_rviz/icons/chevron-right-o.png new file mode 100755 index 0000000000000000000000000000000000000000..91ea82546d8b696b44a1efcb174e9e2474606d6d GIT binary patch literal 1035 zcmV+m1oZofP)I1ga+XkQ?cme3EJKP55fLY)?@DuPeWVh4sN0~Cv zcF+mXU62a4JD}sBw*%JFir)$PGeUG;I|tga6vF#K-z5}o+YD%JRpKW>w>pr|f)0Zw zK$}3%f}W_iRrO~Rpie=UJK)?5e(8i~pigqh{sVmtdLsh&P0$h0Vh;A91am_f=<^(c zGhs-THLU|p=Wu*hG70yaUjThrUU(bVZcxqPI~WT%>443F29xS;x)uwe$5;s6=ih$Uqa-rI9zKwr~u+cSZINNLR`%V{DFy_1J*yHGUuUk+?`wlz3 zBzk>4Q%1|VE~}EZJL`PJQmH=BtI@h2;H-D{iSbSWCyn!05u{InegItuy&kRo0p3xg z>1dwg)3jHW1$Wr{;v4Y^lF*3JR0FN_9PRL#jUfBLnRwSh!zB{PKvxXrSmW)oCeN)V za;7+0_9gJKdH4)49p4j~94*@%N1ZlVmZ%8zQBF@pCecL7T51~sY>Xj(nfp9;t&pf;Vj6?Qo1fbP&Uu$y$=Z(`y1Q8X8 z2N*S=Ul9cTtEXv>0x=Zn4_R$pnEykWxjcrbQj^4*dr6+>f;N-0eq0~v(oZ|FJzh`ya=xt1)I4Lp1;Z002ovPDHLk FV1mDY-xdG> literal 0 HcmV?d00001 diff --git a/scenario_execution_rviz/icons/close-o.png b/scenario_execution_rviz/icons/close-o.png new file mode 100755 index 0000000000000000000000000000000000000000..97aab2edcd5e6fa55442addbfa22f2ca00a86537 GIT binary patch literal 1250 zcmV<81ReW{P)e?ItOOp7`+Yz!u$J%~;0iDc%m6lGESI5tW1xEzuGI%ZvhN~1F2@a(=`&;m?;Nd2C9}yfAETwQCYyDS_3Bhw2 zxQ)&}u_KH40|S01N63WDQ$c5rO^;wQVY8GoNXLzj<7vQEYOE?VcUXmu#^&h>K}QOH zonXqb8Ordn)nFIgFYTnyOqTfArrV5Wy}xa9HJ&Ty9qgBB0mpWc;AdmA-2=X6Ku7Wd zi0#%0&N{;0NMJSzeswTk2v!yFan#ry@<1OOP~nPDaEIU*N8o>8?nA+?1^I1N z@R0}l$$%ax8bEAcQ`oJO9M_zARZp?hv~jrmjs27d`ptk=mkA)|xL@$QBlx=1vh$+= zZ;#=);DP=$pv>hk!`V>Es9zK8Z<6yC!?jp{cT+QjIc+O`@P7fP+u$#>R#PZm?q1JH zpG$%*O=v5WLO&YN<`ND%;)!VmFUF~pd{(+F7i=*cXY22hDKu^D?kz~(35)`J&8sWG z6TnO6`C3A`erF-|z80$$1h1MXb2leaZBz2bp(8qm3{ zQj0l-Gk_H|C0Lh&?@%c8tWD;Z z77QBvywb{cg}cfm_*e#UP1o1zlY*WcF`Wt}chbkH92=`?Gz)CgXen#O5Iie5rEnvc znFa#xTE5Ggmvy6EPM+E& zvh7XqqNC%LKa6vH8X3a_e4>=3USQ&y13b({bg1M~uP*qbn$X_tNFADB1OEm0! z!a2c%ZPH#JdGBg*ce8{C9kQ!}eHCl3=e$iD30`i6G?IVwAi-yXjTH#*b5@&rKin#R zJ%|G-4weL?3RfS6PgybNpx{0IcQIDo$fr2nqfpO#&ZKblaa7>|-mmbpQfJ)PD3rt_ zF~-(5cEUE7^96!fuf|fK%04Ezt1aS9AWtdmid6~!Rz)|d3WJCQI~49Ny`P5i`a(Q^ zwwIYdwpI04gDzkY*aq|g_Ye*%_OAxhgufbm4V;c(p$h*u+H$sk0qmNim9mX45&!@I M07*qoM6N<$f?f7ci~s-t literal 0 HcmV?d00001 diff --git a/scenario_execution_rviz/icons/corner-down-right.png b/scenario_execution_rviz/icons/corner-down-right.png new file mode 100755 index 0000000000000000000000000000000000000000..03f0a575f2828f04ecaf918f6b6c6011bd399bd5 GIT binary patch literal 476 zcmeAS@N?(olHy`uVBq!ia0vp^1|ZDA3?vioaBc-sa{_!qT!Hle28REu82--$lS>)? zFJt(>nBo5-hW|h|kO3qif=d|w0}(_P!bTPcvf+XdEf86VI9!By#{d7nEFIE;?lUS0 z@(X5Q;^g8N6ql5fS1~ZQwD$4!3ki>oNy;ecnzVM)=3V=boj85w(X%)2KYjW7Hg{0OfBC3 zFSvGM#mC5qCu`2n|Cwf{`01xf6b&ksn9|z4l^C?x6Os?MtYe)a zd4_M#gLOx`I1ZdKwc7U1mZw3K)8#GOja@EF7{nSKzAz*hXJop&6?9yZVXYL)idEse z>K-UJ|NgiBi>J$aAEwN-+LZn)=2tkw^1k=~SFAU>`M2|s&nG*}CV><-!_5Cb5C4N#&hQTR{`=oB zvQ6Y#A$V1Q3Qz$mKrjGFmy)(3E6@WTBn>2~G=Q4k#F7>tm;lGNZ=#-o4d7bRSkhYL zLwpFlOX^3n&|h^A?Av~e8l$_wtE6F61s3aRrp9B`i)?!qxuaB(n_2-x_DVmfC+G9`!?D#Hw8w(X4k{#P$29F%@1&9 zdne`asT61(jinUmEE-EF&}lU01V|E%IV|)63{pj7Y6Y%p0l5h*jSS1c00000NkvXXu0mjfOsq=gnxgkcmx zP*IKwI^u#jF0>#nEgoCC!EP7S0Tpf9W)WLNX}1QMmw*aq{Np+8KPsmxRqx&V-Fv_H z)jfI1lm_`b*iEscP$&-K0N-Hn4Vz9ID{x(A`FaC|V%e1#8m{ecO`Uj@hIA`j%gcNS)<8b8Fg#&?{qz*PV8Alkc_H`4i{%&yiYLKJ#m% zh_83OTRc>+x@c@13I~UOy#zgf+Kr zDRzu#JXQ0&Ri4o#)!99Fo;fuzr`96VKlkM1d6nW6=L=9{I?Fz47X%$`)|J?06BRpF zPD$FUIn}2BCUJlMYgSGPw5=++VRyjFkmW^vEbWWKm+t>52|9REVk0Y7YZmQPqC-&O! zmq3j@nASfeRsy*(NjGi#ad7QZ=kVEFRlqV96SLNAaZgboL2HNWSuRY4t8ymVVPW?KIQ8h#VrXfMVT|kb}^pvR=AbqY`s*~OQBe-Cw+XRVjrJ(;s=s1Ov(`j zT$D~&zc{2k*lkRLV|5abkuaFk?An}hs6CIdPZTCl#or2?c&ly8 zc{uOpvaOXtoOS$3$41&xCxl9UZMnrKJNAVKTwh(f@tdoEEPNPTvvj1(Wy>G0LRHC6 zytgS#njV;%&m-qdoUTefts3dx#gk#y&~ zOZt$I7i(*$M?d&sv!o%vC)As6eP;JH9=`T%1XR&-kZ!p>^gq? z&Y7wzy|S-~tn0L%JxY^V;IO0)bg5nvbfa*|A|a+y&=Hvm#py}MzA1)Zmq;NWl?I2{bT%EP`5DOs7S+=Z^3cc#VX*Il0SNFU zqQ>fUY9WJRFc|0tce+Xw!(a*o0tU=tuvj!;LDQ~Q>JTGMsdX_y^kewqT1-Q#b)-rO znJ^JlrPqn5R4@;{%TJ+}NZ!LMwF4{wJ{U$s&0x}DhC;y@?4i~9B><3tgg)w_4Fye| z5sYh9dJTsACE!Y(%U}o@_TFEu*T~J~$S?*j#}&X-3!*ZIg!C6nr0+dU6vU7Uwb=`h zJ;YK+5+BGKlACG9T+ZM`fctygA=d9|HyZ;hiA3nD!t|!}#J(b`DZWsq!bq9We9Pn_ zJebF4(O6s*rLj>qPD3~>jK&raEGB^>1P)_^pu|e84pCyb2?~JINq~bPGJ#CM63`F= zBWP?)z^9>nLPjHasDQ^tIb0OM2SF^>kU*7)d~jAKC>ekv_^3OExg#_fg>jG#AEu#P z9HDX8u#DjF5djAw%uq5+xIm>*AYeI31rmcZ)XEt1go$wBe5qJOWzpdeBT_k{BY=a5 zx`KZ1s1DKiXYH?2p-@6)c*>|N%Is0 znPn?Pu>K%gBmtM10|CGODJ&LI#^B)n9uU;Kaq?q}C1bKMcd$fEgy7QHFpoz=Q4T@F zc_^RFVX`@}j5`!vt0Hs;M1#+d0hNMkfPl=^K(ozMx(>BA#NsBNV3s?L3DaP1DAQdC zbA|4(8_W{IFqQH7OO$bOCV{x4G*rgq(bzHqqoEuYhlcZUj3?vcd?wm2>GuTw1ts!? zZ067sJs76O^=?r;82`8I{RV?N9iXOv40KS?kQwhg@&IQhrF_O?KyIHg0)QS4@=5#- z(=|-jCo%9z#>46wrt6a!_$1?Db^T>@*?rj4;Y#pB&j5C8!TGyafZd)Iy3pU3(r5bY zIa{&?jM%CJmTM^#`|+mJg0iD + + scenario_execution_rviz + 0.0.1 + The scenario_execution_rviz package + Intel Labs + Intel Labs + Apache-2.0 + MIT + + rclcpp + ament_cmake + rviz_common + + qtbase5-dev + nav_msgs + geometry_msgs + scenario_execution_interfaces + py_trees_ros_interfaces + nav_msgs + geometry_msgs + scenario_execution_interfaces + py_trees_ros_interfaces + libqt5-core + libqt5-gui + libqt5-widgets + + + ament_cmake + + diff --git a/scenario_execution_rviz/plugin_description.xml b/scenario_execution_rviz/plugin_description.xml new file mode 100644 index 00000000..596e8d51 --- /dev/null +++ b/scenario_execution_rviz/plugin_description.xml @@ -0,0 +1,9 @@ + + + + A panel widget for controlling scenario execution + + + diff --git a/scenario_execution_rviz/scenario_execution_rviz.qrc b/scenario_execution_rviz/scenario_execution_rviz.qrc new file mode 100644 index 00000000..4e71614f --- /dev/null +++ b/scenario_execution_rviz/scenario_execution_rviz.qrc @@ -0,0 +1,10 @@ + + + icons/play.png + icons/stop.png + icons/check-o.png + icons/chevron-right-o.png + icons/close-o.png + icons/corner-down-right.png + + \ No newline at end of file diff --git a/scenario_execution_rviz/src/control_panel.cpp b/scenario_execution_rviz/src/control_panel.cpp new file mode 100644 index 00000000..48130f73 --- /dev/null +++ b/scenario_execution_rviz/src/control_panel.cpp @@ -0,0 +1,203 @@ +// Copyright (C) 2024 Intel Corporation +// +// 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. +// +// SPDX-License-Identifier: Apache-2.0 +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include "rviz_common/display_context.hpp" +#include +#include +#include +#include + +#include "control_panel.h" +#include "indicator_widget.h" + +using std::placeholders::_1; +namespace scenario_execution_rviz { + +ControlPanel::ControlPanel(QWidget *parent) : rviz_common::Panel(parent) { + QVBoxLayout *layout = new QVBoxLayout; + + QFormLayout *formLayout = new QFormLayout; + + QHBoxLayout *rowLayout = new QHBoxLayout; + + mScenarioSelection = new QComboBox(); + rowLayout->addWidget(mScenarioSelection, 10); + + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mTriggerScenarioButton = new QPushButton(iconPlay, ""); + rowLayout->addWidget(mTriggerScenarioButton); + + mIndicatorWidget = new IndicatorWidget(); + rowLayout->addWidget(mIndicatorWidget); + connect(mTriggerScenarioButton, SIGNAL(released()), this, + SLOT(scenarioExecuteButtonClicked())); + + formLayout->addRow(rowLayout); + + layout->addLayout(formLayout); + + setLayout(layout); + + setScenarioExecutionStatus(false); +} + +void ControlPanel::onInitialize() { + _node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + + mExecuteScenarioClient = + _node->create_client( + "/scenario_execution_control/execute_scenario"); + mStopScenarioClient = _node->create_client( + "/scenario_execution_control/stop_scenario"); + mScenarioExecutionStatusSubscriber = _node->create_subscription< + scenario_execution_interfaces::msg::ScenarioExecutionStatus>( + "/scenario_execution_control/status", 10, + std::bind(&ControlPanel::scenarioExecutionStatusChanged, this, _1)); + rclcpp::QoS static_QoS = rclcpp::QoS(1).transient_local(); + mScenarioSubscriber = _node->create_subscription< + scenario_execution_interfaces::msg::ScenarioList>( + "/scenario_execution_control/available_scenarios", static_QoS, + std::bind(&ControlPanel::scenariosChanged, this, _1)); +} + +void ControlPanel::scenarioExecuteButtonClicked() { + if (!mScenarioIsRunning) { + for (auto const &scenario : mScenarios->scenarios) { + if (QString::fromStdString(scenario.name) == + mScenarioSelection->currentText()) { + auto request = std::make_shared< + scenario_execution_interfaces::srv::ExecuteScenario::Request>(); + request->scenario = scenario; + // Check if service is available + if (!mExecuteScenarioClient->wait_for_service( + std::chrono::seconds(1))) { + RCLCPP_WARN(rclcpp::get_logger("rclcpp"), + "Failed to call service executeScenario"); + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } + auto result = mExecuteScenarioClient->async_send_request(request); + break; + } + } + } else { + if (!mStopScenarioClient->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_WARN(rclcpp::get_logger("rclcpp"), + "Failed to call service stopScenario"); + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } + auto request = std::make_shared(); + auto result = mStopScenarioClient->async_send_request(request); + } +} + +void ControlPanel::scenarioExecutionStatusChanged( + const scenario_execution_interfaces::msg::ScenarioExecutionStatus::SharedPtr + msg) { + bool isRunning = false; + if (msg->status == + scenario_execution_interfaces::msg::ScenarioExecutionStatus::STOPPED) { + mIndicatorWidget->setState(IndicatorWidget::State::Stopped); + } else if (msg->status == scenario_execution_interfaces::msg:: + ScenarioExecutionStatus::STARTING) { + mIndicatorWidget->setState(IndicatorWidget::State::Starting); + isRunning = true; + } else if (msg->status == scenario_execution_interfaces::msg:: + ScenarioExecutionStatus::RUNNING) { + mIndicatorWidget->setState(IndicatorWidget::State::Running); + isRunning = true; + } else if (msg->status == scenario_execution_interfaces::msg:: + ScenarioExecutionStatus::SHUTTINGDOWN) { + mIndicatorWidget->setState(IndicatorWidget::State::ShuttingDown); + isRunning = true; + } else { + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } + + updateScenarioExecutionRunning(isRunning); +} + +void ControlPanel::updateScenarioExecutionRunning(bool isRunning) { + mScenarioIsRunning = isRunning; + if (isRunning) { + QPixmap pixmapStop(":/icons/stop.png"); + QIcon iconStop(pixmapStop); + mTriggerScenarioButton->setIcon(iconStop); + } else { + QPixmap pixmapPlay(":/icons/play.png"); + QIcon iconPlay(pixmapPlay); + mTriggerScenarioButton->setIcon(iconPlay); + } +} + +void ControlPanel::setScenarioExecutionStatus(bool active) { + mScenarioSelection->setEnabled(active); + mTriggerScenarioButton->setEnabled(active); + mIndicatorWidget->setEnabled(active); +} + +void ControlPanel::scenariosChanged( + const scenario_execution_interfaces::msg::ScenarioList::SharedPtr msg) { + auto currentSelection = mScenarioSelection->currentText(); + mScenarios = msg; + mScenarioSelection->clear(); + int idx = 0; + QStringList tmpScenarios; + for (auto const &scenario : msg->scenarios) { + auto name = QString::fromStdString(scenario.name); + tmpScenarios.append(name); + } + tmpScenarios.sort(Qt::CaseInsensitive); + for (auto const &scenario : tmpScenarios) { + mScenarioSelection->addItem(scenario); + if (scenario == currentSelection) { // switch to previously selected item + mScenarioSelection->setCurrentIndex(idx); + } + ++idx; + } + setScenarioExecutionStatus(mScenarioSelection->count() > 0); +} + +} // end namespace scenario_execution_rviz + +#include +PLUGINLIB_EXPORT_CLASS(scenario_execution_rviz::ControlPanel, + rviz_common::Panel) diff --git a/scenario_execution_rviz/src/control_panel.h b/scenario_execution_rviz/src/control_panel.h new file mode 100644 index 00000000..15d64c6d --- /dev/null +++ b/scenario_execution_rviz/src/control_panel.h @@ -0,0 +1,77 @@ +// Copyright (C) 2024 Intel Corporation +// +// 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. +// +// SPDX-License-Identifier: Apache-2.0 +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ + +#pragma once + +#include "rclcpp/rclcpp.hpp" +#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" +#include +#include +#include +#include +#include + +class QPushButton; +class QComboBox; + +namespace scenario_execution_rviz { + +class IndicatorWidget; + +class ControlPanel : public rviz_common::Panel { + Q_OBJECT +public: + ControlPanel(QWidget *parent = 0); + +protected Q_SLOTS: + void scenarioExecuteButtonClicked(); + +protected: + virtual void onInitialize() override; + void setScenarioExecutionStatus(bool active); + + void + scenarioExecutionStatusChanged(const scenario_execution_interfaces::msg:: + ScenarioExecutionStatus::SharedPtr msg); + void scenariosChanged( + const scenario_execution_interfaces::msg::ScenarioList::SharedPtr msg); + void updateScenarioExecutionRunning(bool isRunning); + + rclcpp::Node::SharedPtr _node; + + QPushButton *mTriggerScenarioButton; + QComboBox *mScenarioSelection; + IndicatorWidget *mIndicatorWidget; + rclcpp::Client::SharedPtr + mExecuteScenarioClient; + rclcpp::Client::SharedPtr mStopScenarioClient; + rclcpp::Subscription:: + SharedPtr mScenarioSubscriber; + rclcpp::Subscription< + scenario_execution_interfaces::msg::ScenarioExecutionStatus>::SharedPtr + mScenarioExecutionStatusSubscriber; + + scenario_execution_interfaces::msg::ScenarioList::SharedPtr mScenarios; + bool mScenarioIsRunning = false; +}; + +} // end namespace scenario_execution_rviz diff --git a/scenario_execution_rviz/src/indicator_widget.cpp b/scenario_execution_rviz/src/indicator_widget.cpp new file mode 100644 index 00000000..f43eebb2 --- /dev/null +++ b/scenario_execution_rviz/src/indicator_widget.cpp @@ -0,0 +1,56 @@ +// Copyright (C) 2024 Intel Corporation +// +// 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. +// +// SPDX-License-Identifier: Apache-2.0 +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include "indicator_widget.h" +#include + +namespace scenario_execution_rviz { + +IndicatorWidget::IndicatorWidget(QWidget *parent) + : QWidget(parent), mCurrentState(IndicatorWidget::State::Stopped) { + setFixedSize(18, 18); +} + +void IndicatorWidget::paintEvent(QPaintEvent *event) { + (void)event; + QPainter painter(this); + painter.setPen(Qt::darkGray); + if (mCurrentState == IndicatorWidget::State::Stopped) { + painter.setBrush(QBrush(Qt::lightGray, Qt::SolidPattern)); + } else if (mCurrentState == IndicatorWidget::State::Running) { + painter.setBrush(QBrush(Qt::green, Qt::SolidPattern)); + } else if (mCurrentState == IndicatorWidget::State::Error) { + painter.setBrush(QBrush(Qt::red, Qt::SolidPattern)); + } else if ((mCurrentState == IndicatorWidget::State::Starting) || + (mCurrentState == IndicatorWidget::State::ShuttingDown)) { + painter.setBrush(QBrush(Qt::yellow, Qt::SolidPattern)); + } else { + painter.setBrush(QBrush(Qt::black, Qt::SolidPattern)); + } + painter.drawEllipse(1, 1, 16, 16); +} + +void IndicatorWidget::setState(IndicatorWidget::State state) { + mCurrentState = state; + repaint(); +} + +} // end namespace scenario_execution_rviz diff --git a/scenario_execution_rviz/src/indicator_widget.h b/scenario_execution_rviz/src/indicator_widget.h new file mode 100644 index 00000000..03ba35e5 --- /dev/null +++ b/scenario_execution_rviz/src/indicator_widget.h @@ -0,0 +1,43 @@ +// Copyright (C) 2024 Intel Corporation +// +// 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. +// +// SPDX-License-Identifier: Apache-2.0 +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include + +namespace scenario_execution_rviz { + +class IndicatorWidget : public QWidget { + Q_OBJECT +public: + enum class State { Stopped, Starting, Running, ShuttingDown, Error }; + + IndicatorWidget(QWidget *parent = 0); + + virtual void paintEvent(QPaintEvent *event) override; + + void setState(IndicatorWidget::State state); + +private: + State mCurrentState{State::Stopped}; +}; + +} // end namespace scenario_execution_rviz diff --git a/security.md b/security.md new file mode 100644 index 00000000..e70fcb0f --- /dev/null +++ b/security.md @@ -0,0 +1,6 @@ +# Security Policy +Intel is committed to rapidly addressing security vulnerabilities affecting our customers and providing clear guidance on the solution, impact, severity and mitigation. + +## Reporting a Vulnerability +Please report any security vulnerabilities in this project [utilizing the guidelines here](https://www.intel.com/content/www/us/en/security-center/vulnerability-handling-guidelines.html). + diff --git a/simulation/gazebo/tb4_sim_scenario/CMakeLists.txt b/simulation/gazebo/tb4_sim_scenario/CMakeLists.txt new file mode 100644 index 00000000..ea6f2aad --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.8) +project(tb4_sim_scenario) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) + +find_package(ros_ign_interfaces REQUIRED) + +install( + DIRECTORY launch params worlds urdf + DESTINATION share/${PROJECT_NAME} +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/simulation/gazebo/tb4_sim_scenario/README.md b/simulation/gazebo/tb4_sim_scenario/README.md new file mode 100644 index 00000000..2953df1d --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/README.md @@ -0,0 +1,9 @@ +# Turtlebot4 Simulation Scenario Execution + +The `tb_sim_scenario` package provides launch files and parameter files to start the Gazebo Simulator, spawn the Turtlebot 4 and execute a scenario. + +## Launch and arguments + +```bash +ros2 launch tb4_sim_scenario_bringup sim_nav_scenario_launch.py scenario:= +``` diff --git a/simulation/gazebo/tb4_sim_scenario/launch/ignition_launch.py b/simulation/gazebo/tb4_sim_scenario/launch/ignition_launch.py new file mode 100644 index 00000000..2a11f4b6 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/launch/ignition_launch.py @@ -0,0 +1,124 @@ +# Copyright (C) 2024 Intel Corporation +# Copyright 2023 Clearpath Robotics, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# @author Roni Kreinin (rkreinin@clearpathrobotics.com) + +import os + +from pathlib import Path + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess, Shutdown +from launch.actions import SetEnvironmentVariable +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution +from launch_ros.actions import Node + + +ARGUMENTS = [ + DeclareLaunchArgument('use_sim_time', default_value='true', + choices=['true', 'false'], + description='use_sim_time'), + + DeclareLaunchArgument('world', default_value='maze', + description='Ignition World'), + + DeclareLaunchArgument('headless', default_value='False', + description='Whether to execute simulation gui'), +] + + +def generate_launch_description(): + + # Directories + pkg_turtlebot4_ignition_bringup = get_package_share_directory( + 'turtlebot4_ignition_bringup') + pkg_tb4_sim_scenario = get_package_share_directory( + 'tb4_sim_scenario') + pkg_turtlebot4_ignition_gui_plugins = get_package_share_directory( + 'turtlebot4_ignition_gui_plugins') + pkg_turtlebot4_description = get_package_share_directory( + 'turtlebot4_description') + pkg_irobot_create_description = get_package_share_directory( + 'irobot_create_description') + pkg_irobot_create_ignition_bringup = get_package_share_directory( + 'irobot_create_ignition_bringup') + pkg_irobot_create_ignition_plugins = get_package_share_directory( + 'irobot_create_ignition_plugins') + + # Set ignition resource path + ign_resource_path = SetEnvironmentVariable( + name='IGN_GAZEBO_RESOURCE_PATH', + value=[ + os.path.join(pkg_turtlebot4_ignition_bringup, 'worlds'), ':' + + os.path.join(pkg_irobot_create_ignition_bringup, 'worlds'), ':' + + str(Path(pkg_turtlebot4_description).parent.resolve()), ':' + + str(Path(pkg_irobot_create_description).parent.resolve())] + ) + + ign_gui_plugin_path = SetEnvironmentVariable( + name='IGN_GUI_PLUGIN_PATH', + value=[ + os.path.join(pkg_turtlebot4_ignition_gui_plugins, 'lib'), ':' + + os.path.join(pkg_irobot_create_ignition_plugins, 'lib')]) + + env = {'GZ_SIM_SYSTEM_PLUGIN_PATH': + ':'.join([os.environ.get('GZ_SIM_SYSTEM_PLUGIN_PATH', default=''), + os.environ.get('LD_LIBRARY_PATH', default='')]), + 'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': # TODO(CH3): To support pre-garden. Deprecated. + ':'.join([os.environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), + os.environ.get('LD_LIBRARY_PATH', default='')])} + # Ignition gazebo + ignition_gazebo = ExecuteProcess( + cmd=['ruby', '/usr/bin/ign', 'gazebo', [PathJoinSubstitution( + [pkg_tb4_sim_scenario, 'worlds', LaunchConfiguration('world')]), '.sdf'], '-v', '4', '-r', '-s', '--force-version', '6'], + output='screen', + additional_env=env, + on_exit=Shutdown(), + sigterm_timeout='5', + sigkill_timeout='10', + log_cmd=True, + emulate_tty=True + ) + + ignition_gazebo_gui = ExecuteProcess( + cmd=['ruby', '/usr/bin/ign', 'gazebo', '-g', '-v', '4', '--gui-config', + PathJoinSubstitution([pkg_turtlebot4_ignition_bringup, 'gui', 'gui.config']), '--force-version', '6'], + output='screen', + additional_env=env, + on_exit=Shutdown(), + sigterm_timeout='5', + sigkill_timeout='10', + log_cmd=True, + emulate_tty=True + ) + + # Clock bridge + clock_bridge = Node(package='ros_gz_bridge', executable='parameter_bridge', + name='clock_bridge', + output='screen', + arguments=[ + '/clock' + '@rosgraph_msgs/msg/Clock' + '[ignition.msgs.Clock' + ]) + + # Create launch description and add actions + ld = LaunchDescription(ARGUMENTS) + ld.add_action(ign_resource_path) + ld.add_action(ign_gui_plugin_path) + ld.add_action(ignition_gazebo) + ld.add_action(ignition_gazebo_gui) + ld.add_action(clock_bridge) + return ld diff --git a/simulation/gazebo/tb4_sim_scenario/launch/ignition_robot_launch.py b/simulation/gazebo/tb4_sim_scenario/launch/ignition_robot_launch.py new file mode 100644 index 00000000..c77a7240 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/launch/ignition_robot_launch.py @@ -0,0 +1,201 @@ +# Copyright (C) 2024 Intel Corporation +# Copyright 2021 Clearpath Robotics, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# @author Roni Kreinin (rkreinin@clearpathrobotics.com) + + +from ament_index_python.packages import get_package_share_directory + +from irobot_create_common_bringup.namespace import GetNamespacedName +from irobot_create_common_bringup.offset import OffsetParser + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution + +from launch_ros.actions import Node, PushRosNamespace + + +ARGUMENTS = [ + DeclareLaunchArgument('use_sim_time', default_value='true', + choices=['true', 'false'], + description='use_sim_time'), + DeclareLaunchArgument('model', default_value='standard', + choices=['standard', 'lite'], + description='Turtlebot4 Model'), + DeclareLaunchArgument('namespace', default_value='', + description='Robot namespace'), + DeclareLaunchArgument('spawn', default_value='True', + description='Whether to spawn the turlebot'), +] + +for pose_element in ['x', 'y', 'z', 'yaw']: + ARGUMENTS.append(DeclareLaunchArgument(pose_element, default_value='0.0', + description=f'{pose_element} component of the robot pose.')) + + +def generate_launch_description(): + + # Directories + pkg_tb4_sim_scenario = get_package_share_directory( + 'tb4_sim_scenario') + pkg_turtlebot4_ignition_bringup = get_package_share_directory( + 'turtlebot4_ignition_bringup') + pkg_irobot_create_common_bringup = get_package_share_directory( + 'irobot_create_common_bringup') + pkg_irobot_create_ignition_bringup = get_package_share_directory( + 'irobot_create_ignition_bringup') + + # Paths + # turtlebot4_ros_ign_bridge_launch = PathJoinSubstitution( + # [pkg_turtlebot4_ignition_bringup, 'launch', 'ros_ign_bridge.launch.py']) + turtlebot4_ros_ign_bridge_launch = PathJoinSubstitution( + [pkg_tb4_sim_scenario, 'launch', 'ros_ign_bridge.launch.py']) + + turtlebot4_node_launch = PathJoinSubstitution( + [pkg_turtlebot4_ignition_bringup, 'launch', 'turtlebot4_nodes.launch.py']) + + create3_nodes_launch = PathJoinSubstitution( + [pkg_irobot_create_common_bringup, 'launch', 'create3_nodes.launch.py']) + + create3_ignition_nodes_launch = PathJoinSubstitution( + [pkg_irobot_create_ignition_bringup, 'launch', 'create3_ignition_nodes.launch.py']) + + robot_description_launch = PathJoinSubstitution( + [pkg_tb4_sim_scenario, 'launch', 'robot_description.launch.py']) + + # Parameters + param_file_cmd = DeclareLaunchArgument( + 'param_file', + default_value=PathJoinSubstitution( + [pkg_turtlebot4_ignition_bringup, 'config', 'turtlebot4_node.yaml']), + description='Turtlebot4 Robot param file') + + # Launch configurations + namespace = LaunchConfiguration('namespace') + use_sim_time = LaunchConfiguration('use_sim_time') + model = LaunchConfiguration('model') + spawn = LaunchConfiguration('spawn') + x, y, z = LaunchConfiguration('x'), LaunchConfiguration('y'), LaunchConfiguration('z') + yaw = LaunchConfiguration('yaw') + turtlebot4_node_yaml_file = LaunchConfiguration('param_file') + + robot_name = GetNamespacedName(namespace, 'turtlebot4') + dock_name = GetNamespacedName(namespace, 'standard_dock') + + # Spawn robot slightly clsoer to the floor to reduce the drop + # Ensures robot remains properly docked after the drop + z_robot = OffsetParser(z, -0.0025) + + spawn_robot_group_action = GroupAction([ + PushRosNamespace(namespace), + + # Robot description + IncludeLaunchDescription( + PythonLaunchDescriptionSource([robot_description_launch]), + launch_arguments=[('model', model), + ('use_sim_time', use_sim_time)] + ), + + # Spawn TurtleBot 4 + Node( + package='ros_ign_gazebo', + condition=IfCondition(spawn), + executable='create', + arguments=['-name', robot_name, + '-x', x, + '-y', y, + '-z', z_robot, + '-Y', yaw, + '-topic', 'robot_description'], + output='screen' + ), + + # ROS IGN bridge + IncludeLaunchDescription( + PythonLaunchDescriptionSource([turtlebot4_ros_ign_bridge_launch]), + launch_arguments=[ + ('model', model), + ('robot_name', robot_name), + ('dock_name', dock_name), + ('namespace', namespace)] + ), + + # TurtleBot 4 nodes + IncludeLaunchDescription( + PythonLaunchDescriptionSource([turtlebot4_node_launch]), + launch_arguments=[('model', model), + ('param_file', turtlebot4_node_yaml_file)] + ), + + # Create 3 nodes + IncludeLaunchDescription( + PythonLaunchDescriptionSource([create3_nodes_launch]), + launch_arguments=[ + ('namespace', namespace) + ] + ), + + # Create 3 Ignition nodes + IncludeLaunchDescription( + PythonLaunchDescriptionSource([create3_ignition_nodes_launch]), + launch_arguments=[ + ('robot_name', robot_name), + ('dock_name', dock_name), + ] + ), + + # RPLIDAR static transforms + Node( + name='rplidar_stf', + package='tf2_ros', + executable='static_transform_publisher', + output='screen', + arguments=[ + '0', '0', '0', '0', '0', '0.0', + 'rplidar_link', [robot_name, '/rplidar_link/rplidar']], + remappings=[ + ('/tf', 'tf'), + ('/tf_static', 'tf_static'), + ] + ), + + # OAKD static transform + # Required for pointcloud. See https://github.com/gazebosim/gz-sensors/issues/239 + Node( + name='camera_stf', + package='tf2_ros', + executable='static_transform_publisher', + output='screen', + arguments=[ + '0', '0', '0', + '1.5707', '-1.5707', '0', + 'oakd_rgb_camera_optical_frame', + [robot_name, '/oakd_rgb_camera_frame/rgbd_camera'] + ], + remappings=[ + ('/tf', 'tf'), + ('/tf_static', 'tf_static'), + ] + ), + ]) + + # Define LaunchDescription variable + ld = LaunchDescription(ARGUMENTS) + ld.add_action(param_file_cmd) + ld.add_action(spawn_robot_group_action) + return ld diff --git a/simulation/gazebo/tb4_sim_scenario/launch/nav2_launch.py b/simulation/gazebo/tb4_sim_scenario/launch/nav2_launch.py new file mode 100644 index 00000000..a4f35c41 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/launch/nav2_launch.py @@ -0,0 +1,76 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution + + +ARGUMENTS = [ + + DeclareLaunchArgument('namespace', default_value='', + description='Robot namespace'), + # Ignition setup + DeclareLaunchArgument('world', default_value='warehouse', + description='Ignition World'), + + DeclareLaunchArgument('model', default_value='standard', + choices=['standard', 'lite'], + description='Turtlebot4 Model'), + DeclareLaunchArgument('launch_simulation', default_value='True', + description='Set "false" to skip simulation startup.'), + DeclareLaunchArgument('headless', default_value='True', + description='Start Igniton GUI or not'), + + DeclareLaunchArgument('map_yaml', default_value=[LaunchConfiguration('world'), '.yaml'], + description='map yaml file'), +] + +# Inital robot pose in the world +for pose_element in ['x', 'y', 'z', 'yaw']: + ARGUMENTS.append(DeclareLaunchArgument(pose_element, + default_value='0.0', + description=f'{pose_element} component of the robot pose.')) + + +def generate_launch_description(): + + # Directories + pkg_tb4_sim_scenario = get_package_share_directory('tb4_sim_scenario') + pkg_tb4_nav = get_package_share_directory('turtlebot4_navigation') + pkg_nav2_bringup = get_package_share_directory('nav2_bringup') + + # Launch args + map_yaml = LaunchConfiguration('map_yaml') + + nav2_bringup = IncludeLaunchDescription( + PythonLaunchDescriptionSource([PathJoinSubstitution([pkg_nav2_bringup, 'launch', 'bringup_launch.py'])]), + launch_arguments={ + 'map': PathJoinSubstitution([pkg_tb4_nav, 'maps', map_yaml]), + 'use_sim_time': 'True', + 'use_composition': 'False', + 'params_file': PathJoinSubstitution([pkg_tb4_sim_scenario, 'params', 'nav2_params.yaml']), + 'autostart': 'True'}.items() + ) + + # Create launch description + ld = LaunchDescription(ARGUMENTS) + ld.add_action(nav2_bringup) + return ld diff --git a/simulation/gazebo/tb4_sim_scenario/launch/robot_description.launch.py b/simulation/gazebo/tb4_sim_scenario/launch/robot_description.launch.py new file mode 100644 index 00000000..e5dd9ba0 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/launch/robot_description.launch.py @@ -0,0 +1,85 @@ +# Copyright (C) 2024 Intel Corporation +# Copyright 2021 Clearpath Robotics, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# @author Roni Kreinin (rkreinin@clearpathrobotics.com) + + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.substitutions import Command, PathJoinSubstitution +from launch.substitutions.launch_configuration import LaunchConfiguration + +from launch_ros.actions import Node + + +ARGUMENTS = [ + DeclareLaunchArgument('model', default_value='standard', + choices=['standard', 'lite'], + description='Turtlebot4 Model'), + DeclareLaunchArgument('use_sim_time', default_value='false', + choices=['true', 'false'], + description='use_sim_time'), + DeclareLaunchArgument('robot_name', default_value='turtlebot4', + description='Robot name'), + DeclareLaunchArgument('namespace', default_value=LaunchConfiguration('robot_name'), + description='Robot namespace'), +] + + +def generate_launch_description(): + pkg_tb4_sim_scenario = get_package_share_directory('tb4_sim_scenario') + xacro_file = PathJoinSubstitution([pkg_tb4_sim_scenario, + 'urdf', + 'turtlebot4.urdf.xacro']) + namespace = LaunchConfiguration('namespace') + + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[ + {'use_sim_time': LaunchConfiguration('use_sim_time')}, + {'robot_description': Command([ + 'xacro', ' ', xacro_file, ' ', + 'gazebo:=ignition', ' ', + 'namespace:=', namespace])}, + ], + remappings=[ + ('/tf', 'tf'), + ('/tf_static', 'tf_static') + ] + ) + + joint_state_publisher = Node( + package='joint_state_publisher', + executable='joint_state_publisher', + name='joint_state_publisher', + output='screen', + parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}], + remappings=[ + ('/tf', 'tf'), + ('/tf_static', 'tf_static') + ] + ) + + # Define LaunchDescription variable + ld = LaunchDescription(ARGUMENTS) + # Add nodes to LaunchDescription + ld.add_action(robot_state_publisher) + ld.add_action(joint_state_publisher) + return ld diff --git a/simulation/gazebo/tb4_sim_scenario/launch/ros_ign_bridge.launch.py b/simulation/gazebo/tb4_sim_scenario/launch/ros_ign_bridge.launch.py new file mode 100644 index 00000000..32b3f7d6 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/launch/ros_ign_bridge.launch.py @@ -0,0 +1,221 @@ +# Copyright (C) 2024 Intel Corporation +# Copyright 2023 Clearpath Robotics, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# @author Roni Kreinin (rkreinin@clearpathrobotics.com) + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription +from launch.conditions import LaunchConfigurationEquals +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch.substitutions.path_join_substitution import PathJoinSubstitution + +from launch_ros.actions import Node + +ARGUMENTS = [ + DeclareLaunchArgument('use_sim_time', default_value='true', + choices=['true', 'false'], + description='Use sim time'), + DeclareLaunchArgument('robot_name', default_value='turtlebot4', + description='Ignition model name'), + DeclareLaunchArgument('dock_name', default_value='standard_dock', + description='Ignition model name'), + DeclareLaunchArgument('namespace', default_value='', + description='Robot namespace'), + DeclareLaunchArgument('world', default_value='warehouse', + description='World name'), + DeclareLaunchArgument('scan_topic', default_value='scan', + description='Name of the scan topic'), + DeclareLaunchArgument('model', default_value='standard', + choices=['standard', 'lite'], + description='Turtlebot4 Model'), +] + + +def generate_launch_description(): + use_sim_time = LaunchConfiguration('use_sim_time') + robot_name = LaunchConfiguration('robot_name') + dock_name = LaunchConfiguration('dock_name') + namespace = LaunchConfiguration('namespace') + world = LaunchConfiguration('world') + scan_topic = LaunchConfiguration('scan_topic') + + leds = [ + 'power', + 'motors', + 'comms', + 'wifi', + 'battery', + 'user1', + 'user2' + ] + + pkg_irobot_create_ignition_bringup = get_package_share_directory( + 'irobot_create_ignition_bringup') + + create3_ros_gz_bridge_launch = PathJoinSubstitution( + [pkg_irobot_create_ignition_bringup, 'launch', 'create3_ros_ignition_bridge.launch.py']) + + create3_bridge = IncludeLaunchDescription( + PythonLaunchDescriptionSource([create3_ros_gz_bridge_launch]), + launch_arguments=[ + ('robot_name', robot_name), + ('dock_name', dock_name), + ('namespace', namespace), + ('world', world) + ] + ) + + # lidar bridge + lidar_bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + name='lidar_bridge', + output='screen', + parameters=[{ + 'use_sim_time': use_sim_time + }], + arguments=[ + ['/world/', world, + '/model/', robot_name, + '/link/rplidar_link/sensor/rplidar/scan' + + '@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan'] + ], + remappings=[ + (['/world/', world, + '/model/', robot_name, + '/link/rplidar_link/sensor/rplidar/scan'], + scan_topic) + ]) + + # Display message bridge + hmi_display_msg_bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + name='hmi_display_msg_bridge', + output='screen', + parameters=[{'use_sim_time': use_sim_time}], + arguments=[ + [namespace, '/hmi/display/raw' + + '@std_msgs/msg/String' + + ']ignition.msgs.StringMsg'], + [namespace, '/hmi/display/selected' + + '@std_msgs/msg/Int32' + + ']ignition.msgs.Int32'] + ], + remappings=[ + ([namespace, '/hmi/display/raw'], + 'hmi/display/_raw'), + ([namespace, '/hmi/display/selected'], + 'hmi/display/_selected') + ], + condition=LaunchConfigurationEquals('model', 'standard')) + + # Buttons message bridge + hmi_buttons_msg_bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + name='hmi_buttons_msg_bridge', + output='screen', + parameters=[{'use_sim_time': use_sim_time}], + arguments=[ + [namespace, '/hmi/buttons' + + '@std_msgs/msg/Int32' + + '[ignition.msgs.Int32'] + ], + remappings=[ + ([namespace, '/hmi/buttons'], + 'hmi/buttons/_set') + ], + condition=LaunchConfigurationEquals('model', 'standard')) + + # Buttons message bridge + hmi_led_msg_bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + name='hmi_led_msg_bridge', + output='screen', + parameters=[{'use_sim_time': use_sim_time}], + arguments=[ + [namespace, '/hmi/led/' + led + + '@std_msgs/msg/Int32' + + ']ignition.msgs.Int32'] for led in leds + ], + remappings=[ + ([namespace, '/hmi/led/' + led], + 'hmi/led/_' + led) for led in leds + ], + condition=LaunchConfigurationEquals('model', 'standard')) + + # Camera sensor bridge + oakd_camera_bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + name='camera_bridge', + output='screen', + parameters=[{'use_sim_time': use_sim_time}], + arguments=[ + ['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image' + + '@sensor_msgs/msg/Image' + + '[ignition.msgs.Image'], + ['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image' + + '@sensor_msgs/msg/Image' + + '[ignition.msgs.Image'], + ['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points' + + '@sensor_msgs/msg/PointCloud2' + + '[ignition.msgs.PointCloudPacked'], + ['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info' + + '@sensor_msgs/msg/CameraInfo' + + '[ignition.msgs.CameraInfo'], + ], + remappings=[ + (['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image'], + 'oakd/rgb/preview/image_raw'), + (['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image'], + 'oakd/rgb/preview/depth'), + (['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points'], + 'oakd/rgb/preview/depth/points'), + (['/world/', world, + '/model/', robot_name, + '/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info'], + 'oakd/rgb/preview/camera_info') + ] + ) + + # Define LaunchDescription variable + ld = LaunchDescription(ARGUMENTS) + ld.add_action(create3_bridge) + ld.add_action(hmi_display_msg_bridge) + ld.add_action(hmi_buttons_msg_bridge) + ld.add_action(hmi_led_msg_bridge) + ld.add_action(lidar_bridge) + ld.add_action(oakd_camera_bridge) + return ld diff --git a/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py b/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py new file mode 100644 index 00000000..c89f12ee --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/launch/sim_nav_scenario_launch.py @@ -0,0 +1,108 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetLaunchConfiguration +from launch.conditions import IfCondition, UnlessCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution + + +def generate_launch_description(): + + tb4_sim_scenario_dir = get_package_share_directory('tb4_sim_scenario') + scenario_execution_dir = get_package_share_directory('scenario_execution') + message_modification_dir = get_package_share_directory('message_modification') + tf_to_pose_publisher_dir = get_package_share_directory('tf_to_pose_publisher') + + scenario = LaunchConfiguration('scenario') + scenario_execution = LaunchConfiguration('scenario_execution') + arg_scenario = DeclareLaunchArgument('scenario', + description='Scenario file to execute') + arg_scenario_execution = DeclareLaunchArgument( + 'scenario_execution', default_value='True', + description='Wether to execute scenario execution') + world = LaunchConfiguration('world') + arg_world = DeclareLaunchArgument('world', default_value='maze', + description='Ignition World') + + faulty_scan = LaunchConfiguration('faulty_scan') + arg_faulty_scan = DeclareLaunchArgument( + 'faulty_scan', + default_value='false', + choices=['false', 'true'], + description='Whether to inject sensor faults to scan message') + + ignition = IncludeLaunchDescription( + PythonLaunchDescriptionSource([PathJoinSubstitution([tb4_sim_scenario_dir, 'launch', 'ignition_launch.py'])]), + ) + + robot_spawn = IncludeLaunchDescription( + PythonLaunchDescriptionSource([PathJoinSubstitution([tb4_sim_scenario_dir, 'launch', 'ignition_robot_launch.py'])]), + launch_arguments=[ + ('scan_topic', LaunchConfiguration('sim_scan_topic')), + ] + ) + + nav2_bringup = IncludeLaunchDescription( + PythonLaunchDescriptionSource([PathJoinSubstitution([tb4_sim_scenario_dir, 'launch', 'nav2_launch.py'])]), + ) + + scan_modification = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join(message_modification_dir, 'launch', 'scan_modification_launch.py')), + condition=IfCondition(faulty_scan), + launch_arguments=[ + ('ign_pose_topic', ['/world/', world, '/dynamic_pose/info']), + ] + ) + + scenario_exec = IncludeLaunchDescription( + PythonLaunchDescriptionSource([PathJoinSubstitution([scenario_execution_dir, 'launch', 'scenario_launch.py'])]), + condition=IfCondition(scenario_execution), + launch_arguments=[ + ('scenario', scenario), + ] + ) + + tf_to_pose = IncludeLaunchDescription( + PythonLaunchDescriptionSource([PathJoinSubstitution([tf_to_pose_publisher_dir, 'launch', 'tf_to_pose_launch.py'])]), + ) + + ld = LaunchDescription([ + arg_scenario, + arg_scenario_execution, + arg_world, + arg_faulty_scan, + SetLaunchConfiguration( + name='sim_scan_topic', + condition=IfCondition(faulty_scan), + value='scan_sim'), + SetLaunchConfiguration( + name='sim_scan_topic', + condition=UnlessCondition(faulty_scan), + value='scan'), + ]) + ld.add_action(ignition) + ld.add_action(robot_spawn) + ld.add_action(nav2_bringup) + ld.add_action(scan_modification) + ld.add_action(scenario_exec) + ld.add_action(tf_to_pose) + return ld diff --git a/simulation/gazebo/tb4_sim_scenario/package.xml b/simulation/gazebo/tb4_sim_scenario/package.xml new file mode 100644 index 00000000..383916da --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/package.xml @@ -0,0 +1,27 @@ + + + + tb4_sim_scenario + 1.0.0 + TurtleBot 4 Simulation Scenario Execution + Intel Labs + Intel Labs + Apache-2.0 + + ament_cmake + + + turtlebot4_simulator + turtlebot4_description + scenario_execution + message_modification + tf_to_pose_publisher + + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/simulation/gazebo/tb4_sim_scenario/params/nav2_params.yaml b/simulation/gazebo/tb4_sim_scenario/params/nav2_params.yaml new file mode 100644 index 00000000..2f997af4 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/params/nav2_params.yaml @@ -0,0 +1,440 @@ +--- +amcl: + ros__parameters: + use_sim_time: True + alpha1: 0.2 + alpha2: 0.2 + alpha3: 0.2 + alpha4: 0.2 + alpha5: 0.2 + base_frame_id: "base_link" + beam_skip_distance: 0.5 + beam_skip_error_threshold: 0.9 + beam_skip_threshold: 0.3 + do_beamskip: false + global_frame_id: "map" + lambda_short: 0.1 + laser_likelihood_max_dist: 2.0 + laser_max_range: 100.0 + laser_min_range: -1.0 + laser_model_type: "likelihood_field" + max_beams: 60 + max_particles: 2000 + min_particles: 500 + odom_frame_id: "odom" + pf_err: 0.05 + pf_z: 0.99 + recovery_alpha_fast: 0.0 + recovery_alpha_slow: 0.0 + resample_interval: 1 + robot_model_type: "nav2_amcl::DifferentialMotionModel" + save_pose_rate: 0.5 + sigma_hit: 0.2 + tf_broadcast: true + transform_tolerance: 1.0 + update_min_a: 0.2 + update_min_d: 0.25 + z_hit: 0.5 + z_max: 0.05 + z_rand: 0.5 + z_short: 0.05 + scan_topic: scan + +bt_navigator: + ros__parameters: + use_sim_time: True + global_frame: map + robot_base_frame: base_link + odom_topic: /odom + bt_loop_duration: 10 + default_server_timeout: 20 + # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' + # are use defaults: + # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml + # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml + # They can be set here or via a RewrittenYaml remap from a parent launch + # ile to Nav2. + plugin_lib_names: + - nav2_compute_path_to_pose_action_bt_node + - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_action_bt_node + - nav2_assisted_teleop_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_bt_node + - nav2_clear_costmap_service_bt_node + - nav2_is_stuck_condition_bt_node + - nav2_goal_reached_condition_bt_node + - nav2_goal_updated_condition_bt_node + - nav2_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_condition_bt_node + - nav2_initial_pose_received_condition_bt_node + - nav2_reinitialize_global_localization_service_bt_node + - nav2_rate_controller_bt_node + - nav2_distance_controller_bt_node + - nav2_speed_controller_bt_node + - nav2_truncate_path_action_bt_node + - nav2_truncate_path_local_action_bt_node + - nav2_goal_updater_node_bt_node + - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node + - nav2_round_robin_node_bt_node + - nav2_transform_available_condition_bt_node + - nav2_time_expired_condition_bt_node + - nav2_path_expiring_timer_condition + - nav2_distance_traveled_condition_bt_node + - nav2_single_trigger_bt_node + - nav2_goal_updated_controller_bt_node + - nav2_is_battery_low_condition_bt_node + - nav2_navigate_through_poses_action_bt_node + - nav2_navigate_to_pose_action_bt_node + - nav2_remove_passed_goals_action_bt_node + - nav2_planner_selector_bt_node + - nav2_controller_selector_bt_node + - nav2_goal_checker_selector_bt_node + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_assisted_teleop_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node + - nav2_is_battery_charging_condition_bt_node + +bt_navigator_navigate_through_poses_rclcpp_node: + ros__parameters: + use_sim_time: True + +bt_navigator_navigate_to_pose_rclcpp_node: + ros__parameters: + use_sim_time: True + +controller_server: + ros__parameters: + use_sim_time: True + controller_frequency: 20.0 + min_x_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 + min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 + progress_checker_plugin: "progress_checker" + goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" + controller_plugins: ["FollowPath"] + + # Progress checker parameters + progress_checker: + plugin: "nav2_controller::SimpleProgressChecker" + required_movement_radius: 0.5 + movement_time_allowance: 10.0 + # Goal checker parameters + #precise_goal_checker: + # plugin: "nav2_controller::SimpleGoalChecker" + # xy_goal_tolerance: 0.25 + # yaw_goal_tolerance: 0.25 + # stateful: True + general_goal_checker: + stateful: True + plugin: "nav2_controller::SimpleGoalChecker" + xy_goal_tolerance: 0.25 + yaw_goal_tolerance: 0.25 + # DWB parameters + FollowPath: + plugin: "dwb_core::DWBLocalPlanner" + debug_trajectory_details: True + min_vel_x: 0.0 + min_vel_y: 0.0 + max_vel_x: 0.26 + max_vel_y: 0.0 + max_vel_theta: 1.0 + min_speed_xy: 0.0 + max_speed_xy: 0.26 + min_speed_theta: 0.0 + # Add high threshold velocity for turtlebot 3 issue. + # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 + acc_lim_x: 2.5 + acc_lim_y: 0.0 + acc_lim_theta: 3.2 + decel_lim_x: -2.5 + decel_lim_y: 0.0 + decel_lim_theta: -3.2 + vx_samples: 20 + vy_samples: 5 + vtheta_samples: 20 + sim_time: 1.7 + linear_granularity: 0.05 + angular_granularity: 0.025 + transform_tolerance: 0.2 + xy_goal_tolerance: 0.25 + trans_stopped_velocity: 0.25 + short_circuit_trajectory_evaluation: True + stateful: True + critics: + - "RotateToGoal" + - "Oscillation" + - "BaseObstacle" + - "GoalAlign" + - "PathAlign" + - "PathDist" + - "GoalDist" + BaseObstacle.scale: 0.02 + PathAlign.scale: 32.0 + PathAlign.forward_point_distance: 0.1 + GoalAlign.scale: 24.0 + GoalAlign.forward_point_distance: 0.1 + PathDist.scale: 32.0 + GoalDist.scale: 24.0 + RotateToGoal.scale: 32.0 + RotateToGoal.slowing_factor: 5.0 + RotateToGoal.lookahead_time: -1.0 + +local_costmap: + local_costmap: + ros__parameters: + update_frequency: 5.0 + publish_frequency: 2.0 + global_frame: odom + robot_base_frame: base_link + use_sim_time: True + rolling_window: true + width: 3 + height: 3 + resolution: 0.05 + robot_radius: 0.22 + plugins: ["voxel_layer", "inflation_layer"] + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.55 + voxel_layer: + plugin: "nav2_costmap_2d::VoxelLayer" + enabled: True + publish_voxel_map: True + origin_z: 0.0 + z_resolution: 0.05 + z_voxels: 16 + max_obstacle_height: 2.0 + mark_threshold: 0 + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: True + always_send_full_costmap: True + +global_costmap: + global_costmap: + ros__parameters: + update_frequency: 1.0 + publish_frequency: 1.0 + global_frame: map + robot_base_frame: base_link + use_sim_time: True + robot_radius: 0.22 + resolution: 0.05 + track_unknown_space: true + plugins: ["static_layer", "obstacle_layer", "inflation_layer"] + obstacle_layer: + plugin: "nav2_costmap_2d::ObstacleLayer" + enabled: True + observation_sources: scan + scan: + topic: /scan + max_obstacle_height: 2.0 + clearing: True + marking: True + data_type: "LaserScan" + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: True + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 3.0 + inflation_radius: 0.55 + always_send_full_costmap: True + +map_server: + ros__parameters: + use_sim_time: True + # Overridden in launch by the "map" launch configuration or provided + # default value. To use in yaml, remove the default "map" value in the + # tb3_simulation_launch.py file & provide full path to map below. + yaml_filename: "" + +map_saver: + ros__parameters: + use_sim_time: True + save_map_timeout: 5.0 + free_thresh_default: 0.25 + occupied_thresh_default: 0.65 + map_subscribe_transient_local: True + +planner_server: + ros__parameters: + expected_planner_frequency: 20.0 + use_sim_time: True + planner_plugins: ["GridBased"] + GridBased: + plugin: "nav2_navfn_planner/NavfnPlanner" + tolerance: 0.5 + use_astar: false + allow_unknown: true + +smoother_server: + ros__parameters: + use_sim_time: True + smoother_plugins: ["simple_smoother"] + simple_smoother: + plugin: "nav2_smoother::SimpleSmoother" + tolerance: 1.0e-10 + max_its: 1000 + do_refinement: True + +behavior_server: + ros__parameters: + costmap_topic: local_costmap/costmap_raw + footprint_topic: local_costmap/published_footprint + cycle_frequency: 10.0 + behavior_plugins: + - "spin" + - "backup" + - "drive_on_heading" + - "assisted_teleop" + - "wait" + spin: + plugin: "nav2_behaviors/Spin" + backup: + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" + wait: + plugin: "nav2_behaviors/Wait" + assisted_teleop: + plugin: "nav2_behaviors/AssistedTeleop" + global_frame: odom + robot_base_frame: base_link + transform_tolerance: 0.1 + use_sim_time: true + simulate_ahead_time: 2.0 + max_rotational_vel: 1.0 + min_rotational_vel: 0.4 + rotational_acc_lim: 3.2 + +robot_state_publisher: + ros__parameters: + use_sim_time: True + +waypoint_follower: + ros__parameters: + use_sim_time: True + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: True + waypoint_pause_duration: 200 + +velocity_smoother: + ros__parameters: + use_sim_time: True + smoothing_frequency: 20.0 + scale_velocities: False + feedback: "OPEN_LOOP" + max_velocity: [0.26, 0.0, 1.0] + min_velocity: [-0.26, 0.0, -1.0] + max_accel: [2.5, 0.0, 3.2] + max_decel: [-2.5, 0.0, -3.2] + odom_topic: "odom" + odom_duration: 0.1 + deadband_velocity: [0.0, 0.0, 0.0] + velocity_timeout: 1.0 + +slam_toolbox: + ros__parameters: + + # Plugin params + solver_plugin: solver_plugins::CeresSolver + ceres_linear_solver: SPARSE_NORMAL_CHOLESKY + ceres_preconditioner: SCHUR_JACOBI + ceres_trust_strategy: LEVENBERG_MARQUARDT + ceres_dogleg_type: TRADITIONAL_DOGLEG + ceres_loss_function: None + + # ROS Parameters + odom_frame: odom + map_frame: map + base_frame: base_link + scan_topic: /scan + mode: mapping #localization + + # if you'd like to immediately start continuing a map at a given pose + # or at the dock, but they are mutually exclusive, if pose is given + # will use pose + #map_file_name: test_steve + #map_start_pose: [0.0, 0.0, 0.0] + #map_start_at_dock: true + + debug_logging: false + throttle_scans: 1 + transform_publish_period: 0.02 #if 0 never publishes odometry + map_update_interval: 5.0 + resolution: 0.05 + max_laser_range: 20.0 #for rastering images + minimum_time_interval: 0.5 + transform_timeout: 0.7 + tf_buffer_duration: 30. + stack_size_to_use: 40000000 # program needs a larger stack size + # to serialize large maps + enable_interactive_mode: true + + # General Parameters + use_scan_matching: true + use_scan_barycenter: true + minimum_travel_distance: 0.5 + minimum_travel_heading: 0.5 + scan_buffer_size: 10 + scan_buffer_maximum_scan_distance: 10.0 + link_match_minimum_response_fine: 0.1 + link_scan_maximum_distance: 1.5 + loop_search_maximum_distance: 3.0 + do_loop_closing: true + loop_match_minimum_chain_size: 10 + loop_match_maximum_variance_coarse: 3.0 + loop_match_minimum_response_coarse: 0.35 + loop_match_minimum_response_fine: 0.45 + + # Correlation Parameters - Correlation Parameters + correlation_search_space_dimension: 0.5 + correlation_search_space_resolution: 0.01 + correlation_search_space_smear_deviation: 0.1 + + # Correlation Parameters - Loop Closure Parameters + loop_search_space_dimension: 8.0 + loop_search_space_resolution: 0.05 + loop_search_space_smear_deviation: 0.03 + + # Scan Matcher Parameters + distance_variance_penalty: 0.5 + angle_variance_penalty: 1.0 + + fine_search_angle_offset: 0.00349 + coarse_search_angle_offset: 0.349 + coarse_angle_resolution: 0.0349 + minimum_angle_penalty: 0.9 + minimum_distance_penalty: 0.5 + use_response_expansion: true diff --git a/simulation/gazebo/tb4_sim_scenario/urdf/create3.urdf.xacro b/simulation/gazebo/tb4_sim_scenario/urdf/create3.urdf.xacro new file mode 100644 index 00000000..34dd4cc6 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/urdf/create3.urdf.xacro @@ -0,0 +1,323 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $(find irobot_create_control)/config/control.yaml + + ~/odom:=odom + /tf:=tf + /tf_static:=tf_static + /diagnostics:=diagnostics + $(arg namespace) + + + + + + + + + $(find irobot_create_control)/config/control.yaml + + ~/odom:=odom + /tf:=tf + /tf_static:=tf_static + /diagnostics:=diagnostics + $(arg namespace) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $(arg namespace) + odom:=sim_ground_truth_pose + + base_link + world + 62 + 0 0 0 + 0.0 0.0 0.0 + 0.0 + + + + + + + + $(arg namespace) + ~/out:=dock_status + + 1.0 + ${robot_model_name} + ${receiver_link_name} + ${dock_model_name} + ${emitter_link_name} + + + + + + + + true + true + true + 62 + + + + + diff --git a/simulation/gazebo/tb4_sim_scenario/urdf/turtlebot4.urdf.xacro b/simulation/gazebo/tb4_sim_scenario/urdf/turtlebot4.urdf.xacro new file mode 100644 index 00000000..e57e1948 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/urdf/turtlebot4.urdf.xacro @@ -0,0 +1,144 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulation/gazebo/tb4_sim_scenario/worlds/maze.sdf b/simulation/gazebo/tb4_sim_scenario/worlds/maze.sdf new file mode 100644 index 00000000..274a8620 --- /dev/null +++ b/simulation/gazebo/tb4_sim_scenario/worlds/maze.sdf @@ -0,0 +1,1066 @@ + + + + + + 0.003 + 1 + 1000 + + + + + + + ogre + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.90000000000000002 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + 1 + + + + + 0 0 1 + 100 100 + + + + + + + + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + 0 0 0 0 -0 0 + + + + 0 0 1 0 0 0 + true + + -10.005 0 0 0 0 0 + true + + + + 0.01 20 2 + + + + + + + 0.01 20 2 + + + + 0.1 0.1 0.1 1 + 0 0.01 0.05 1 + 0 0.01 0.05 1 + + + + + 10.005 0 0 0 0 0 + true + + + + 0.01 20 2 + + + + + + + 0.01 20 2 + + + + 0.1 0.1 0.1 1 + 0 0.01 0.05 1 + 0 0.01 0.05 1 + + + + + 0 10.005 0 0 0 0 + true + + + + 20 0.01 2 + + + + + + + 20 0.01 2 + + + + 0.1 0.1 0.1 1 + 0 0.01 0.05 1 + 0 0.01 0.05 1 + + + + + 0 -10.005 0 0 0 0 + true + + + + 20 0.01 2 + + + + 0.1 0.1 0.1 1 + 0 0.01 0.05 1 + 0 0.01 0.05 1 + + + + + + 20 0.01 2 + + + + 0.1 0.1 0.1 1 + 0 0.01 0.05 1 + 0 0.01 0.05 1 + + + + + + + 0 0 0.5 0 0 0 + true + + -6.5 -9 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -8.5 -6.5 0 0 0 0 + true + + + + 3 1 1 + + + + + + + 3 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -3.5 -7 0 0 0 0 + true + + + + 1 6 1 + + + + + + + 1 6 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 2.5 -9 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 7 -8.5 0 0 0 0 + true + + + + 2 1 1 + + + + + + + 2 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -9 -0.5 0 0 0 0 + true + + + + 2 1 1 + + + + + + + 2 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -8.5 -2.5 0 0 0 0 + true + + + + 1 3 1 + + + + + + + 1 3 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -4.5 -1.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -6 1 0 0 0 0 + true + + + + 2 2 1 + + + + + + + 2 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -7.5 4.5 0 0 0 0 + true + + + + 5 1 1 + + + + + + + 5 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -3 7.5 0 0 0 0 + true + + + + 4 1 1 + + + + + + + 4 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + 0 5.5 0 0 0 0 + true + + + + 2 9 1 + + + + + + + 2 9 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 0 -2.5 0 0 0 0 + true + + + + 2 1 1 + + + + + + + 2 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -0.5 -1.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + -0.5 -4.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 0.5 -5.5 0 0 0 0 + true + + + + 3 1 1 + + + + + + + 3 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 2.5 -4.5 0 0 0 0 + true + + + + 3 1 1 + + + + + + + 3 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 4.5 -5.5 0 0 0 0 + true + + + + 3 1 1 + + + + + + + 3 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 6.5 -4.5 0 0 0 0 + true + + + + 3 1 1 + + + + + + + 3 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 8.5 -5.5 0 0 0 0 + true + + + + 3 1 1 + + + + + + + 3 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 9.5 -4.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 3.5 -0.5 0 0 0 0 + true + + + + 1 3 1 + + + + + + + 1 3 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 7 0.5 0 0 0 0 + true + + + + 6 1 1 + + + + + + + 6 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 7.5 2 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 1.5 5.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 2.5 6 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 3.5 7.5 0 0 0 0 + true + + + + 1 3 1 + + + + + + + 1 3 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 4.5 8.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 5.5 9 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 6.5 9.5 0 0 0 0 + true + + + + 1 1 1 + + + + + + + 1 1 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 4.5 3 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 5.5 4 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 6.5 5 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 7.5 6 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 8.5 7 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + 9.5 8 0 0 0 0 + true + + + + 1 2 1 + + + + + + + 1 2 1 + + + + 0.1 0.1 0.1 1 + 0 0.1 0.2 1 + 0 0.01 0.05 1 + + + + + + \ No newline at end of file diff --git a/tools/message_modification/README.md b/tools/message_modification/README.md new file mode 100644 index 00000000..3fdf79bd --- /dev/null +++ b/tools/message_modification/README.md @@ -0,0 +1,3 @@ +# Message modification + +The `message_modification` packages provides ros nodes that receive ROS messages, modify the content and republish them. \ No newline at end of file diff --git a/tools/message_modification/launch/scan_modification_launch.py b/tools/message_modification/launch/scan_modification_launch.py new file mode 100644 index 00000000..e9eaa341 --- /dev/null +++ b/tools/message_modification/launch/scan_modification_launch.py @@ -0,0 +1,68 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +# The main goal of this launch file is the visualization of the tf output topic in rviz2 +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, GroupAction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node, PushRosNamespace + +ARGUMENTS = [ + DeclareLaunchArgument('namespace', default_value='', + description='Robot namespace (without leading /)'), + + DeclareLaunchArgument('in_topic_scan', default_value='scan_sim', + description='Whether to execute simulation gui'), + + DeclareLaunchArgument('out_topic_scan', default_value='scan', + description='Whether to execute simulation gui'), + + DeclareLaunchArgument('drop_percentage', default_value='0.0', + description='Amount of dropped scan points in %'), + + DeclareLaunchArgument('std_dev_noise', default_value='0.0', + description='Whether to execute simulation gui'), +] + + +def generate_launch_description(): + namespace = LaunchConfiguration("namespace") + in_topic_scan = LaunchConfiguration("in_topic_scan") + out_topic_scan = LaunchConfiguration("out_topic_scan") + drop_percentage = LaunchConfiguration("drop_percentage") + std_dev_noise = LaunchConfiguration("std_dev_noise") + + modification_group_action = GroupAction( + [ + PushRosNamespace(namespace), + Node( + package="message_modification", + name="laserscan_modification", + executable="laserscan_modification", + remappings=[ + ("in", in_topic_scan), + ("out", out_topic_scan), + ], + parameters=[ + {"random_drop_percentage": drop_percentage}, + {"gaussian_noise_std_deviation": std_dev_noise}, + ], + ), + ] + ) + ld = LaunchDescription(ARGUMENTS) + ld.add_action(modification_group_action) + return ld diff --git a/tools/message_modification/message_modification/__init__.py b/tools/message_modification/message_modification/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/tools/message_modification/message_modification/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/tools/message_modification/message_modification/laserscan_modification.py b/tools/message_modification/message_modification/laserscan_modification.py new file mode 100755 index 00000000..1248b08e --- /dev/null +++ b/tools/message_modification/message_modification/laserscan_modification.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import rclpy +from rclpy.node import Node +from rclpy.qos import QoSPresetProfiles + +from rclpy.parameter import Parameter +from rcl_interfaces.msg import SetParametersResult + +from sensor_msgs.msg import LaserScan +import numpy as np + + +class LaserscanModification(Node): + + def __init__(self): + super().__init__('laserscan_modification') + + self.declare_parameter('random_drop_percentage', 0.0) + self.random_drop_percentage = self.get_parameter('random_drop_percentage').value + self.declare_parameter('gaussian_noise_std_deviation', 0.0) + self.gaussian_noise_std_deviation = self.get_parameter('gaussian_noise_std_deviation').value + + self.add_on_set_parameters_callback(self.parameter_callback) + + self.out_publisher = self.create_publisher(LaserScan, "out", qos_profile=QoSPresetProfiles.SENSOR_DATA.value) + self.in_subscriber = self.create_subscription(LaserScan, 'in', self.callback, qos_profile=QoSPresetProfiles.SENSOR_DATA.value) + + def parameter_callback(self, params): + result = True + for param in params: + if param.name == 'random_drop_percentage' and param.type_ == Parameter.Type.DOUBLE: + if param.value <= 1.0 and param.value >= 0.0: + self.random_drop_percentage = param.value + else: + result = False + elif param.name == 'gaussian_noise_std_deviation' and param.type_ == Parameter.Type.DOUBLE: + self.gaussian_noise_std_deviation = param.value + else: + result = False + + self.get_logger().info(f"Parameter update {params}: success={result}") + return SetParametersResult(successful=result) + + def callback(self, msg): + if self.random_drop_percentage != 0.0: + ranges = np.asarray(msg.ranges) + indices = np.random.choice(np.arange(len(msg.ranges)), replace=False, + size=int(len(msg.ranges) * self.random_drop_percentage)) + ranges[indices] = np.inf + msg.ranges = ranges.tolist() + if self.gaussian_noise_std_deviation != 0.0: + gaussian_noise = np.random.normal(0, self.gaussian_noise_std_deviation, len(msg.ranges)) + ranges_with_noise = msg.ranges + gaussian_noise + msg.ranges = ranges_with_noise.tolist() + self.out_publisher.publish(msg) + + +def main(args=None): + rclpy.init(args=args) + laserscan_modification = LaserscanModification() + + executor = rclpy.executors.MultiThreadedExecutor() + executor.add_node(laserscan_modification) + + try: + executor.spin() + except KeyboardInterrupt: + laserscan_modification.get_logger().info("User requested shut down.") + finally: + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/tools/message_modification/message_modification/message_drop.py b/tools/message_modification/message_modification/message_drop.py new file mode 100755 index 00000000..e3b3053b --- /dev/null +++ b/tools/message_modification/message_modification/message_drop.py @@ -0,0 +1,79 @@ +#!/usr/bin/env python +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +import rclpy +from rclpy.node import Node +from rclpy.qos import QoSPresetProfiles + +from rclpy.parameter import Parameter +from rcl_interfaces.msg import SetParametersResult + +import importlib +import random + + +class MessageDrop(Node): + + def __init__(self): + super().__init__('message_drop') + + self.declare_parameter('message_type', rclpy.Parameter.Type.STRING) + datatype_in_list = self.get_parameter('message_type').value.split(".") + self.topic_type = getattr(importlib.import_module(".".join(datatype_in_list[0:-1])), datatype_in_list[-1]) + + self.declare_parameter('drop_rate', 0.0) + self.drop_rate = self.get_parameter('drop_rate').value + + self.out_publisher = self.create_publisher(self.topic_type, "out", qos_profile=QoSPresetProfiles.SENSOR_DATA.value) + self.in_subscriber = self.create_subscription(self.topic_type, 'in', self.callback, qos_profile=QoSPresetProfiles.SENSOR_DATA.value) + + def parameter_callback(self, params): + result = True + for param in params: + if param.name == 'drop_rate' and param.type_ == Parameter.Type.DOUBLE: + if param.value <= 1.0: + self.drop_rate = param.value + else: + result = False + else: + result = False + self.get_logger().info(f"Parameter update {params}. result={result}") + return SetParametersResult(successful=result) + + def callback(self, msg): + drop = random.random() <= self.drop_rate # nosec B311 + if not drop: + self.out_publisher.publish(msg) + + +def main(args=None): + rclpy.init(args=args) + node = MessageDrop() + + executor = rclpy.executors.MultiThreadedExecutor() + executor.add_node(node) + + try: + executor.spin() + except KeyboardInterrupt: + node.get_logger().info("User requested shut down.") + finally: + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/tools/message_modification/package.xml b/tools/message_modification/package.xml new file mode 100644 index 00000000..bc6f237f --- /dev/null +++ b/tools/message_modification/package.xml @@ -0,0 +1,17 @@ + + + message_modification + 1.0.0 + Modification of message data + Intel Labs + Intel Labs + Apache-2.0 + + sensor_msgs + + rclpy + + + ament_python + + diff --git a/tools/message_modification/resource/message_modification b/tools/message_modification/resource/message_modification new file mode 100644 index 00000000..e69de29b diff --git a/tools/message_modification/setup.cfg b/tools/message_modification/setup.cfg new file mode 100644 index 00000000..3b78448f --- /dev/null +++ b/tools/message_modification/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/message_modification +[install] +install_scripts=$base/lib/message_modification \ No newline at end of file diff --git a/tools/message_modification/setup.py b/tools/message_modification/setup.py new file mode 100644 index 00000000..90f3389e --- /dev/null +++ b/tools/message_modification/setup.py @@ -0,0 +1,47 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" +Setup for message_modification +""" +import os +from glob import glob + +from setuptools import setup + +PACKAGE_NAME = 'message_modification' +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=[PACKAGE_NAME], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + PACKAGE_NAME]), + (os.path.join('share', PACKAGE_NAME), ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'launch'), glob('launch/*launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Message modification', + license='Apache License 2.0', + entry_points={ + 'console_scripts': [ + 'laserscan_modification = message_modification.laserscan_modification:main', + 'message_drop = message_modification.message_drop:main', + ], + }, +) diff --git a/tools/scenario_status/README.md b/tools/scenario_status/README.md new file mode 100644 index 00000000..ae457f2b --- /dev/null +++ b/tools/scenario_status/README.md @@ -0,0 +1,3 @@ +# Scenario Status + +The `scenario_status` packages provides the scenario_status ROS node that publishes the current scenario status to a topic. During ros-bag recording this allows to directly match data with a scenario status. \ No newline at end of file diff --git a/tools/scenario_status/package.xml b/tools/scenario_status/package.xml new file mode 100644 index 00000000..820189f2 --- /dev/null +++ b/tools/scenario_status/package.xml @@ -0,0 +1,29 @@ + + + + scenario_status + 1.0.0 + + Simple node to call a service to publish the py-trees-\ + behaviour tree to a topic, then subscribe to that topic and publish \ + changes in behaviour states as strings at the time they are \ + happening + + Intel Labs + Intel Labs + Apache-2.0 + + rclpy + py_trees_ros_interfaces + scenario_execution_interfaces + rosgraph_msgs + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_python + + diff --git a/tools/scenario_status/resource/scenario_status b/tools/scenario_status/resource/scenario_status new file mode 100644 index 00000000..e69de29b diff --git a/tools/scenario_status/scenario_status/__init__.py b/tools/scenario_status/scenario_status/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/tools/scenario_status/scenario_status/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/tools/scenario_status/scenario_status/scenario_status_node.py b/tools/scenario_status/scenario_status/scenario_status_node.py new file mode 100644 index 00000000..4bc6efda --- /dev/null +++ b/tools/scenario_status/scenario_status/scenario_status_node.py @@ -0,0 +1,204 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +"""node to publish the status of the running scenario to a ROS topic""" +#!/usr/bin/env python3 + +import rclpy +from rclpy import qos +from rclpy.node import Node +from rcl_interfaces.msg import ParameterDescriptor + +from py_trees_ros_interfaces.srv import OpenSnapshotStream +from py_trees_ros_interfaces.msg import BehaviourTree +from scenario_execution_interfaces.msg import ScenarioStatus as ScenarioStatusMsg # pylint: disable=no-name-in-module +from rosgraph_msgs.msg import Clock + + +class ScenarioStatus(Node): + + """Simple node to call a service to publish the py-trees-behaviour tree + to a topic, then subscribe to that topic and publish changes in behaviour + states as strings at the time they are happening.""" + + def __init__(self): + """initialize node""" + super().__init__('scenario_status') + + self.bt_topic = None + self.snapshot_srv_name = None + self.scenario_status_topic = None + self.behaviour_infos = None + self.last_behaviour_infos = None + self.scenario_bt = None + self.time = None + # self.client_node = None + self.logger = self.get_logger() + + self.states_dict = { + 1: 'INVALID', + 2: 'RUNNING', + 3: 'SUCCESS', + 4: 'FAILURE' + } + self.types_dict = { + # Possible types of behaviour + 0: 'UNKNOWN_TYPE', + 1: 'BEHAVIOUR', + 2: 'SEQUENCE', + 3: 'SELECTOR', + 4: 'PARALLEL', + 5: 'CHOOSER', + 6: 'DECORATOR' + } + self.params() + + clock_qos = qos.QoSProfile( + durability=qos.QoSDurabilityPolicy.VOLATILE, + reliability=qos.QoSReliabilityPolicy.BEST_EFFORT, + history=qos.QoSHistoryPolicy.KEEP_LAST, + depth=5) + self.clock_sub = self.create_subscription(Clock, '/clock', self.clock_callback, clock_qos) + self.status_pub = self.create_publisher(ScenarioStatusMsg, self.scenario_status_topic, 10) + + # self.request_bt_publishing() + + self.snapshot_sub = self.create_subscription( + BehaviourTree, + self.bt_topic, + self.snapshot_callback, + 10 + ) + + def clock_callback(self, msg): + self.time = msg + + def request_bt_publishing(self): + """Request publishing of the py-trees-behaviour tree via the given + topic name vy calling the corresponding service. + :returns: - + + """ + # self.client_node = rclpy.create_node('srv_client_node') + snapshot_client = self.create_client(OpenSnapshotStream, self.snapshot_srv_name) + while not snapshot_client.wait_for_service(timeout_sec=1.0): + self.logger.info( + 'Service to open bt snapshot not available, waiting again ...') + + req = OpenSnapshotStream.Request(topic_name=self.bt_topic) + req.topic_name = self.bt_topic + # calling service to publish pytrees behaviour tree snapshot to topic + future = snapshot_client.call_async(req) + rclpy.spin_until_future_complete(self, future) + if future.result() is not None: + self.bt_topic = future.result().topic_name + self.logger.info( + 'Triggered publishing of bt snapshot to topic: %s' % self.bt_topic) + else: + self.logger.error('Exception while calling service: {}'.format(future.exception())) + + def params(self): + """handle ROS parameters and store them as class variables + :returns: - + + """ + self.declare_parameter('bt_snapshot_topic', '/bt_snapshot', + descriptor=ParameterDescriptor(dynamic_typing=True)) + self.declare_parameter('snapshot_srv_name', '/scenario_execution/snapshot_streams/open', + descriptor=ParameterDescriptor(dynamic_typing=True)) + self.declare_parameter('scenario_status_topic', '/scenario_status', + descriptor=ParameterDescriptor(dynamic_typing=True)) + + self.bt_topic = self.get_parameter_or( + 'bt_snapshot_topic').get_parameter_value().string_value + self.snapshot_srv_name = self.get_parameter_or( + 'snapshot_srv_name').get_parameter_value().string_value + self.scenario_status_topic = self.get_parameter_or( + 'scenario_status_topic').get_parameter_value().string_value + + @staticmethod + def get_behaviour_infos(behaviour_tree_msg): + """get information about behaviour tree as dictionary + :returns: dictionary containing information + + """ + result = {} + for behaviour in behaviour_tree_msg.behaviours: + result[behaviour.name] = { + 'class_name': behaviour.class_name, + 'status': behaviour.status, + 'is_active': behaviour.is_active, + 'type': behaviour.type, + 'message': behaviour.message + } + return result + + def snapshot_callback(self, msg): + """callback for the behaviour tree snapshop topic + + :msg: incoming behaviour tree msg + :returns: - + + """ + current_time = None + if self.time: + current_time = self.time.clock + self.logger.debug('received bt_snapshot') + if self.scenario_bt is not None: + self.last_behaviour_infos = self.get_behaviour_infos( + self.scenario_bt + ) + self.scenario_bt = msg + self.behaviour_infos = self.get_behaviour_infos(self.scenario_bt) + # we can only check for changes if we have a previous bt available + if self.last_behaviour_infos is not None: + for behaviour, infos in self.behaviour_infos.items(): + if infos['status'] not in self.states_dict or self.last_behaviour_infos[behaviour]['status'] not in self.states_dict: + continue + if infos['status'] != self.last_behaviour_infos[behaviour]['status']: + beh_type = self.types_dict[infos['type']] + last_status = self.states_dict[self.last_behaviour_infos[behaviour]['status']] + current_status = self.states_dict[infos['status']] + result_str = f'{behaviour}({beh_type}): {last_status} > {current_status}' + debug_str = 'behaviour %s of type %s changed state from %s to %s, with message %s' % ( + behaviour, beh_type, last_status, current_status, infos['message']) + msg = ScenarioStatusMsg() + msg.data = result_str + msg.system_time = self.get_clock().now().to_msg() + if current_time: + msg.ros_time = current_time + self.logger.debug(debug_str) + self.status_pub.publish(msg) + + +def main(args=None): + """main function for the node to spin + """ + rclpy.init(args=args) + + scenario_status = ScenarioStatus() + + try: + scenario_status.request_bt_publishing() + rclpy.spin(scenario_status) + except KeyboardInterrupt: + pass + finally: + scenario_status.destroy_node() + + +if __name__ == "__main__": + main() diff --git a/tools/scenario_status/setup.cfg b/tools/scenario_status/setup.cfg new file mode 100644 index 00000000..b2f519b2 --- /dev/null +++ b/tools/scenario_status/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/scenario_status +[install] +install_scripts=$base/lib/scenario_status diff --git a/tools/scenario_status/setup.py b/tools/scenario_status/setup.py new file mode 100644 index 00000000..c19beb01 --- /dev/null +++ b/tools/scenario_status/setup.py @@ -0,0 +1,50 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +""" Setup python package """ +import os +from glob import glob +from setuptools import find_packages, setup + +PACKAGE_NAME = 'scenario_status' + +setup( + name=PACKAGE_NAME, + version='0.0.1', + packages=find_packages(), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME), glob('scenario_status/*.py')), + (os.path.join('share', PACKAGE_NAME), glob('params/*.yaml')), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Simple node to call a service to publish the py-trees-\ + behaviour tree to a topic, then subscribe to that topic and publish \ + changes in behaviour states as strings at the time they are \ + happening.', + license='Apache License 2.0', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'scenario_status_node = scenario_status.scenario_status_node:main' + ], + }, +) diff --git a/tools/tf_to_pose_publisher/README.md b/tools/tf_to_pose_publisher/README.md new file mode 100644 index 00000000..012a975a --- /dev/null +++ b/tools/tf_to_pose_publisher/README.md @@ -0,0 +1,3 @@ +# TF to Pose Publisher + +The `tf_to_pose_publisher` packages provides the tf_to_pose_publisher node that publishes a specified tf transform on a `PoseStamped` topic. \ No newline at end of file diff --git a/tools/tf_to_pose_publisher/launch/tf_to_pose_launch.py b/tools/tf_to_pose_publisher/launch/tf_to_pose_launch.py new file mode 100644 index 00000000..78edb412 --- /dev/null +++ b/tools/tf_to_pose_publisher/launch/tf_to_pose_launch.py @@ -0,0 +1,83 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, GroupAction +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node, PushRosNamespace + +ARGUMENTS = [ + DeclareLaunchArgument('namespace', default_value='', + description='Robot namespace (including leading /)'), + + DeclareLaunchArgument('base_frame_id', default_value='base_link', + description='base frame id of the robot'), + + DeclareLaunchArgument('ground_truth_frame_id', default_value='turtlebot4_base_link_gt', + description='ground truth frame id of the robot'), + +] + + +def generate_launch_description(): + namespace = LaunchConfiguration("namespace") + base_frame_id = LaunchConfiguration("base_frame_id") + ground_truth_frame_id = LaunchConfiguration("ground_truth_frame_id") + + base_link_pose_pub = GroupAction( + [ + PushRosNamespace( + namespace=namespace + ), + Node( + name='tf_to_pose_map_baselink', + package='tf_to_pose_publisher', + executable='tf_to_pose_publisher', + output='screen', + remappings=[('/tf', 'tf'), + ('/tf_static', 'tf_static'), + ('tf_as_pose', 'robot_pose_loc')], + parameters=[{ + 'child_frame_id': base_frame_id, + }] + ), + ] + ) + + base_link_ground_truth_pose_pub = GroupAction( + [ + PushRosNamespace( + namespace=namespace + ), + Node( + name='tf_to_pose_map_baselink_gt', + package='tf_to_pose_publisher', + executable='tf_to_pose_publisher', + output='screen', + remappings=[('/tf', 'tf'), + ('/tf_static', 'tf_static'), + ('tf_as_pose', 'robot_pose_gt')], + parameters=[{ + 'child_frame_id': ground_truth_frame_id, + }] + ), + ] + ) + + ld = LaunchDescription(ARGUMENTS) + ld.add_action(base_link_pose_pub) + ld.add_action(base_link_ground_truth_pose_pub) + return ld diff --git a/tools/tf_to_pose_publisher/package.xml b/tools/tf_to_pose_publisher/package.xml new file mode 100644 index 00000000..70c7f9bb --- /dev/null +++ b/tools/tf_to_pose_publisher/package.xml @@ -0,0 +1,18 @@ + + + + tf_to_pose_publisher + 1.0.0 + Publish a tf transform to a pose topic + Intel Labs + Intel Labs + Apache-2.0 + + rclpy + geometry_msgs + tf2_ros + + + ament_python + + diff --git a/tools/tf_to_pose_publisher/resource/tf_to_pose_publisher b/tools/tf_to_pose_publisher/resource/tf_to_pose_publisher new file mode 100644 index 00000000..e69de29b diff --git a/tools/tf_to_pose_publisher/setup.cfg b/tools/tf_to_pose_publisher/setup.cfg new file mode 100644 index 00000000..c8ead78a --- /dev/null +++ b/tools/tf_to_pose_publisher/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/tf_to_pose_publisher +[install] +install_scripts=$base/lib/tf_to_pose_publisher diff --git a/tools/tf_to_pose_publisher/setup.py b/tools/tf_to_pose_publisher/setup.py new file mode 100644 index 00000000..7926e26f --- /dev/null +++ b/tools/tf_to_pose_publisher/setup.py @@ -0,0 +1,45 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + +from glob import glob +import os +from setuptools import find_packages, setup + +PACKAGE_NAME = 'tf_to_pose_publisher' + +setup( + name=PACKAGE_NAME, + version='1.0.0', + packages=find_packages(exclude=['test']), + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + PACKAGE_NAME]), + ('share/' + PACKAGE_NAME, ['package.xml']), + (os.path.join('share', PACKAGE_NAME, 'launch'), glob('launch/*launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Intel Labs', + maintainer_email='scenario-execution@intel.com', + description='Publish a tf transform to a pose topic', + license='Apache License 2.0', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'tf_to_pose_publisher = tf_to_pose_publisher.tf_to_pose_publisher:main', + ], + }, +) diff --git a/tools/tf_to_pose_publisher/tf_to_pose_publisher/__init__.py b/tools/tf_to_pose_publisher/tf_to_pose_publisher/__init__.py new file mode 100644 index 00000000..3ba13780 --- /dev/null +++ b/tools/tf_to_pose_publisher/tf_to_pose_publisher/__init__.py @@ -0,0 +1,15 @@ +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/tools/tf_to_pose_publisher/tf_to_pose_publisher/tf_to_pose_publisher.py b/tools/tf_to_pose_publisher/tf_to_pose_publisher/tf_to_pose_publisher.py new file mode 100644 index 00000000..2e17fc3b --- /dev/null +++ b/tools/tf_to_pose_publisher/tf_to_pose_publisher/tf_to_pose_publisher.py @@ -0,0 +1,131 @@ +#!/usr/bin/env python3 +# Copyright (C) 2024 Intel Corporation +# +# 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. +# +# SPDX-License-Identifier: Apache-2.0 + + +import rclpy +from rclpy.node import Node +from rclpy.callback_groups import MutuallyExclusiveCallbackGroup +from rcl_interfaces.msg import ParameterDescriptor + +from tf2_ros import TransformException # pylint: disable= no-name-in-module +from tf2_ros.buffer import Buffer +from tf2_ros.transform_listener import TransformListener + +from geometry_msgs.msg import PoseStamped +from geometry_msgs.msg import TransformStamped + + +class TfToPose(Node): + + def __init__(self): + super().__init__('tf_to_pose') + + self.parent_frame_id = None + self.child_frame_id = None + self.mode = None + self.last_transform = TransformStamped() + + self.params() + + timer_cb_group = MutuallyExclusiveCallbackGroup() + + self.tf_buffer = Buffer() + self.tf_listener = TransformListener(self.tf_buffer, self) + + timer_period = 0.1 + self._timer = self.create_timer(timer_period, self.timer_callback, callback_group=timer_cb_group) + + self.pose_pub = self.create_publisher(PoseStamped, 'tf_as_pose', 10) + + def params(self): + """handle ROS parameters and store them as class variables + :returns: - + + """ + self.declare_parameter('parent_frame_id', 'map', descriptor=ParameterDescriptor(dynamic_typing=True)) + self.parent_frame_id = self.get_parameter_or('parent_frame_id').get_parameter_value().string_value + + self.declare_parameter('child_frame_id', 'base_link', descriptor=ParameterDescriptor(dynamic_typing=True)) + self.child_frame_id = self.get_parameter_or('child_frame_id').get_parameter_value().string_value + + self.declare_parameter('mode', 'continuous', descriptor=ParameterDescriptor( + dynamic_typing=True)) # choose between continuous and onchange + self.mode = self.get_parameter_or('mode').get_parameter_value().string_value + + def timer_callback(self): + """timer callback funtion + :returns: - + + """ + try: + t = self.tf_buffer.lookup_transform( + self.parent_frame_id, + self.child_frame_id, + rclpy.time.Time() + ) + except TransformException as ex: + self.get_logger().debug( + f'Could not transform {self.parent_frame_id} to {self.child_frame_id}: {ex}') + return + + pose = PoseStamped() + pose.header = t.header + pose.header.frame_id = self.parent_frame_id + + pose.pose.position.x = t.transform.translation.x + pose.pose.position.y = t.transform.translation.y + pose.pose.orientation.x = t.transform.rotation.x + pose.pose.orientation.y = t.transform.rotation.y + pose.pose.orientation.z = t.transform.rotation.z + pose.pose.orientation.w = t.transform.rotation.w + + if self.mode == 'continuous': + # continuously publish the transform we looked up + self.pose_pub.publish(pose) + + elif self.mode == 'onchange': + self.get_logger().debug('tf to pose node is in mode onchanged') + changed = False + if t.transform != self.last_transform.transform: + changed = True + + if changed: + self.get_logger().debug('transform has changed, so we publish') + self.last_transform = t + # only publish transform if it changed + self.pose_pub.publish(pose) + else: + raise ValueError(f"Wrong value for mode: {self.mode}! Possible options are 'continuous' or 'onchange'") + + +def main(args=None): + rclpy.init(args=args) + tf_to_pose_node = TfToPose() + + executor = rclpy.executors.MultiThreadedExecutor() + executor.add_node(tf_to_pose_node) + + try: + executor.spin() + except KeyboardInterrupt: + tf_to_pose_node.get_logger().info("User requested shut down.") + finally: + rclpy.shutdown() + + +if __name__ == '__main__': + main()
-YO$&7oY4Xq)-^^T)v3)XJ2UU8Z=yB8kYBfP0bz^y*C35AjKaQhX zyOSw>!24!g_n%>te#0q`hdkbhW`lnIUP%{TN~isHjg*1onpkLiEqicG`EFj075lX4 z>xGutTQJt5thxX+%=NM$&${SC7u!?InrgSm<_=pZM^y13jhwnv=kihHnR)bwCb@yq z^Tn}wMefwru3080m-%9&I!CMW*0&Tr5{8J6SW||UhK2SM&-C<64i=_ua!otw4F-HU zY33l<8{n41(pG7VQ!><9te9ve+dgKp5Lx%w#G9QQ#Z*pA8|rpe?jQJk&&6)aU9X;X zx+(uZ3QdM|#M2+QhKVMi2Q6SKO=`uC)$-Rsaqb5_X^=RbQR0w<`;B-*88XfWn0brV zazHA2shy8Vh3X%J%UVtO0;zI%4X{JPZpm_ELbtRJ%Z^`e?SG_71py>neO%~DMv@!F zx;8`Hhela8wX4A;o~zT)#X8H=;Kxp+1iK1m-m!V0mD&G;5%ajwh+EXTcIag z89ptBSZ`}ND0<{RH}3qCJ>gg{E;jvH>*$+=p5N39AYr7)6B%~3FY`WD5F_szaDMir zeEgKE-cMZ6>GUZ#GhMgJpmbc=V!r-5;p&#Ui25B>4iOh)OI}#3m(JU#Yr9f}*z~g& zonf!5qfwv`Ne~xW0IguI^WaZ)2$-qclRA}RqU+|ZDLU19Mtw7fK}U_<5{HvKHT zo(hI)13l;oWXj{|ykrJGUkRnMp<}Gh(Cc8wYY*Gv$HD zeIdbsxf|S5`@?t*?$?VpdsFECS%N&8%!ZK>?x(WyqACFcWfgxo^eFk(SQ?2ej( zWX!&Mb%s$Y@wBDmWZ!)~Bv=vT2^ptyn=)I&Gx8A?N$M*6J@1x}@WzuJ(Jt>y>G61c zY=O!bXAq+fd<+tGk3PjJ5llp->*U=y`wIA)U4pj0jth6hNJh3!re$Te8omlz*IpM* z9DF?9(l9#zXrf>dq+AMlnvzxx-ka3%_aumMCTaAPR9yoqU=TJKYHA6!g2|DOqryqq zasBw6VyUSNY*^TgNRGvDt;W@Ad@xjr%CTPRSMs=%{bdHtVvYG08%VdRr@$mJ%}k{5 zb0+C{nofM=;Z9AGyLFh-y1djA7P&GiG7}2v+!^2gQLe?txbzTf^+aC$V=_EM>`o!k zdL9?RpX{s`uLH71sxz($;T~PEa_$*Bz33R9DXMDEdgG_f3uWNR-+G{goXXAx38lR2 zv_`W$M?>KY1B1sxe6WH#ocOJM*_m+N zd5Pvkv*7?i*jCf3=l1W^2ux+i1UoWr{x&E$NHJldjo3(P;gX@56_R;^RTA${lmA*s zmNuDFNZtKz66uIf!%cORxjO_QeHLn$v#~FOoZY~0rJ9)ELK5IZmRoHsY`VWk*ejwfvVfF>As!0osO-! z--DkKKfo4yB9?6zy~KH#V9{G`e{M86GY6=9&K~J_i;-`7C}DGFA9R=qi&c9L?NM2~ zhM=@xFIK&ay%sBN-g{N$FB8GA@BfAhOAkxs8AVv`qG`-|WeVp^ z47ya-yj$D67xWt-?b_tyZ9lghJrQV~3c*98t4oFO}PNDtJ8xv zSjEnwg%Q7C=M>@T3(JE@9!)b8X!LpiNN2C!!g$maFXLb|gZc_TTa?!E8R1S=6*g9K zpLWQS+st5o8Bbu`qf%*NPs^1CPPIp=clj+ z=Nhv;MGwY;IFn@OI?IARK5+E-sEx{(Ny=e3kPL_DrUHSiN8v{>!<|F2;aPL|_HvyH z?h*?U`C>K7D6RQT(0Zg=IH<0rDAo6T1?W(!I3rVk$P$BrHh-UqjsXtO;X+EMIuec@ zGfmS#!y19ge**M`zN`{E=~*=tYkpB|;bdF5QPW>>z3d4boZM1!wUz}{r1rg}b^Qvs zcLKcGhgoy^wuk6$2rVZ#uIN(Xz^hfr=bp%-;N zRuV8pREe#KsYbM$I9F#zzPQ`?SahVJ{9Z8kMdoEv-Z-l>(*YFkd!O_}<0WB>V@(p@ zD5=LJ_k>VP6S+rb_{q|N22$D&eceMNr}7oQ*5iQ%*i!KH{eMF^vN;gfAx}#IVSWVf z>9{OC5Tdg(5D{)$)P8c?(Sf&N7x%(6J=&c7K`97Uh7|VKAwMq4E_k2J&Q_Jv*Xgim+9XY`m4U7>MgFr;bnrv+R&68i7S{Ms z<~U=sZbgq^5>&D?AD$VR@X$dOE)tCV%6|*x7%~4BvZF>vo!5)n_}Su{PZKT@9=jyr z-{|=*#B3&|i0;hZlOOc`{E=w&<|yDx`97PqqqzK(?sQ!ae0cSlPSMhPsEZdI^qSLJ z8!wH5BLgUO0?NPiafyl$r%f7z%4aGP;HcSdyWZmfOl?8+^R7Sb_NIQe5~mjmeV+Dn z;WFHRAqjXHC;2p2Iac2nrXDet2WN)NHaETH)3W5#Eye<++CQ30-4zperMS1XEM-1u zt#q%MpO}g`9?HN#Cyy(~%F1oY4P--IFs2%RVNQb|7@+eqzHfuwmROtb5<@V;A5v!L-pc3{9)7{;8nB zhWptkEQK+(PM$>rSMvJm^qbdeU=Srqc|rc`2cQ53Kma-pPW}5$O!ZPBkb}MxbFFOW zKjYN${WMv|MqB?&mXPtWD0+0gF$Y6^m(8c8JjhgabJmAnvi2dkDaJ+T8OpSI1U|Tw zD1yTIUbdeuXwG`ecA2|)uq`JE8k_RC_2JpI;3_A+3vOk3Zx%tih9a5dOwq4B>!*jY7gFLtK5j{3!8+FVb{rqn_qI ziL(AvW?$s$)KZ4mh^_Ktk_)q~CKibVeA{?eKlw@ZFwAc4oVrg(rsG~JQ|%4GwQvt0 zl05zXb%8RolX!qJs@~W+P{jIUUB5hOUTAv&?PY7=fwC!26vU->a$Cj7_X|PfbpN+Z zErF9q`LR&*_t#6nPXeK8)&E=FW(>4-utlM)inpmx{`@mO;?X=}B5A{sU`C8EUAT~) zY9c!{;(T>R8zN}L93w$G2g7CVqRq>UIz_ftMO?Db{dN$Tp>THMPlS!fW-(oPD^e57!O7|+L3@$XQ zt!pnm&=e9U^$jMY3T<;8C0u+`){c1_i^PR-Pxze&vNqs|c>XYbG$_(b*{zgYF-1wtbosky0Jv1f{vLC}bjE!ZTpBB{Ll2dTKqTcq&-Ash%LEHvT!Rgi#DEFo~`=-#^OU#{f#KkQ>7g$7nga&XQiG z%GK^QXL6CGv#wMQeowhxm8xfid-EEV+xQQ4cepucJcAm6Lz&xwQTV!#bI|d| zcNC7XQKVf(;j-$EjiiuZShrZw-GS*zp@|)d4eU3)+V1nl6&q772F|k!y&HZqvSQ)p z{BWc4TnT_ZE|4OC`wE(ePWvzR3-_7QCPn|q^GnqZC9y`oS9ZmepSI5M!Q2HXB~P<= zRx3OHDqSjE(4o+=UK2m+dt$%WBz}^1ZCpr{;pIVP#X?Kn4ucGj`XJ|Oy!IpzgO+C*O zM%~PV9YJB6n!Qv4PWPSAs>@1iz=VC6=YVxmm3++oI-n2$B}=dh6A8tCk&LEf)OGNs z+XrqXpiRhrUdm+tBU5Qr^-)aSjJzL^9Iv$mED&-(jh+x((#MJcEF_*fK-Qg_@=f;M zl&=3_YYC!E9FJ?!uxoTir_Q>z`z^`;zA3E21T^se=PhU=|4e+4Gf}(w!455_Atk6i ztff>_p4r+?X)Ji{`@~7}hJApB2a)+1Yxw$j?WRtFM2!4Iz>94lNCwq0oVNw^i{iqT z?$Ldq>?TRmz`9>hRAFM?=D~BFWUyzD}ta&=ypv z)J{SdjSi0RPzF<#Pz{n1bm(kESHwI8+dzu3N1MEiF!QU#Fi@j@oQG{@GH@-!%Dkk3 zT6is~zv`y5ff)C`sNc8JkMTccW`f?Bp6wyId_Z+IRhZa1eL*bfk zvO+JhBAq#I*yrC%2xUlIdtg9&1yPA1fMyX0=UbE!r&4PP<7i*LUN{%iZ2pn|4;QSIbLCvX&U|r>(C)-e2a$GZcXOw#3Rx>*Zm{mmVh$IR{y;& zwg1uP(WMFCTtC<7+W4({Q9CY6Nyr8K%IVimx7tB>aH;1p=-U_X&NjQZ(mw_fO97Q_ zZ5q34Qn+WR0Y1Yj$wWRx;&b$O{Cq~3wfVxC)>M>FMP6GTl1k6j_~>DXw5kSH3#)>i zrKTmc&gx+TOwC(;o%9B7#=3wgg6uv_Yv_x|e+5ruDd6Bd8I>kDf__$x<8PKcaoUa% zn;Uk&J*$Y_2f?-E(gXQXA*3#(Z*z_L&7_til^bvT5*7%nD5;l}CJq2lO096g`QVyq ztJPo*;0)E>OrrOVxa@DTH*%kw6FU?*GF@L{>Ol@zR<_{-pC}Kum(GCB1z{Hh=|F_S zmb^^42>s|MvkXsL}9|7qfYVb<65ZlN5fAlAW5SW6VZIXT0F(|ujDfzHw z`m^kB=cnchL6VEJIgbhXqsw^J1=UAGJ;9M)zls)0iWV;nFK2h`qwU-WJ!%jMypcs@ z5Rpc=`PiH5acYomF}NXG2+7d4qt72vwMo?-mZa~S1%W#oVi@{ zjMd+9Q)0X7}$LeksyvC2jwfgJnxl#&H)SDZ9uFUJj7 zA_>)iE0e(Q9@DCKt>DEwlWVh{`nV!A3u7^0%QBYywLhrNoGK+4Q={hY*o<7DL{HvI z0!qO03G_#Qj~DbNJ8tG{cIH(PhON8S_-FNP69Ywb5mA3V@csU)37?Lah3}iLG118K z<@l$D8t+A;0M%9ZsF^LYUrA<{hriRDRoXl%qQCa;VCCLyvv7~x_ks%3X6uN-Fi$qr z>x|Aihk=DB_-6rZgAJoXXO{B*iRU6hy3W9yi`rp3`{!O%)seE-xs38eSEGw5u6jg5 zlBtewQ>=-fZXDiesTuk@@Q#bekJeov#=1WtnIB*biZ-t|^3kKm{|qm#GBgCj@??d< zD>^r~nDGgjd_BAdKd&683O_vxNe#DKa0irbz_A>vD>A)lN(drEWbwACXfRa8ag8h7 zT7nqugmvX=Ujn8bK;!2-_{|TOf_uM~1!W41wT-%c3HP%DDERJ-53CK!ey7`6`(~xT zkqR&8{>mrX%J*s1z}S}ZKJZ1PV#|B#JD+Z*raqm-+)6_ApIeV(S;qw3x4I=S-`|e? zf+E>0EA&HVTe;-}w|~FnZARxXzdG%%d6di#$a6^FL}LoR>mN*w*) z)e7K&>;sOAEdIO#^3rDzT)AqUbNww)<+NmV!R~igs$hLyDS_byR7-!xe*o}VY{tAv z(Lf0@@ya7N5mA!aFb0~WD2?K-rgSjJ+!amx`pN`eOjFF4u2i6z%opoo7~+QFlB_)f zNA;7H%fk;U%vSvG0>RZ4dgiFQIm)wm%c(-y!rBL{JyC@oH~teFQ)G+qmuIKP-xKip zGK5N2P{vs$scv-Wx7-nLI)Ryn7dAccP}CG^C0#vP7aO?g7jf5lm~UK;@4eSlAXefg zYuD#_b4u@Hu)fT*zB8t{v*0FZml)$e#JvGA07RXt@APE;eD(5hx7{i8-SAqzQc`?8 z{o}1wP8kow5084;Tl-RK5w*)7TYBXN_SZIiJn~@{jR zza*0y0fKX{Wuu*sNBcaB#Z(@(`#+zp*5Oub=K3GjfiU?Yz~;b}NRpai+3ID2G9H7n zrP!5a^u;z0BvlXZHE|N8%)a*jdr!GF3X+528c|n#BZb!j1-A(kpOW$Rom`o-bh+C+ zgW2gOg!LPDZ+xk^1{@|25NmrZuoGG zSLBgZBJ0CBayhx&2-x1l{Ah1&K3 z`8PUKdZMg?Ay((vdf|s@?D+#V%r{SVAUx07ceQYC=iVO>&@A5Qc`zmU&EyaWF^MP7 zX7j#71KKn5z?A~A$L8CuXsv^l+Pf1%9*-=MEu`yYy!`t*9eC5lq{A#FZ*!tw{EOfD zq+vrRXM`r;aMtsOubfi8?K3*FgnTgl^Yfe94ig`*t)LyEL~JV z-u(&h&WGhfNtC!j(TqG?Otcoh44bc0Gi?iK0Dl*I6n$jQ3zHethYBDyIs5mn5CtxE z#>HT-(Xn3jU)b?BJVa z^DtBf&#u8{t!!Zx%7ry>32AW__6d4V_KdQM0<}YFsYLQ#a^OGe~_f{<6UOG8;x* zwxiYDzieOaW!0+p`YUT)KS5Q|`r;Ao(L9T()9PvTDB)+Jf~*#o};Z>(bxYl1%gSZ~OL^xBPz{Eq^LwL7-}2-ViC&r?xf= z_%>t7I|4mvuY6fLvaHo!hjhb`ul2ZhI45!S>4eZ(`_KHza#&aIRmS=-`+BmX`R7y0 zROty?E3b>PVHg-E1CMlNjA@0Oe>-hYEZ;cqW&N9+zQx{D4Yd*@WfgKMu6-S`t8Q+x zi3a_fS(V7vV8w0EIhU*o6NRe^Am{qeC010iCf)>kP11Tng-adixK{`+e{I{mvK;&WI_e?6db;bIm!|{;=g7vLahq(lX|qkTh)F zjA$fYd_h#1{HwL6fjDg;@~2eFoba)3jgMs7ugnUZun&HyiTgBJloFK*lq0QPpu&54 zbgCl$l_v$NE|GjqQ`K+p(Gr3$1<}HMD-P*zu@I=lzqEk$h!d zvC->!sMhLyqn$%Y%tBK^K8E2VG~z(?2)f%M5Pdg9zxt3DgH92DtIKi@h13v|mMxCu*l|JK1wK(MbC6P-?O zWR%H|^!ljtC89a?)zD-#hdK4&%b6v3dsE&~OLQT{tx~g3+zt7B#>>K$majCWc*Wou zsy{g8H@+ZrEs0E_(atRrR(w@2x2xS9zaM|G7UtfJ2G9NJaoBpz#iU$WXEWl}o72tF z%k_eC@Dr{WF#o=m>TcN~y`i5LHt|OTMp+|#jzK5WnMpM951Pnp=u-hN#QLXD|W zz6uiSG5_eWcxzufppW=Jog+Yb@B{YO=F^l6v4dFrmSh<4mS4uW`Rjc$f&}OI=V`ZR zrrn>~Mo$?otIu3J1DQ30`7a>x&u71TBV>B?hr1NXJIDfIM^6kdi5hl&Uv3T3H;``# z2r_llTsya*R%rxupWD^V(QT1cn5X56khP4|zWDR@T$4r`;ER&;ekIv|zB2TTuAwEG zsT5ShJ1imJa$2&rb6Ckx3l9vn9Uo+#((OtJsu;3WW*~Q;z7{EGg}>v1+pK?*usRx% zEHe8<3%-TylJ9@=Wdee&IAnVrAO~nt2HUVzE(rZa88KeM`VCEpCfgu3?-yF_9*z3A z{xE6H(T7%3%!~XetkH{=AUYs`5JUnb|Mg818XrCc@=rW^rzF?_0Oc z@Tt@oOhxIdqC`UvdW?Kzpz7czbRx%e4G5(%lkG7WX7VNQoCN>-M3pqDD~tTzA-=$N zTcTECaTT=TfBSzO;)hS1SXFV;*WGZhddE_7p{BKd|NN^1S&W7GzIH2T%xA5*QA+H4 z&-S*948LmyfA9`)=1_KsX%4M9Sz4h@v-#LiZ5pj6o*UMZ1?HURxx-JoaRLI)lJu}5 zy6TbWaoHQxe)sKWQ6+HnQ*MR!H2Y+&`DPU9_EK0eSdHA;G^FwV%w6|l6^{V<2ut8W zfieT- zRVNMEFA~Ksy(Kxjd71O=fyo6!D=)zYosRP$e0=@yJJXcRFqVA9N=D977Vh7zn3A{4 zOl3cN*^o}hSibW0=7!dXM?pD1iOuS4Drv)u58bJFJW6UpAS=s`ewO;>GvkVIW7W{Y zPNUu6^QjxNOQZFxR1WO1?jgY_Sbe|!q#zhf-;4hcycYDSl3$Gda_9pOX}-|R^-zId zRXs*}`MAmPU~sxhBiEOwN5I~@0=)F~V)A3-I)g4e0cm&75Sgm+?p!1L`2T2KGkVN8 z0U6_;n*(&Ddbt!W^-7OHp8Cu4_&@(6?xwdwWk2_R9Sjhl5yL8$UC3>(cf$X!=)Xr5 z!9XrzB3jV8rt;{B8aHL_Wd~!pY7{wU@;66Y~8jp>RMu(6rW5bnXAMHBKp#X z_+a>Oc=rnTM;)rcg$FhGqx1Ujqf@OJVrv~Ilw-Lq`=YUt z6Xd39g_sH*P<)rY6_RTNOddd<4qA3JZWk1vHIx~K(*q&wpYs8KQdNzr`t5^m?gw$} z72eMTx{d4f@DOuvU!B+Mr(<{&OT6b--E1BJ=v&u+m(IZFN&-Mt-X{!CRj~j%TrZ%* z^|1g17OVfdq2P^5DgSl7!7FN@B`)~$uZ^4X6&Z_SMFn0Mt7@^l@y*mqZod085J9e%27D>pyM%rxGK&6EPo zGj@RE;FGiQmTA9^A4POWx6broGj2;4U>)9yiqzJ0F1w;NY8BfEDyIXPnm3YUApa9v zzHQ&}_te@A(UTX6%dl<9Qtn-SezF0RD_evAeZTQuhyU%+VR+_k+6EN^bx&~Blx{;> zrgla#i*Mv$ag2rq0$k5r>wzgCMWN<=o@`?)`g+o3eA~=vd_uSu=D5$pSrb#X}b*P*! z`u9h(^L|y}?0^%RE2#M#FeT{}vfj;t*tKV8q|cx`DPtXPjf`bHHtQ5xISg34!I~O4 za9bnV}VikZrEYJePhe_Yh z4k?@_YuET=f}2+HzBIi0iS#{hDRSXorbpkef`JQAr(ZBk=re#k;4R?5cH4ciocV^Y6|#tL zu~oX;$OI9?dzX2_TDA8|Xi&9RysA_W_I(t+t*=9N^fb*;J!$Z!mAGiIoRTpzmA3yOtW#G)m4{&_D!^4jmG@~?KR_pz~b!E@qa`Lb!lnKu*xGshd{ zS~XrD|B-Hj&vdB&c_Lc9KY=!6kjek|q@;YRBn3-X0MKT_f{;tsq%6n>ks$Z;8htIlRTV8)(n{cs)X+481(hl|rX%740 zU{oBCoWsi2HOutQ>=*I_M2pgfYUiRwj}rRqQ>sjBoMEL{#L+~#5qA0MT=#|EX_KhH zq~?P3)KNg?e-JkqXp}JY%skm`?c{)iJ z*;_+`60syFz?-Xqj7e#&vT&lF7Jn?7D0HygH?QAwIn^R?$vo;iydNK&l3 zl%Th*EmTjr?%I4)I>Y|K^LcWo_LIC?>|rrWArI|bkfP|jgy!BG)81~LCu5Pzu2+xp zA_fxM26WM0In%wdg;UhLeD0WWVRMw47RZtQfr<}^5CkRWbG8R(X9E#WYp#IBN$Y-{ z`Pvy5h6>+#3`7gyQF9GQ*7a&{OOAJ_N>^>-YE=|Fw6I^l((iSEpdfqs1^XUG>TA>v z74JJczIB^0XS?&Pxc4JJw#%in;OR4ixXzy12bTMc?9eP!^=k11sU&&(%Nw=*PUO1o zrX4t^XKt}+bj-W__@`Enl#^<@uUOZ0qQw~Vw!Ei0`J4z5W%)ukFEnb|7OLq04|#1I zqPJUN-l5=nY2hw=kXxTh9kgFo|B`sW8tP9C#bt zSbe?VizTw7|At4QK!{6>Ev6!@LA#UGtPj-wXTN6rJX&5ZE%~u6x2+rs%S+u6{U34 zbhtzPuyeZVGO=a2qkr>O0Tg|uLV5VWS(3vshcUzNwc{fyC}yIjl3v zM0D1%eA9rDQy7s$ugFPpNmhWUeOh%I?RO@;;&$cjlbtWhD6yAOx{YR<;{hc|XqKSv z4hCXU`*U?cfuS$WbJ=s;2#9v7%PSRJLSCvUbGj%8%||19uf?3d@V^wY6m(P8Gz z*m!0-{^G4a2N{FRNT%{@0(iqFkw+LIk#CBa|0|VpwPE{pIF{=R3-#Ua*3yhQB|3bHO<{6sP|IQaj~7HQHyc?Aw+msDM&|!%yFe z*gR^ge|h8bp!r>MA{K+jv>&^rH^XtA^Tjv#pp+i*P|e}GPQs_X@KLn5=DWT*l8yt@ zq~M1?qF)rI?dfW=J%iurN^h}ZU7!vB{KFmCV90qJcO7p(sv)EExsC`3E66~Knq#R1 zcxUZdhaDr>!*wIk+@DubGC=0U2NEz%-gzkoSS>0{FaNB~qb`LBTUyby2b!_fEmxoum{ZS(x2cHb-7VryG} z_i&*_#*?&&jYpYK>CXDHm(N@bUaOtsvD7Kd_uP1OYg}Co^8MAVc7*ioCI8#U#vD+( z3Q~V6Ux`{URV%oH3-0o?(hKzWb7?WTf{PD451Ue4GL4eua^WOvrScl~WVsM2^u+(I zFKX6Pane-UNYOsuysAu~j#8z&JUIXCKwy+9s!8lry}^y^;DUsmCsrq{o{Q|c>&mb+ zCQMG^n?nlJ|GFdRaajW2s`^C6LyZ20n_BigEnriUsgXh_23O04@?sSg-MTodYR!z= zdm@%pz7OAbV{>Si6i4(W1XYxKNHiA-cQ-9ehM3w3(h-PHL6_F0&%I#6IZ0 zQT6FO{o#UJ(Svx__KdmH5>f8&8T=uMMH_)lm)cpS33I69&x#ufR31R&mK+C^7Z}96 z-*s7!_=W&>4?)lMiS<`eDifvwhk$}y-WMdKp?ndI9k9}PVm0HAArzn>HhOvEUWW!G zd)ebKrzEaGua1k(ZQToW4=mC`63E>T%C?lw-_Ew5ouRZuPibLCGrkDSB)yd8Bz&)e z`7E7s-#b(Weg89qvS=K?z3f_i3!A{o!!(b#?|XV(nRfu8&Xz0aDfJE9;DO3zZrXB% zU7a(XeUoP?eMk4GWRLj!AiOf@@AQ{oRrZ@mpK7`jMy0wZCCESt18=%#9!G*O*=~`L zWwxJ=g4=gtb`is_$Fosb3{;4=a977Zogovs4$sx@o+kc%E$2Zecl;hxCPM%+4IjQL z?A*pi%`HQZGo3yl^D@jt+b`y-(w6la^l;6ly&ATlN7r~M7oMox((Fw&BEHeY206;e zZCcD~tJs3SP_co^7BQP;E45L@w-sTmONT3Z_#J~FA22n}+mUG#Lt`Vs4^U;wJTO)f zT8*Mu-Eg0fHe#dwZhc`?FeHwZXBbCF&!5e)C~eCl`qbj)Es9JzplqSY zyA&fo)a#HS?d?*P*E3h4V`(B?00OoLa_Srva_u<-iR1aKN`o5P+?(D!E}jccf7ocHY3Z^Z8e1?UVq5E;dt1a zf;|Sem240)+*qzqp=?)@}#cBHf9n6O4ccJ=4OkWF%-!6VVnHbG*VX?tcvX3htkE*x+D zi&Xmg`jA>LKp+#vRhBj%%O6Bx%z-6P9X(39Td8K9^jxaP1aZq+x@EZY7PhoHU68tMij9mZ=Wv z$Hz6l6o)r{T~Gqq+>TbL2yClmi2Zno1mI$=|C@Ww4fnF1KY4HhW{ia0EQ1IuG6n!C zTxKTw>8yTM0M@W_H;xYkA6dsD92f4w8zB`xiR%^a9qA9CS;@**CdiFjP@UaxXHaom z>R#(*vvSV0kff_06a0z@PzEBqim&#v30|lzC+2?jZ>Uxo70ygE6rCODacYlf7rlqu zPTyR7ZGtV8Tc=_94xjctnx$N*R$|EN?L#=_tnH&UQ*OfFZ-+1F5(0`-IdwXEm)6Zd z*}Pk=w;L>T!d#8!8s~l>{CYUY6T|1L)r#Qfo+^&I&-dArHmAnaDwrn5$=Zl!K8C!#)A6vRN(SKD4xpsbqz-J%_FV#FJ?qng%sm)9n z9^yp01`w|2Zm7KD3F-7d9`0IM`ti9x<9&G`>=)Tqv&V-4Ua+PTFLsw1W~o0DycL3+ zIk>>M@Jxcq{}CCLYBoN$7Gk9H@9PjE(~Knhi8CK@QG^9@QWfRBA`4WBW|DcGQ*t>t zGW@(iBE8qabg(WmR%7hsw9VRS9s&zcwy2VFgh{FeRKhxfbsHs&bQTb zFKD{Hx(u{g=q5t$X3M&_FZG)GUn36}!L1Zz?)|V&u%R7Zlx-t!=Lq@392Fn?<4~-d zgA75oVYI!SYg#jQU6vsTjcswYr_i+&pLj`#@_Ac`A9UO1u-{~Y4|;JpcNp}6h7)&b zyr~J5%a6s(d5pLo!{>xcDY|U5-@6U53Y+azbUfjxA65{7vpI(NVv*umeetIj+BII~ zbwtX4|6vjQBB+27J+Ot0Sk9zyFw@YWhScteVpMA8A?hK-X-b;>*@TJXLlKLaX0FQG z5|K;-cTobS;tJ$>pp)l9F-W6qkOy@(y|)yW43b1T>mwLS<`$e0@~;$E`-P^WSoA2Z zMYp|{9OK(L;C!(16GA&F?^YTxX9MTt*Iz;w8?2*rvE86$V?hrlq#|v5=my`K$ftIW zL5jhuOk`2W^|&9$f~m=lMGq{fPR1N|`It>Gz3YK8j8(z^aQRB!{sQ2A%J`4#8xQ;| zDZd|j9HgpL-n>RU=23ljxcy-9UF45=$-v5E_fS1aR)mbg%x?@hl=gQVkq&P_TmX&R<996I zKx|@=I_BmuJ4_KK*lGT7Gm3rVA2YtCBfCyqLAqu? zGQ3#AQ`prhuKS>7tu~Ifs{UwM2Nr16UqT3ucz~`*X;RQCTC2t&U+;keL(2@m24gs^ z^;)^y?8=COhyJqQw0laP1z0Mtq@-JW?E_kS|0#{r`e~2*&SL+C1lGvJ=h-7;PT!J~ zBy-M6Z&?u(#Lt9&Q@~8uYC=^YpBPJ#UI7+yL=#k9O$8EM{6Sv!*9{d8I!l6xmBLk^x_Rp>T&9x;UFlEVBG3@--p-&gzha< zz8~Hw;mE6={yQA^6$G<@({ITg3&C6u##~v+`z*63^+DWLpY8dA) zL#{h)___axl}b0J&L)#qDs5HAGOCWE3lA7$Z82q@CvTLZr=4ToG>Pg|^j#@iu0zV| z=S;6E&zDLu5D>ViK7A~qHqPt*Yb~wnM~>Blx#UvWKtIi;+$X1U_8(<_r`pCG(X$>& zyci~QP1eHt(Wvs5AFdwOJvB~bA0=PtaW21fBN0Wpp6&Zh9LQtsPYyCYN0OYEvlsGx z?JE(sQF^3N`GG~`uYbubej|`j%HIR&vE9li(7jpCfWmt?OI~DS4GKopJ0&KiKJ-`q zfYDEKjL2-bDcRa4kr^4;maoe*>h(k=5gGCd-^L`hGK^MIE8qgEky(^#PRHA5Zu!cz z2p^5lInCRROD-mFsNa8+WB;k$F=LgHs=yqT>IXy@dWNSqS>U=QlRoapbkL#3$~i@L zKXZizboxrrms@nFHx2GbwF=HSCM@l?bo3?|h3vBIdnNGO2hwKjf#7`f6C0KBwLt0z zu|ji}u#S(r93*9TP&|bn1#SsE@lG?nenP&vEvPO-e#bul(Q0t9n8r`~ATX0Gz9~DI zeN>)X08gvXgJ=lro~S>WU3!YGpZBO(cB~WQ@on7j*xpWWi}xHBUG1&O9@cQQ$lsGW z?vi-Ob+;180)MUW;#I&`8|*QJ-MRiSQxjeV;Cg4)xtBM-^c%ucj2E-$$N388NR-QC zzolywIVSpEnnUbY>d9ITeSS}F87#En0<-ge@9ogW>D0b6lp7MuluI#@F<*8zULjVS zDlT5o%m#U$r$>nqes$W=Q^aS?PxvU>Iix|vj$tm+o5ZewIHW)s&dd6;y7khuXNI0# z&J?nNFsJpDBG2w*N`uLhD{=C`0d(u#La5mEUr{-vasK|^iH!0p^oggUC-2$G8_X(A zg;}KLESu)v*z#qr31zzjn*_FOc&Xd7ntAnR0I%89gva`7l3Y69!tA^r`PZ?e8N`Op zQ|Y)AajsHIj`FUD7yUrRXIiGL-tZrM*AlJW_0^GOp+0w}VZJmV^e^^;ynS1zPkzs=PFkmi%v&)7bRG?z zEF!wm8zcGnuy&JJ{o5eArxRQID(c4ac%N;=uF#psLDToy!Ius+Sv0npdUhE{S4nB( zn!--SqmWO)l@#9i@M?U03S^ac=<9}qC->A##N2&3g-+~XcFVozPFzFRd+XS&YaY&? znL7eKkHs1+ep(&tk#Z*tz+)#6!}LOpEnQ!!8Di!*}}36x=JQ@@!ZzY3C{6X~n? zBfR;p0Zygu^VwrA8KX^9hdb!T^?ZDO#3|gn$(Ki>G19#8{^z77`esi0Pg_w-kXgbB zC02{%NLPIPUNQMX&SVO}&o+|KQzhS^FN78)a+T5|@*(=pj_}-{! zza*9@&{j{coxcK#ZOmmKJV0)-2Cd8Pg+mLleZ-``5~=1no}GU3CvMl`7wEkY8oTs` z1$ZxJtj?D3d-OVvR`@JWNROvb;Ye}GP+Cun({w_{f5?qw9kJ$l!-;O# zif?}`x$Rnw2k34v=+s-Q4QD1@b`yJ*^vE#j+;GBz;0NP-7K5fwY367HD#UnqUFS&7 zT(+t4NKF&pk{G&X#5!yPL4u%1Cpml)TzF^Y#Gn(@o)_Yd~&t0)hlM0~) zkjPUu4SY84G~Y2Vq8*FQys?{j{d7!;x)JxOL+hl5B2M+GV^7l?&&9xk#>HpaOu92> zIO^lBh`6Jx0+xHSSFx_XNm1>hpPL__&1m{xt!`@_McdbG*ucI)U=4-I;eTd zMrHP`cv8Ep6a1gt*<^LM#{1+v+eq_eE=!- zd&!hIZUNEQ2jL9W`m^*HRkd*#d8jV2?Z3Q`i-Feek`i0@9Y?IVoJZ9N`HBXlUD z-CZL^Nl!o-DY?uIxh4;={wRWFVeOaQ2 z#XhT(=J{J}@%U={g5*=lKb$S7&aYZFXrWbA3tTad!?5HFzG_!2K)M=V5nzrg7kaVJ%@8{P~WEONKXZ%``#ioEJ_UsmJu5~e0q+R&~1|$UnZO(dZYA>rQB1| ztd88&_{ViUC$)Qt+ODgD21z%C7B5WDsQfkCvy}&pGOdA&0p5rBZ=S|~5jK7iY^x-c zII-ZtJf*ev2KfZsfx{~L*#XU5n4e{D*Tf8vBK`rkkwcp1w0 z&oJ}8dlE(;{V5eU^0ALUN zyDX1?`(yDxXOnF6A5M%9FIg}w`kz>^@t0@||6T$X7hsY2&yhp^K$PHhnUu~Yt^d4^ zS3LaQWM=&l`SJ-s=^*#}1t{L$@%P5yf9P0wA24&7|5z<5ef@o~;*ar}Ckvq zt?ueU<2fO9mp*qnQHKKz$Yi@OhLcL@ zqa5i(Bd1X(X_Kqr{?^{dW#q%|5P#&5hVu&c0&a$G+=0zEs%pBp*}HeY*eL>>Lez;)-50L>L} z=`M}`Rjqfa>vDCy>5WTJRl>u$odvjnFCsE3d%0b#Zlf#9vok;Iw56NqM0}JpCk#xq%8VOPEYk7ILFDh?OVs2*+fsVv-`{&{Gl-iR#nwFeLszMiv6X!R9Y@|&Jp({A0)orM+nropLpQBq zbDv?LJJ$t*zx*5Edpw0A2GZFwwM8_Rn!k^JOF!dsM^3~dM+ji=H_Zhd+^$$3^81*h zGgxrd_N9)%LxDrPnkE&aDp+DMF=K&H_qB1?%3Q@Nr}v=pFBB{_iA z=HNPkI2n@FS-y=lep600QNVm8->EfQvz9;apJA~D8dUuudiiw)9fWXGPMfY3R!qv; zAsM1_&XG{tce>O(=lE!uWnkg{UB2krdd(iypqFBeQctG$&x*mFY~SRjPXs>fup*mN z%Jh=`|7h*ZVUnErdJV1dHl`*f9>0kPQ}aQ7zj$3dWl=mefR9;ojV-%&Cx%MRNe?Q|0Lu9+f_1Y&Zl|F% zB<5gQx@XiK!$MzYitxrpr0%4m1Z$_1KWTTHCElw$3X3`1d}-n>Wof3vH-U-=xtxjE zNg)hWv+?u@r&i?y^gdwbJjkNy@7CJ;IYA0&ZS*mKr6srrR3%Dj=UKgC2hZIpv}xt5 z$TL8EL0>b85A+Sg=NUJXytc;xTWiu2%7JkQEEWp?`^_$BW|uXj65qPNcbv0v?J`Z} zqBhC|rI1AqGZxtcOYQw6E`2ozD~B~90gSf8yGdD1w99xGi}B%_^NR^>P2L$0>Qcwy zJmWoOokZNqK7!ieLsYEytNwR;W+LchKMsbwohCa z$=~Y*>=<(Q!WBneu>g$sn=$9Y6U_MhvHhAiS7w~ynY;NnzP&gRXVdkd6SbSAAb%t8 zuJYB1O1OFSp^E%iexP37Wv+dcZ&$sa+f?kjg?&*ey>gH8(-3BP)5U#20ZORIN;QA+ z0Xf|Dxlnk8CT{6K+Uem4jc4CxPl>dp%1#wOZt&(6RPb3{as0CDeg-577MZ~$MM>YWI6qF$2lD|D}4Og_=`T`kRP8U)DLnkHC_zoA_qbQtg(>0bAfhDg8%1DM380K9P|4e`(pCzfPQ8h; z?A=j@l`#ACqhs`w-oaW|w7^3}3CPD~8gm3+!|B0@QiOC zYzTsR>hy8>?B2DWP1ASp_2%fZfoeyCg`532E{; z?Lz{yy!?}^2$*)%vf~QLrU-6)|IHpND+TMHiEh49_U~{V+OvZi!;ni(p^W9PFhi}J znn~=Xzd$bX;3iT!xD6YLa|k_xj9oc{1J0#F&OJqDv+0XS-FWAFmnq|G1m*e7hG159 zSBJAc@0sUOH&|X}dTyM5IIfRLt1Q%xWHh`aNdB!OkQKG;D1`$OP`78ae$uZg2w&76 z;K^hQ-uV2tG|dLm-HWYO#D!mh-y@?{EZMuodI?CE0)Wg8zll%h zkmYMA(pq#4e#S_4l}`oTv`f_c-e;*uZNEchsEu8`gw}4U53uZXk2lfm9o;f@YHXYF zRpSt2o}z%U?A}ib#Na**essO#bXK_DYm!h=3|UR^dbOpV;Wpj;dD6^z8dug}8A~;Y z(=^<*nlF&M_XS(ox_g2Q^&}zPsbaFMJH%-lPRE;emASUEAKkOPm3m;R+Z)YEL}jnJ zI&Wz^Y*pTz(fYXR(63D?_5ef-hKSRz(IJLt<3+TSk^Iofb);P=?YI5C=D4gMJ86OM zs=b1(vGu_P1_a-40y`4g-*#w=M1}c@zJKS8I~WgSDu4N#HmgDT|1Hd@gKVk5gt; zU*t)nnD@>-7Ryz*;;6aVb-)5CgEC~`xVN|dmSUtTS5;$T>v#18grcVtGOXem3?WyS z1RvVP4ajGh&rk_FC6uN_&6t|Oo&9VjPESU-|KX_hlrXzkm31E#(ChFjrdCzI+Nc8T zyHWl7FC6mq#`E=y4^*DZrto65sRq!&Z$Q_a-SYJv>La;otmEUO!Ly!DLv;5wwa7A& zjD{WL(!O=W7UEY1PaV}jn{~0U-2uD&;nLpyqzTVqM=A=@L2ecrGzt499gd?y=_@sv zEoX@+ZV``89;rr|GxzZsw_)OTS2Wj{SKt{nnI1{=3v8Sk7G1QbxS{>bN%+)Ul1x$+ zW+Vo`usz+D5i|FrN`a4L91-5jcUHdgbl44kd?ax+d>jfoHhY;hkK28Bz_Ed7gaHe< z#NwhUJ7!)fcqg0G9WyJnz(70NIA(OM)AqWDZR~m?hABfY#buiQG-)x7V$;zL`f|-1dgsHN#iovv5L556wl<` zU@_=HlzPyAh;XJJgz{4gsf!4p$PgAZ6GXE&@k{h0>6y2a5 zz1wX)P{T#;|Fn!Al6Y}XqZ6`;QEym7E56PxLa9Y7Hj2^4LB;3AqJ-43U&_w#RlZh( z<8uvwmRp=Q2|L=yg@FdRwZLEQ!T!KRAfWxh1VI1!(Cr@S_m(2~+%+{cqNkXS-su^T zYMmXs3^yJnzB_4YH32-_weQgY$A;$Zhj^Dwm4;wv;|1zQNE$p$uq=X>Z0x`;(kMqZ z8r@R4^BMb!(TlLJmLLl82-|jF=$^n!@-s@=Q*&kBHagn93=;~H+kpj+{w7i=%$k3D zp-#W3P{hIQH}k$tz^2vc46p-dtra=;#9S+BTl9I>T*z*y?hmCA#55clW`bF9hUsCO z1e(Shc+FBC>k`B0wdtG=5~R>~kbrtOuKd&eJb4srXLsfw<0x@N4jK6ZS)jSclNUSp z;Um?Bh1^-R78>Ejz+3FrNN4n;7e_mC-$KJRXccF(4GW)LmC6W1LbU7Q;i}Kq-sMiR zS}>)Ux$!&!82!wGDuR5W3`_aZq1iM>C87##C98MtzNWHO7H0A<-Fu0()6uG>+oA+M z;UL?02LC`8vMBe{KxxQOyt`zrtV(D@U|175Q$AFqc1!(5#+U3=^>8_7-BXB6W1ynR zo>;qwr60#K>$d~6bVq9HWLk3~AIzdAO%HSghjX~ZpPIS0FOHqL#k>iUy*(Ic*BGef zrHrgR$f2I}`K0l1?#En>?m!Ndmn;uT)v9mQeYOwS3G5JB{OX4m*yw@&dVXnpz64YYrWA$CwDj z`Q?{aD`Y}^fk>qU@Ac}B-+3QsSEbD2Yj@+SfGb(Fs?5^TNzj<{UWvJsR#%T4mn6rB&ooC7uPe`X44qr0_5l8obkX05n2 zo`^9y^{BBFXLyVIs`*&<%R1+wbHd`J(FWgIK*za&>i79d zJTXZ>Yy*2%{o7hj+ssG|&8(IS+|N`EPfx0$m?mX@BLWZd#E6V7+8M4bHsvHa`pOVWeuYM!tf;G8#(_Sau-q+Eao-}cJ1+ORx zd#c2#_qCP2BXEFI-QKn-BLSmwymL~R)1eh|UGD6&f%n6H@4AZ<7OY=}0l>!cNQNnb zHJqZAerT(bqkCH4?8?qepMGt?DrWyv`hzx(3^whu? zOOM?=#nCwSJhAn4ZhY9K32n{6#S<=Xw*(JTME&TlxgGmI2A=*q6&MCUxqL%t=f(;`R^C6mPk%sT`@hD|x$ zT6?0J9H*ak3R!i>HCcH%i&}!NGX~SRV*}XcOjexOU0@*Kejl)*m5#DleWWWsHoWcm z+%vH>dVm{r6>+pF>u?4h&rR-)t8H;{KaRu;xo2td`Y@l{`gvCmQ1`SlA-Y8C_V4uU zCf*`nd}<uIYjrA~m} z_AnU~|K3#Sdz!qRc&jGy)pL*iNL=IT!Gz0OEep2lc2KxZ2vtJHX+Jw;sbylTN3477 zy%7;`(W$+SxHNfoy4+W7C>bY9_!qoIVV0dRep?so*r^hJf6?mNPmDh$=fP00tn_O( zLX3m1l~3ojcEXeG)exujFp+x`ff-xdKc3sSN)j zcwszFsLX&6Tpyq+$N`uJDWN~vW5}iMW3moFCBv}YO0bfj8-3PTr6J~!8yZ1Wm|&*q z&s9FVMn92t|E#Jd8qqfHPXO;GzLY*4V@~8M4<9*pxK7S4CxzSHW~h1Y4yw$^x54?Fj|p zfZ9{Gsc!7v+3BLkUO?hd6VIA!W1Lvty!Y9X?$zp7*{avLWP1DU;aV7c+H*f!QfXl! zNypk+nkfy$6eB9p@L92PdpKY9kNAuE`))C`5wzH2wjV6o_2^Alysg%_sMN$%>hTP6UMzUJvNSO+m`7gucCl;;>@J4lmUTm8? zBJG@a`**})8_Jj2^nBK~zhcML(TjUtpK?AT8_08dqRx9OXG3(6;x8+5B;zz_mCCS? zY^fAn_UfSZ4?m~Sw*`Jsdxz!s?^_^SC)(iNWy_PXRu`b2Ef(uAKeRmG%u2y>ocdR| z?`?=oZ)3f?M4Bu=7~bN-#a%NBcjOje#+-#rOV6xcw^Vdj(*B@ z5bAsb;Pcn$m0`PmF0L09Gnt8kdv6en{RX7*eUqT3l|UeW|F6`Myahe204`ypR&(urzJSqw))GUx^+lAL;Edz^) zCd?|ZAt03*s0C~&V?c_F1r z9qG7!TP2#u?Jy+;ad2E~r8vPZGXS!q)B&MMMcWAu}bEh}C-20Wq>3A^-J32Q({ zwMK0iyk=uDO?2K*o9_cX{*B|xi)3%NJ?d*+$O}u7@1y#OXt8QaYBmZff+0K4T+5>|&R(}ogVF;_~R9<6aDa|6q^&}=hTpZZ#5)?ACM`*PKRP7rq2l&BJ*z>_xat{zJHTq)+!986Yb z`a=4>0}W*MowktIQ8VgwMJ_ES+h$E$?3D67UK1$YzAS`m(x?X5>9|(I;O=H$G>-sF zfpo84$dpyj%FOT>o)@u{r}|K4wOnBjxJT%&iu^Px(eSA23YInQ9~hE=(SB}-K+}Cp zBP;}PFd=BIy*Aft@0-`YwC`B=w*P1}H$AJOblKMv@s7vrp`2xW;hL?U@~En%&APV@ zFHEYP%3~@@cLJR2dTG_Hz_fGypXb94Skhhty%*cpqM{~c?Ip&tSp$BO1rO?K2!6lT zoWMVN?Hfy8_KGEPD~fC6#F$7uyrSN~tmOlqn9e}7f--+DZIyhF+}pq0;oK(^eMQ9Z z(};m>4}W-Ocl-;~+lh@MH<&El#m>w-B*HzxK{w9^9>O4dUrW>0vMpYDA>vL;^jH-n z=)LlU9t3*CM#{$f~yYtC#%HT;QrmZzcuC5;TOk253At>V@}=rE@qf(&j`F0w1&) zEu{CDfTm<2wfo6hhJI-V4&L{?ju(i)j8%E*;=&IVO{@RZp78hJ0%$)rzvI-XBA%O< z+rilHLo{U*FKMd`jphe61#qzm!b2PKlPGV?J~{Vy;e+rX9N|-8NOZPdsuST`bSr;SoFOD`0`e(ifV=BrW2FbYn~c z1m%8~VmDj$`4k#idkv204W!4=4Nj?QR&r9PRIwjU3m8fug$>Y%9IV>(eQnpujV6O% z{5%*el>166WN_ye#rd5@-F$N?cB7XfJ(C|(8uzYYm)*`h{3i}o?FY&XcuaIv zAZiGnpIa{sn6cH{!Fq*`cId$bTQb-_GOlia_f4N*e>KqfB|LDrcM2SsCU>Hnj9RL& zclPXM;JwG^Y8*H*BZW)Us+yZs0!enQ?Jig}gI*k{{F&FQ$Bk0?{~S6$jBOg^EKl3t zeA68=UGu2*oA*~cKoMrHRXmB9x>tXqo3r?k^iX&Mp_4R>nv6L5t{-ee~E?H%Y9kQVx}~pDTAA7ET&m@GyxFYOssl6HZ9;+#8>{85J-^y=EodD%dc+ z86NJdJk6JBSZ(#P;mxWH`U!4POaQ`)!7BjgRie@3i2~zH0{iLqNY~xn{u;Uyd*`v3 z;)XXz4p=)0WhJ?gRmbMBD{VO^1E&Xmsv-(&dMklm|4)1G8P!zRwu@r-5fxDpr79{a zRRl!3qKHaU5kilEln{!P&?3cx(ovKmU6CRogqA=;i6TWh5+Fb*QUZjMNDUB@>=mB} z-}n3W*kha@XME?3vEMa@KMcuQbKP^^?Yggf&g31T@7uAH6CY>qqhJed>W5>PK-W!< z%lwH6luC~BkJYOA*_?G{fPZg*Fj|PQGI>%x7-JbQ1au*hvez761qU;y?vQXbbmFz_=rcLQU#s7O+m=NJtIrGNG+O>(3OLT?c8FQ&inuniu|I`@nH5RP z^)j5cPqYMhdJa0-8RL3Rg}bd3%AA1AMQ4PW0c8>O9Vc_$W-V`h`w+fI4JH;@V<-r z`feI|yfhrSa|Lu5dKuWJ0@!~h2dH-e-VwmG09q=?n?8_T%JY1yC6w>;>2BzDt$i={ z<7YI05~)5TZ>+HT=gSu%>CXg)eY}@I<%HP_N8=^;y}d9o9;)pfrDDRCo2}VaQxxBg z1WZSK)MO*~xD#iRGaIrR_g6l7@!7Z)fVoD zw=+r$|L#(jP~L@oklh+=HG{6QBg#?wo*Dn>`cboMWOjHJwp4gs7==NdOg|^}7(t}t zV>e0MRMcegf32}ikYq2`Z z8og+N2fbdYe+ehD16FAGV39H!>ors&8A=l%Zo1OovRr=-r055YKKEoO6z`ZN^UP)L zR~-C$P$G;;FWLdE_ib?TR-OKY#_a!Q<*Vkpr}x61%C8lt$9G*`>>7^doQW5|e`N2@ zIiG=c4kP2P+or2B7>K2SJ)q;uZd%I^{B_>{6z{#O+M}Yow7SrPUe^syr_G-~|M6~U zMglqrh*DKhxs6kCS{hk}qEjz!ZZh&;hp!sZVT0vwt!A4)1%NIAjeTYcM3FXZ0@~W^ zILz(n+ENCpWG}>C3xz5&{AI~rYvBR<(S#YWYPUN9!u~ej8r{-O zYt~!uEK(?Gu9|A~T*UyGkdaR|YI-Z}QA%yeuyCZBHtjT9h~b|hiqjmL(ve^R3pZWg zZ~S)UyYFzrS=@qX%IfJM|J6?_B5ioz`3nyc=K_-{LXD)I_!9!#TVKHEqogtHVJH+I z7pnWM)%*}j-1pHdyU10(y^H@=yMLtpPc7Pk^}J4wEtf+~^ZA;rdReXYXwT>8(f$D? zR$(Us{TEC!%GDvQJ$7?itwrg@WCE~t-$3n#WQ=|#DQU-Q3HOD(=zW#B1sx2h_6k@vHDO)mPE>AbjCkG65yBbw{Fb}eo@nHJqhUKPC|c270v#?F(GIlj?McD8WV z=7Y5ePb;2FIR=}eBC73`ZAlr#fzbUI9*_Zyo#fzi_nLILulDWRqlND?NTE_rxKd!h zz>r6;+pYX5p1_`9-!e*`hl%Ttbb+Wj&8P!sj9udN(`;;&-)#=utQSDvJ-bS7Gwv}16 zUz|)>Sp6#ZHKDR;r{pxn6fI3t>70%Kba&V|7t6PYc{G85dES`0-o4U0+dgK~y2qAr zH?*M}7@uB?hVtX=BpXOoYH!Xc+pDc6gnB4#k0(x=xSJQ}w7f^Ba{7$nxTDM5+D65QC z{>d))J@?qN8&>;@eQM&Q(AV>s+pzZxPK7-clGwg&r}DF}L-B_m^SwBqyRW4_ejC!{xPhq$a~-jgj>>DRSoY75l0cm z!5DojyRZzbtW`e-8umE|U%>Epb%Tt|WIQjYAv8M@3h3d@*`845iS15GqBIpY-=|7b zIr^UdV`*RAX+!5oA4|iUu7YbOmO{@RzYsbf=rf{Z<+IB7S!aliuD`}sIYY|#{mL(EkkRLR14FC` zo3+LEuU;ZI%FnPEm2Bhv6ZbY53w2AHMtjLJ>Pv9Q2+x7G8ZAeUpHr(X7_LkobvJO5 z>o)JG9-WmA%=G@3`mL9_RK6_VgRz;HNDlLqV@Jq$Y)dR(*!Z$^zTF0+!>-DF%yV>u zXvDQdTCmi!m!O+N;3^raE1VrOg_p@^3TZtl>|hlfuRAcL4!`6zlGT6nbdaYt;mCCF znS!VcY{knAqPlb1WB##Z(Tc)#fbSTBhQ5v7$VCNHN@`bwnE_hnYYoq8eSDA6Cz2ys zrH9_nYp!M1c7O8ZElX3L1kS}8tho8c5+1oE5&qeax47(R)3&mP=(mNkH#{?#-G7Pw zrW8(}!S&n#ww}PJcD;LbKVS|!wpx%YnOMD_*SdZ&KSLm{%Lch7nmlRq(en0SiYQwp z`xV>Nzp(h-{8w1x+NMpsZfAm_gasko^Q?Z_^*YDrz6O+#Y9oP_g_pXc2d{iwlndPhy(iVo;1{5l89AuaXXRf{*e#_*!VlIEL&|K;WgVcCGpor>-EVFbCqj)g7ts2j* z=2ynxI?iveG*3Fe#~UKv3{wIA$%r>!n>x~hk+H&@Az64;(#jk$yS@xKd=%nxwfQL2 z`9tsBtfk(&9V&6*p0hX050be;V7JZ_DSOE({2zq4t~T;EZ|gj!rJR}d*Y8g{-@M>_ z&m7qD>Ypows`I;x==XoG7XG!x`~(1WMc@uw7gqfD_F%vNdy@EKiy{lO6(|4U-ExIk z9@*m50@fC)wZ$+6VsrifJmk0R{v)n`R@8r8UA^^MSdo7&tUu=~SBXFR*sof?efyTB zF6u249e9)T=lPX~L(|1L1I&ScZo|cewWIuQe)#>t|L{8Nj47;|>IelGvf>WoqG{vaI5eJQ06IG{iFBJz+ieG2#xRK+~54q{qwHD zwLQ-kdn15-s~^rE+EVkflVaGtq=A(G`l&+J(I#a3D#=1fb$AC?NX(zRIB7w!Juwjz zcgED~023no$MkfD0mH|HabytlXXMQTF`RFr4gumSQ{58H)%Rf&?bdtVSl+HG2OgUl z_-E*svTwP;F!;hcWmDkD%uMFqEn7D8F2TZz2>c>7^7k*c{t)7ZI@$!g%#qCMpIO48 z+XVoDVgDBW>8)AHBt_h!&KU>+e^QPBZaiSHB}#AI-_ITCug98mp6j|bTUX1C%-zrk zV75HkInU_*V;zU?T!@>^=ZFA#Zfgc{(S;(w%@r*3S>e4Y1=rKKPj zSKGhjskPIdH-W4TNcGM94z5mxt;N#mT6Z|xKa6~XBkDiP5Eox4(o&CYR15=lDRutW z45Sqbw8V=6Pc;9tFuiqoQ`34vZI#~uq9$!EwGg-2MVZ4b+GqHu_5mONYduMCFKe&b z58WC^z`s^cv4iTVD>*djWBTJu@``zS&vx z=bQF2;KpLh8=f8jj8Z1L^@dmD_xAMGUnzSM=Si_6?b-wwMreB~wZ%!l)TzFc{#zzsm}wZ ze+2IKXD|cTVE+i5{_mPo^s>EXuhGkYV&lK1 z^8ae|HT!R2p0xQ!Coe2`avY>rKFst~S$NjZ2lDF5bM1 zHf1-hOP&M`-Vtk^>bmV}oK zP&pT_)w;(fg+ds`OEWk2RLD}X3=MLKal(Vd!YP}1bvubxdUpy zsJ_oipTBfTxIB~xO1?rS*9IkdGG8mWbcVQ~yspednL(PPHZJ%XxgU>vN$puy7V+OG zi1_TEwvfE&^xsALPUbj4HCotA)Za(3c+godPLeW1e7h%WHmHFr$vBasQ0OjDrQ6|x zVjfTn@WAZi5^mXY>bSHfI^IMsetw)$r7B#^KGtvjLzY??JBiCzEfh#iQ1e?;>!+8HkOzthR!z5I6Gh9#*<5pD_H_mv;e2%XtKA{5?)D zWxTcijsa?ig$0c>D*c?^H{dFBqFmSMX7&qJD=-E>&+!>NC1tX~ucTk#pVz-E& zuX&M^HYTy_lcZ+c!4oDYI?=ro46rUfon;=d#>3rp+EBVRT_3_gZe&;c_A78+JTx0P z$HxkN+At$Nr~QdK2|66Nho=J*k&pLnUb)^?bZtjTbxwU;DP8RseOZ%WjZ_`kMOo*c zr4ffKmr<&;11aiL&hjE@i8oW#Hmu9fyc7z{@RNp{T>Kslk2k>J7LyB)Q~JfZ`@actvb#pOcl z4x>)yJBjPwhrB-E~5Z{6t_MFn~H<<;pHO6;F*LQhQJte(V3*M&CD~YDNS6^^DcIP0yH`Cak?gVHNJ4 zt=g z^u?#Dm-?tLw0`uSfRuKHf;6quv<)ha2#go@BCi29kI=2LG0xn}kn(*`H%CZ=~+ZlDGP!kgS0Q}I&j8!k&ftg&Gf zF)8SUWl4HNTo0rhFN>&1_w;a&5$N^iIzDyc)CgGMufBY31%5daYNjUlZ1yZFW{1V$ zQ&y>l&}V8~-??>Bf46vdN?5@tJ$tdknznbe&(mLl1I1j+?eQ+CVI9MybdjKvpbe68 z21zb3aBdIuV4zrBWzg853(AS0ACPUwBVuZL$9w!hq)pq9ytN^b?dkU1wBU(y-`>7q zztZFFsb1@E`HU!q8t$=WEvtg|a7r3kPuJNhK#{7i_X?pAn^ZwZoh~YTZUlkpWx^+piH{@>2e<9km+>;M zS$4*n)-Er-qDu&|-PxvTK_0Yb1((=#KKh3zl%AxIAl7iUy$QXq#!r^DF)$O6ZK*p3 zBLr7m6DYbpKE?mWVke9&c2mvSuOng>Ty-Wp7wo6Xq(#L8yXs_Kv=*gj7UOjjtaqJ6 zZRI#+cR&Zow)aWl{H;M#tts4B74!`yB2LSV9$=SuQz$$c#^6Uw~R zdFShIlzHaH&cqvNlz`rjTBH(*L2D-U%h<4Cx0*cntOcmu2g|BP-*?GBYh2nA*0RL+=KG1P@(zrEfd5apWWu9p3Ir_^E?_hQDF0vMyA=hR zLbt&>MuK{N);>VT`QhOrYj6y)Sj<*3mQrgdbE5mv8UC?Ud@z+ti6i*5r(f7ujqd2J z(sRAx`4&Y&{kSDl_X)3BC}Qbng*Ed!_Q>KzSgTmOIYDP9v`v{_F$_VaNd#AKqM^e9 zQ;zD}3uU8Fsf)*s^dv`442&_#P0}5AI(fLYY1_)R$$YGE9RUTicm>-7N-$&{`k+U( zce^90#(Pc?Ofd>$3#c~wQA=c3WnRF^4y};Q!5~Ioe#9*q@o)8XC12)f9|8O}5K z$%oamPTNlMY^|vYYbmg~`ujOfu;8kA^i<#NjA3z-ByPQ(Ur_ITz6nz!G#oNTO_*1d z9;VIani$wd(k%pomVvHbB8(Ga7VFnRd)h@xuM5a|m%5;)n^Pp8*X7)BDsMDsGkh7z z@bv7NDthd(bd6tlO4W{WG+~!?I9UzFG+tN=`|RWe{>+0C`zhe-IqulY>k&;dfD&W$A(*<~N+B!_Qi^NC%WI$XCujZ4RNPjyqSf z?$&Hdb9w8q-X8iLhlC6=$nWrqVPC~+o!ig7atFef`fl{z(Pa5-=S!sGJv=T8fp_kV z4g-cmGIfN-sH!X)`5|tAOnt}ycEX&nGn(0o;p6?Gjz?AQQS8=f3ymQAkUYj+5YtLL z%+n-W*T~M9%^&fa9hw!c+BnE!^KRW&!;cLzj^(DJdjn%1+_dFwLW@5{9PFhg)s*C9 z^i*s1t%4D;eYu#ky1sq+i|WnKzj%K0p_wIVfReA$i+Or#&dhwFm(ixSaal!g1$2Xz ztVFL;Q=_Kbc)~j=kuE3*2b-9*#}Ol?9uvD{s5%yM-#9B)U~I$Yl@jG0PBPU-QQc za{%9o-3bwb4nHIJTVL;Bue7-!@=A5A4b|}#wjX;}X(Ja&&S`r`nwj$}_WdT~yIlrq zbUl3>vv>-5a(gH4wJc_yE&k-Zez<@vhEs(-ns0fExhb_`F0;KFh{&KlSsTZNk=3~~ ziVjo+g8S=;;#-rWB8^s6Qo^g~Y)H!+_Z(hFX?;69-Na@Ld?T8xGi@t4{*Gq9UvoMo4>Rx^i)1xeHS@qFY%i1Cl&Q}AIyvi-jtsLS>gmOw-)bt1fX88i9c3IIW$2lo#Ys9VrqH^ZY8; z^u9m(Xd<;u#iO~U-iZ7-m6K%=FBUQ?#unW5pGFW%8Lr1==l-64aRu63))hG97vT5G8hO1e8qQyW462H zQsd2$EcN*k=1sm9M-4VnsT4U--(97XZk{yHSM6R}(|^q0i}nrC^`g?`5xoBHEJl}c zjAeEh97{x(n`)H}%FDt~cV(y$Sf<}>JuuGHlLxuXx8RSHi7fXGC?Fb6tU_`%Q(i!t zu)V*3>CVc(4skIfR{K&jT>11ftVoBEXX%@)6|F%f*yJpQq@wxpTRaejgD zjkR=jz>GBU6gc-x;7l+15XTcgeXGGJ2>ULSD6kU9^FcAf6biq@X{@OOj5zPij%TM% zRgUb`;5xsB0H5@=ZSFsSPfeNUi`IC8*j;Ra6g!WwHbDoN5r0v5X)Txtj*i!2yKNh? zmL$Y~)-#aNKV7=7?Es$4_9by6BVyfZmg*yjqVUH<3;WBPv$=yFVCNiPm;=E+zDSrI z#f~{-uB&#l zW?6f;(<*}PF(7aD5hVA4ZJCHIH21aYTdIHd*LS5m=z)e9;$_E};SV3#5qZ)HzS4k) zN_nso#(fNVYov;5*l)emj@@hmEWFq0@^*|$FTZA~zV_AQEzQF!>tq*{f1;tEjQ;zD z01Rk3)DF|zMD7Gk$|r^cQ3q1oJ(GQo{&}sSF|gRM{%`@1kI>PHSuar|57&F#hbz?D zEV@0ZD-+;h1I+@JL|IV+qHV#&@mGq@tVXQBo${nlN~@JEUCzcrTtlgUly|*pKHlgD zAoLJ@$;6i~$Txdx%D;Xp6J^oC0(Iwz!GRsSNBd8VPkjnjkTa7JZ%=#7np^&E#9itb zVKWl0Q=>_O4$wq1GF;JCdM%Omkd`#R(Ye}3*ql1$;PGV59Bx#Q3Or{zwPW5iY*$la zSZl-3gY_jrU8EahxEX(l*0b#15@iYmN{C1JQpYXKtwa=TQsY;#9`!gjnABR zOV=}{nOLD~BbuV7sV|Afb5$@hiatI7`1hq#W1Q^xTZdVK2oetXX5W7+YGi8bimH61 zcC<4jbIzrky<1hK`toh#M5ITb6)D0d*OVz6;qkh-_V>%-yIV?b-dLR%%xGJU5DQXW zCy+j!g4am8R@umPV&M(5lnrpZv|hTT(%;C|%PCSHgI2A}_7(f0Ye>S1Jy2a-HiOKx zZiKt*3oF%@1G#DMPqi@|3pUXU!Shrjir5V)l7!aANu_{x4-sEW^(zOaM=suqvbWbs zRa;8yI8$2%04|n;kZVt9*Uq)IuA0-UXPY3} z6@5QQKSTK;v-S+ubBgKYpZpl~?dsfj9Pt3D+HvDcZ#|7k(lp7f6fre6{fHjW=U>$a zlJ}s`eV!J=OAhsTP3z<`8z2~v)~R{#%7>=Y4+6fX-jR1~X>For7VkAQ`XP73fURn0 ze=0{Z{7O*(WiVw{qjAPCdt>Pz7;2oJufG2u80wErMR>2?mB}fuKUy9aRxRcL<>~nf z3cKJ87G-?hU3}Z_o`rN!041|_XH~;s0KJ7$$L*lxPe(leVtyTa=;`R^k$@`O5-X&b zHKVC~)mb5qTMN5tB;1THpE;keawoEHhFw#6%_hLoXtD;U!g0-fM+O^&1|*{ywzS>B zhGXb&23GeMeDf_|!0mKan^$L|@%H{WXWMV4g~y0bvJIcF6w+DYWvZ zQXyUOqL5!3IdwNMdxBPfhyyqPSWxjJ1%+z5UmzDQBVKFeIndrOFCBToACy+EbIKAb z5tlWKqmLRN5HGLq%5T&5JXI4k>=CcY#IV?>QcF@f&$ z_{EsNoQ(?mGW%~8mPSH?Jr2mhP{(+`MQdgoZmjrTzD4RCnyuJ#R?ezWv1M%gRnQ+Z zti-YX2NHG)`~PGBzI_3kCHbw=4?lASHSyXeg+Hgi{#^xt<1K~HEgj@^gv)_nsS8g9A!w(vOujDYb zZm7g2EwBFVR>VpK0&ls#F{>(6Yu=aJBP<(ZA#E*a)M88N-dovR--Xf-&o-jreV%Jw z^xep_J}@j>=e2;o5+ucMQB&Xo;v-(nqT=i>Sr3-ZILYKR*6+lxZM;=lL9DgfhWC0Z zjZ{0Z+W|1KZmXPBcE=GMz}Jfgc=&va4Zx=b(&Af%wEx@rGre}OG#8-8%elZK1f9elD|3OixhgLLF?rXUZ$v|mrp>&WFYnn@GRajp zFzxzD>t;O<$gz-_NtuTQ{f&7RsR2muGr4L)-<#@^>dlmu?tF#CP5XXp;>PA~k?Jd? z?IAJt05|LRHPrA-Te7SBJt|jFyj}mC=}>a{IIZL7%H>8gE&pFoIFb4@Ufk(nxwMKxmvs8jTU?--Q~ zEUM7pcgPRGc+0g2cgK$HTxEZfD;Zas)kZFW^qUau0JzzH#F+9X_t-I8<>@=(nnljh zIR)Bbt9_+u@>k)DvhKMba;0t)98muI_i`QD3fH|M;~fKvLmoXplSRD51I4PZz;56s z%F+lxT-F?O_h|7T2mYJCHdUU}f?`pBv{%l}jAb7)-^DeMxaH^F?60ziDRXkFpPGpC z#FGh(Npx^428XIp(iKtLOw*Yo_|IYO$S6PJqxGIedr-MQ3M{;XYkd;`n|=(y`qJ~o z1aS)D+=H7BJMa}}I8dVtk4i>|$b%EU7}$Exj6En;U|62Co$LF#t%~tbZ@5mi=F0S& z`9}`w#V1M6+NX9{(DRa5y}e`*8#)u=n_xAMzZbh4ULESmb+u+IIhw}Up6KNS^YeVt zmX>&-v)(s*2qOa}n=|u-S^QMq=qvypbFKIMpI0bNuXdkNp=jL80|Kw-(Zlx~TkjY- zQ~{+a?uDA`_JjHVj6NrD|1C^Oz$k2lG^O=P?EQk6PSUnfw-P`dY-_*=E&+iKgN^ zDhXk@@y0mZ?7;6B0O|%LlfY;>a6czai@pMdtm+Lp$~|Fv&x1A|!KFFN2lRwJl<59? z*b<`>trl#ys&|LMGxOdJNTD&r5;H^O9lCmnggR@G1R0py*ejdUb6@~cz1$Q?G!z{| zI1V^O<^<=BA16d8t7-7ym(ire6de%#l4cgl1IU%9HBqzau*cAZww-6R?-Sv1L={^&5T*jXvzQnfhl zY-n_a`$z|?@E0pqv-CW}Sws7H4-h*mImd$7Q>^%Y6S**F=$T_;ohqA9UG6u%#z#O8 zZg|>^j`f62wO3P-3d`@#LN=vaEMSFDvEg&WvcpR4NHqoSV$lvA1-}{kuyc?9khO2e zt8|=#FbC8hEqvJ+Gwq^Zs5({y6nac5P|?DGB=|urW9YpXq2C&0^zCMAl!Ahqfe3)H z@PxA2!T7PL;4U5L#?^W6kN#U2s+Hy)GLI*@zKSkIwoB%GuiuHAIfRs3NDgZal3OPq z6yAB9?%9__q3OMc-hScg7?nYoyHF2nz!E*v&MvTCr7tp;*D@A`TcR~8Jh9zL`%Mtd z_8@ppcY}=$Z=|pnt7O^9xUMHPtWu0C^0SXHCHicAr_?YID}>h1T151Z&GP1GKQs|e zR6N%{{>#g`lIquH1GX4Asp4`cm63>gB1wXp-Efx+loe|**Dg@Py=3g*O8ZxFZ&p=F z15_LZUHeW=aj-};(ld>`?a^Z(fYwj;ChK%@LUNXW`;?EAl&-nwSZJwg!P}JbhyELh zULu8I2kqYXm|_$~JY-1jJ&!;4Bpp(+Tdi_I-Pg-S)U;RoQovWNE$t`^1l>K^_fGG2 zK%I|RTARc2IKtPx*E&}u6DFg{@=)F*Kbv=;4C_5g=6l0#QFTY)h%rZr1T*!(2Pkhs zXdt(4U4tC}An()tmJkVX%3=kYC70(dp7YE__9E75Jd5{FyY>^uc!?vadkM|CMfDR^ zSISM}fMHcRFKlEOA~P_=Bw6si)GsE5#j`Q=^BEibV>OMi#8)tlfr!n~_rKzI; zmP(jdfJP6Gc|}emEro!rgwnSV#+-p4rB9JG5z=ZqL)!mU20BV;6*ur#CP_y0xd1l2 z-+D^keROdd1rAmKKJ#;F|77@ymQe{;dDJ%vnYP}skGC;Y=fu0nJ(n$(^Y*?M8_u^MAbuL@-2-#A@=>&{Ov*E1x$#B} z0aXji;CMjp4vj(i1H;*C#{<7_PzF%Tw}BY+^EKFEbIIIHu1xu@{Jm59#-qy|`@i^CNA{4;Feu5vL`DoDuj8IE4>QojGEop# z?MCO>oU$PRroWks4h>_8Wm*UpTZYlYom?5xf|?l}qNT8nUWlqAT-!+0>B;9_cyoGe z$7HjYkGs#J*$pqSy3H#9xDL*#PIe^|@It01ZugXII_n*kR9>032C7xgD@+SXJ4BM( zu@9zoF8bjoX_Ju~CVJN*r(JsAqV;Q`kzo^VpWz*Q@d8IWM*M;@A~Fzr`^9z^9OE71 zIcIF`d&6_Qrcd>N(!yCZF7UTD$%u3rrRv3vE?osnTHV%+7dUWVB{rO}N4e%QEhtoudN-1233q5k67w)`+Jz`oouUN#B zc|(@F{VVCeHiu+aAeV=^c|Xi!jmW4re%ZFm&4bEz#`T}dE2tjl=!KB}0l(NKge@j% z&O{wcZ2*HBym-I#Tw0LLX^Gzxrtc544m?8?$k40;*(_S`^y1xPV#wGLQmC~B>y;lP zGzWP$W!4@}Pczf|CK=l(rWbj^86DQ-c}|#6Y(y5*LujY!uI#L;z&Mjp;Yrk1_YR0$ zUWA>j|F2)QoHr{h4bFk)qgzl0fq5E_BWVcOdY30%{r-t@w2y?<%Ffa&Q!(esV;jy^ zCaZSFUw?{%osPc)9HD*PWlTJg2^5~d3md@rt6xyu^TpA^8fEJcck&Bv7T{Rgvec;D3zl%knl-x7QjiW^zp017QIjT#0&@Ls?0lO4a{q>% z#(HA8WDc|bMMdw6D0pxY8O&^4$UoP?DVAk((7+)zfBR7(u9F@AT5g=GK~cAZbgY*K zaApT5v;{oEr$m}^g|1Y&`C=a-vIO~Y$Y<~hDPJE+m>O^%KLE`LGLDqL=?)G%(Nce- z+I?ir#pbUeQv*5&W^FmAMnrzYHY9*uU9MW#^!JoNypRW~?})%LmvT1BXNT_qES=tb zofSD1E$IadqyYE#flJZuvBDC;>g>hYm5fG7cHU+;1`eK$0naX1>DF{U{ye#+){bNd z>7=3+<^wk4ya9iIxP9Ae-9N%FTX38=H+3#eXjEzly2vrK2V)ylYM&{A9$9ExxD6|j znsfIaKNsYlvAft3`&k}r$ZyT`K9wry_j3r+x?W1)gzH-oX{5_mgoF*r%Jl#{^g52 zueUwQsr{WY7w*zl_}>Yse}pv^qt|~v-DM~%{O)G-@xHlt*h4=C!};4~q*?}qg*3`8 z`6XMTH)q^MEsW)O=k4Ga@Ok=}t6)x|II`bv?)#)>2X#7pO7-$BL4d-1lJ4`A_>Z{<9NwMS<`43EUO^6(f$Z{iA7*sZTQk%YK|Sr=wTMmO{knN@|d~T+oi`0oZVhjyAvmKX{W@;8q>=w9NhvOWFiNGpOe%l+2!i* z(=9V;^o&)jzDQ~=pCLbRY`t*PjO<~;jt=;g)hynDu5YC0KgpP}x3)NZjab+yd;3+O zD@27lX3vSFNk`L=t_+YBohITsw2Y}}XiP^&wfGE_u!t+XQ~E*VTfdW1vlp$ynMD68#ajv1lybcTIL31jT6~gcHXZw@eeGd=q;b6Up;)apHyWV z{sXA5^yOdh01a%nd`39sI z;M^qN^t8bbNd(sm(d1{F2C|AX46V$i@p-j3rY4o6dl`UK;{6%)NHyO9N;v6jAO3N4UOf79Z`$385ky{JsP< zmlGcTPRCLH#of;SugmD|%u?hgP&HX;KY@@)uu^x*XhxN5*ID+opn{ef$coa;6Gys& z9+M(~kffz?dFHUq_~>mEx|afR0;j?h z^n}FSZ=IcVS!r^!AHd$dN*&F8#_rJ!X)|DDV`?73QL(ZWdc#wxY)oC{`8;MW(O|=y zd^rDA`Ubak?~6>}6Mql%i!hg-qV*+Gn5`s8Q1m^JPFQ##SfKynBUQFe3!%zE>}$$7 zl-{`*I6^G%H@G`}UBH?SM7y_gWAmTH76Zw`0pyd^{(o=Sz_RxmK$;e%Jp5iJNj(8l%|S@!x6`Q-ivA zL3$3TA=GA_-LXM8C=c?@0ElR|*egLhJ>JrSkwrpKwK3+{df_pk`{bUlY)fLY6+mkg z@K|isvOKMNH7PP_fa$kWWi2awYcYE=if&lQfogSw5XQiAV!ln`t2KOJYhugzf#AKq@ioDYn@@jHV)qX=|EIxHXF~Z0oLEWUA zqE$g~nCC8DU1LK{?&5A}odpmXnE2I|l`fLOx`pd^GQ5AjN=bjrPw2@{^o#x}m2f<| zalAuOy}Ix;^JjqupPX&j63%%n!h7>9M=IGz68Jd`uG#l%$QlUIHHD=ZxYJ1q++BW6 zil1m11h!KZE03EAL0#ZgHVJm~VDWydcQjTBvedOB9(wxd6mDmT%vSElH9yS(><}HK zEL#C{qk{q^W*cqM-}V(-LWKa9tO7tVRSX1IIV{2$dRo@|SdG^AN2 zed$fw+t|Bt3#-CgV#SEp2<>zyh_@rA(h!{ zCz9{d)p>6L1%xg7b%@XEx*f*A%Z-FT)T+H7B+{l`aZLBw&1oM1StC?JQ_p~;#ar5d z%3G~B7D(DnZg?#O0Zd70>r$X%`Up%37#lnt5Xs;(TF9q4hP|ey%_1v-_wfPonh7fw zT+&hnC~ZC#K4^2j^Ofv@1N%mecUna2Uyhs_gK{vka!bGi9OF>RnIpbR=k??e=`#G2 zAZar0vi3CnRmuk6Gwc<-Izs$Q{d&U$b|H89wwL&_WE}))R;XYtI3hoe3yK~l`r-XX z!VX%%=MH69tgkDrVC#uvrD^x*CzO=79pb`06G6;ABK>3OK4$X>-=pV(rH!J5~IMbhx8xojC-mh+YWSh+r8iFT^sr$nhqaNO_CU(U8gkzgy@s(KS7VS3+^^b0nm}qMu6w~hQqm@lWeQx z;FYHhWm;Dw8c*PeAuhnS(~Ez453TBo0ieV}n?tYLXylM%#>L`P?KV>%)XdC)41v>? zwsVD0Km6~UYYIqjwie*sXY-!x&?DnVBPov?Mbs{G@PAjV|HxebyCC-3rZ=e@pRJRg zpK*qNbvQdXS;NK;qoea1@#l7G+JgDE-k>bvuG>(=UmhGwMuMgRc`n}haR5E1y3}!c zuaZw*{kH)yNEV)BF9)Ln#5ftfxFbN)~x%1}$5qC$rbOgnN*2Hi1pw?sJpcdz diff --git a/docs/images/graphs/scenario_structure.png b/docs/images/graphs/scenario_structure.png deleted file mode 100644 index bdc70cd754089006e6361993b6348e2bda0e0f92..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 57202 zcmc$`bySt@);_whP%M;Ckx-ECk`9$zNO!ArH_~9ClF}UlixiOVFaT+3=@O9cuHSs{ z-FtugJL8PsIDZ{p-ys8@_1rb*HLrQidHY^YM*K1k5e^E4x-2OnqJTo3)j*-Jvd*7_ zpRkHCNWfp`o=J&|ppKFM606ceP^dd7Ns$LiPO%Ha&QAE7;|;6r(^t;?zVzcRZkXad ztWf&#A>0qz!uK?oE7PCJzuHVx%Gz~S%!E z{m=Ju=>PHU14C^1aXOlxG|;dm^5fU94-1k}5!q&aIi>@J8U3vAOE(-*dK60dRy4nJ zzE~ish2y2Md`^>2iTPd&7CuK|U3fP0WrF9CdbXx^GWJ`tE;HH4xN|g7 z7U_ASB`e<*?ek)y{N75!PqZrj!U^2j_1DKy}5 zbmO99mR;HvQ#rfjX<3^X5^S0vckGm2uCudwtdkpGFEU4xz?y4~Sd$1)sKn3_k9~`5 z-5MR;b{Y;o9JyzKHH3-uragVX^7L8*PN7g^T{I`JeL7n0?lOKH-}Ni#jcL!<1rFgx z1|24MfiyXGBN>&=xt`X5)5z12yfBwUe2?u4%_8&0OW6*D=^By!CSFnzx_3lJi9eYQ zZuPaO%M?t)V>|p}g)oFxs;DpFtnP7ij{36m$9xS%#S&$6< zv?3sxdnWVgH!7Ej_tbx1YaoY=9{RH_j&F0VnfXt@JZX{fGe@FCeL{w?YN=J@w%Ba~ z!ur@7Fja#$8L&JQ`pwwd%6e|Efj;!oUyE>y&lQnmfz&nFIl%=>DNHvRi;;IT~n zlZA!W9_+4j>Ulr1qw)$m2P{p1H8%ly-XZ0W`3|leuI;5 zWAk=PE6!-X^IQAjG2yD6PBWLaM(UHjm7Dsz4cDvo=CTGVo~KnOJZ!`nWuGn*78Mnx zrKN3Lpn(75DdM_31 z5mkDo_`&I-#hQ$!y<*`nZpxR*Y}sT@xwzE?TrT&eC3rk_B!&&8^A*B_hnXfSmaDsB z%hopz8S{u_JM!$Wev1 z%j6`gN^qQ$)3p1?0yi>YB1OarwQ5UkCO1a-@CrQwG*x@K_%6$_ohG}~xfE+w$Yxgb z^5soE*fY6!?m;*-?m++BTyw2l)PJmG74yGty9uajeC|%BloCwR2hU1J`5_L*9q8fi zI=j*ywKqP0>g>5_#K9V5BrMFo5E)l!DyANMJDGsTi`-&(b=!C|bB)qKl0D<@kfsB= z_d~hDgMi-#IsKVTyCk!}GpwuDn#@iPZsqm~gd9(Tleo+^vbsDe6&+5>`cWrzw+Qq3 zoWjwAf{?`6?EZVwd;G%7)qD>&=hQ z*N}AHZ-!e2FO zE>$l28#JON#ea^T!Us-c-Bl3LbQXBAHoX|3ly8DtUv;-Ym==JZk@C*$grmtSoW4_(|C^zEMcAWarZ{2qD$pv!~Z#3;K%Kfn2{Nx6Vjn%pN z@wa5X{#+wqFUU+EAuh6#B`dfqGAqTl(NyGoc!5^A88OknFT5&p`j&3wF zp~@}EsC*+$Y4yul^>|#U(@)7HTXAoh-=v?8)+{bm_s;Of2mC(Cffy!tUY)(k+-=P! z<`3umgZCUlwwS}>NogqqSi@^LWr+9`qGOnvKqzlpUhaj=p;qJ3-xJVAfoK7hTbrVk9p4>iCYupmuM~P?O2fZ9?bDYc8vG z5hr*v7U6a%dmj9VEhr=;IZsyTqtFo3uv1mP3A*w69V<2Z#@kF~RSGXuN50bkX8gpQ zn^s-9B;hP@H+ZVsnd=(qWE%wn>-HWBrV zk7&LyAb8qiWw0f!;Be|`hT-c_Zebr23iok_y5&ysPg?ZSM-dx)uS=9F9F-&2!TV~r zPmoi>Wjaczc|sudMhM!`*&U;QAq;azJp6zp|Mzn6P=$fb%uP&Ih1?ox1f^3J6GxbE zLviQ4tfXv>1&2Mp~U#CVG!4KRY)>^>t@E zOxrl6v*IYTSx#(hoXL3l3IC^xPlZ$ykAmBNkOT8Uv8>U>3xWloY)+e~_Ecc2vA%iJ z`RB%~?(BL0^8KZXzd@;_^cEo)kt@B*r=QqlZi$}N3h5f0Ei#JdaAb*&Jq&`B{*-Bq zoXSn%KkID~uH@9wI^FyaGeV;=tnUtG>pwv^d_`ZcPeg-z16shwT`E0UP z3T1*+wuZ#m$z8)!Ao|7`K819^xn*cZ?m0i2{=V=yZY)3gnvUG<4I(w zQBhM%7Z(duDEWgLHsIou=Ape5Qj(ae6q)Pwvo*NRy+b**oy+pR1HY<|sf*z~Q!S$m z`IL>dQ4Ah6W?@qy>qTcH|74j4C#EEoXg+(G!J(|xsa2GM@My1{ekzX6<5jklgJZEC zb&8dupR>X8=P)WQD%W~1JJaaqV?o%{Lm)ky$2AVOG!mu?K3flqj@+Q+G`%FN7H zSXE~?DN8i5dbpaeTOT>Ax8F~XU=1$n5l)sX+72SE?73OTyT9D|?U-76N5a$vv$14X z&z}SSp3gz2?y|+0;XyK6CM403jrsjNWtEI5H$(Z+z;od}mz-7Rq-gum*3Q;dg}%WQ z@6D7!OSV+vch%}d1IsPtCPEU;X}1F#D(R$SP5B*N{bKau+P3N&6nv>VTb^U4{hJq5 z)o1w+%S9i2;oJlajUoY9tzA~H)UhIne0K?$$L}ko{OP^fIlTg}0*xPDU{>5F(6RcA z6IiSuyt$ZvhJ>B(O4HB4EKE*K!5?4d>TZjYVZ*;jBaR@=LGS6SLuot#?S&r2nyN}~ z%GBGx#PrGGa8pW21oX?xdGnLbdTYK?E;#bnC}oK&Q-{DohjkJ}J!TuoJiFolBxY)- zEb~S>NgQ4#sh>6liiv(z+n7Sb5Y_&!G`W0mAf@X=mo5VTAqi|qeoI=Z>t1nguJ;At zuq9-$LgD{-MY1V7n$!=MY ztQF44N4ft^A&yBQ`!;4U;X{6JR2;mCjKBxl+(1gi@lv+&k-MRH}(xexpu-1_qXSFXW}~)ui|Gqg!Y>-wF^w9 zs4%85GMOA-pS}A0ra>0-uHg#~e#!D%1^A%n$QQB+L&s*(}YdWClB-_DFl7t{SZtRv~-KEC!3PfC$v5wbm_BXV2$Y~zG-EO zeF|puBQdFKB>vmaT?WN`;@7%vy0$z+%hmrL?(T~j)k&t`d6DnELAg%ct0s3UBI zWUbtuot@pA@Xh6zjXI@#m5Z-+YQ9^hd{Q#Gbf~yu$F7SS{mLb7m&YQr`{QO*!urLO z7*e*T{;Ju|v`LImwWCSYjqI%xMypG{ zxMMtz#d+;TT+CwStJ|a_bkJ-~zaha0^_!S?QL~uiWM|u6oEY94t`Vn4$A`;eRr@#E>vXjmIej?L&2c83F`mHzGw8#mkmBXC zo$`t;$xTzqFApd^mz;9&?c;2CYB2t+<+kfrGW0ZOH`7wmbh%Q`JFVq*W*n?D2ObnX z9`+n7+3)w1%U4U;b7*78(wuLZT#?hmUo>G?^e@wX^(v)Sc((XOXLnSct|Gy`s_Th+ zLH-<$3u=%Uf~oQ&*^qEpiCG_0)y~8GdVxRkN{R(tp>Y6ZDc2OHBgAf%xg_WD-&5m_ zdOq!76nMpAK#te?*UbxiHB4Jt!y3WQwO2hQDg0)ZtJDX$WzoBDIheKg_El$eM>67A zZF}-oO7?9SLS5`bP5UYfN52SF2aO!BJ>KP;WuH83dt6nx>HdOVG5UV49Nwsh?9-=D zPm;u1XXJRj=&V{I8@fNoYswB=IR@uLU z;a6G`J{!Z~(zg0{zaoyA;<#xIaw9Y@bNKZ83aDnKZuBbYRhV%}Xfpi*R~rz+Nql< zukA7}F#B-^lPEk%rR6ImV7H$0H)I8x^?cYO`A{8icF@dc&>~MSN#;rIPwX*mBNo0| zI&Yz{USB^?*|-?)v1hfKkl(AxiuXNqebu%~#gIeSWLGhw9 z>iwi{%RNoAnQ)ThO`V>Nh`m#Fv^V;92G{>iR6!=5Kf}>NGjq_vbz^t_4HzR@zw1iI zA>^)m181fUAv~|JBH2Dwph?fLi#iP&LX#Uk&0pVzcW&~Qzvpq zrk`}o{aGu|{VW~V*kFQcqdhm1rDuVJOtFs}Vd-P9PEzMgznF7deQk^;8oSajUheYV z61>MHYif2;C1Gc9v)$9<+219dJ30e9p!~Jaq>IDK!-vp=9Idhw3+J3n{guPxVE!*c z8cej~!kgD^?d&$YL-g#ITe0RGPIJ}1v{J87cQG^dqLLxb{UI@335U6&d@@V75k*-6 zjOSx#sd=Lc0`)#b75P3)km4>LZCdAJ-t$Sl>m+Y0eT-~DZCbW=g-S<9-~6JGE63b( zWDBP4-r8@g`GRis@ZrPmD%aE?~) zTpSVVv%0n$rQP*}4EsO#5mm>uBT3Y@Oe>o2d5+`KP{zA==N%RYlvT2n9V@gg28%iQ z*pN4Qoq+47cESC}i1u_#*QIC51yl^mkPRQvg!Y__&D-}gbgEqH;s^5$e6^S&;13~# zS|Wvb01X`-8eRu~4)-<{<9Hn&qY){~?nKH0ukT1U?b;){JnJsJEYL7}$*pN~{;=oq;SIO!!NuN8?BAfZ2Zy- zobzoz%DHSel&RUgz)_1?cftIsc&UW@Q>Xc;N(&1Mi&EowXLVAe*j!zHwftEfj&hcY z^l-&t`+ZF48 zZ4~Bp6mW79p;v_t8}Q4XY%`-b zCPkfsHg=~Oc0ymh#i)S9`C{}~ezGAD-bTsiaZno0s7V#kO!@ZP$0D=7OpPMbxsfVY z`PG3uy#_QpFX(!;<|o*sz~{1&KH|16UA4A$vFRvB&LZbN-!(b5?SKNB%?62V%^FGA zCBud?b0b;y57E(?Km;=$ygE16Uy$}mCCjpWmI@@{?+cMI$J7&t2x|)<;rngP&0*Hd zz^GL!7p&@8*^u2A&%$?0j!jAxZS!2RD^eesqxqu#|Etzl3u5tYE1w87r{IqC=B$m%{J#a z%eMy1S_2e6dK~S7VH8R*MM&ArwDo|xs+=r#8Tk}I(dz0dAk~`_+i1c^Y$KiJ?G+LQ zQ&ZE9LX>y_u{;R21|@?A1^wM%PS3b{oyXtY*yxfKii*4$(L7~4J7AWpTwvJR67Vdu z+I`=&J6+zefn~UVy`n8aNLM_Nl<|J6SC6Uk;y_Vrzy;Vlx|0*uvKTH$J{H_H+l`q2 zrb`b->INkhmFcg~PfxV|Yw}mfDJV7%*4xcC{&X0MKcJj+tSB<=$xNDX0BogWU{JER zx0jzKx^W}z=TEu6+jbsV0gd9DH*cDnnu5QLe}LEf5YQ{7$&hT$_sQOmk$&WTse?dO z>#5`8P<9^`txT{^v+=KQY zQ?>-dEvE1QvTqBH74XMpa}F~$_M|{B>6Coogl(KatFWnQ<`oj&lyjGf(v8~V^EI-| zXH#RkQzY>U^x$|8&LQ(GWvDq=^PO&sqfhI~D6^ZPA&`r z+(#w!EM%n%3kyjToB{&cX)mR**MaH5px}!Yr%s(} zK`i_L7nvY8GmPBQ@)&HqHIntw?fd3(RW6$x)?>o`i;kCxx#dorP=r#X!^h{d=dlN) zPNf=RWz#JkIocIUC6?Noi-W2Vq5g-Jc_o}@Lp0ZPEty#EkIOa3I^cI9-^PEAe|t+n zKtLJOnhF^Fq2n2f&L4JT#czg%Z4}^8Kt2()zQ%* ziZRpDihcO#(TQ(oo=3LxpgWq=?6*Ddlr?u~P|!!Px(wL_K{ys7Ui)+~%hrJNWMUmY zP19pvUhN(2FHhN)g$4&FWowrF7pjRPG85v@WQauImGGmvxht4b3UFv+v1HV=FGst4 zE;EbcNiC}1{66Kqdo=g%0cfR@(`d-|gB5u-PbtXA1Q2l;C&ml7HbMCNnfSnTs5B38 zSFfuGuqEQ~3A}6`w>F+`iQ)y&94NM+uNY>6T_hE7VR5-Q^)iW|`a1-7KE8@{dudtO zz6`}QpVnnw7!%Cm8v^5r*OQSq`Sb(DAinZ8RwfOCP6|Y}y88Mi!-82TlgWorNw)-? z7XqHE8y*vr<>%)IZaCEx2Bb&{@It?!U%zCK01xk*KNg(H3B%keh4P(&fk7k84ggG} z!Z90+I@#lJuhFo;1cGL!dO>PG>$nlDHf&+EM%VWSb9nPqXDp9hA*6FXS*o(`dmBN3 z9mhw9J(bROC$1BMgu$^_z;kIKl7Qo=7Z{pAEzHNqhmObuKE!+$8#{&s&%-Z?K)D}* zp%^aNh5!=!|AryDn}~r6PDJQ>bPSc*P1*Bu8nqF}@jEMk2Z~Oaf}6p5@jn{Bsj;pY zhDa3#%nLS$jh)>fPYoZ5gymZc{UI@zVK&%EI7t5v44opaix!;F&+igIPzD5EFd6t$ zzScw!CKHP%N`KHZ8-rV}#l)!gSs0*I5pcK%%qD4~NUtGa=p8Ol{dYh`ywJ#@fg{VL zDUP~t$KAIaO5fX@H>>r+LadP6I+2{5yd~g*7GU-hZr5n6h-OS|EHS6?PhkPqtQx=U^JkWKSqL-G@^Mq683A0{3LZem`yozMTVl%?ScJ0r6lVjq>U5^$XSf&yQ3 zU!Cs_dLf~jUk5p-&s~!9C*nN81*X%;wo&~mwuk{5dIy$z_9Eer$<=hI&?4*HosQ|r zH;^izIE4YCr#18*k2*9eN?oZkN2^TX#fuknofuyLOo-9I@pkfo*N{DcsR^HjQ}j=j zj-i4Bg`jxiL|titfL)wUD^Gedm75pd2}gm!qbH@900$v)19W81wh**L=J$`elMp320PyCt0}Y` z<^>B<1?~~nYS`7vHQGXwJiZNY^KsbXI1O*&;o*U(`f*}nLcd4@EaXo0_SJh+|LO(U zIgLt;MV!j|0%TfY(b07OA18Ju8lP>k+q?Ls3o}1a=Np!g zplj~Yhjseg3g!;fWx?%GUh6x%GYOnlBm9swN<$^owqh8zBOIoeT{4mhtBNMMmR<-` zY?}Q39P-iP?Zb+l>B!% z{{}c@nuwPnnc9yZ5(pAQ+ySjs)z~;4z%~J@UONE=Gtc9=tm1)4s+dQ=*x7M9u}k2X zN-oG0YeGUoDE_iru&~)5K@_Hg#o1u(aKP!Qf2QWo4NZ@SWyf1eZ_34;7iX@`J zB{IEFV_z{wI1H>=$g{fGYBUGZt1S4qXr0*!kX?XxA`p-s3``yJAYkBk;gkvJRni?7 z2mXeCA~yYZIi(Xg02s<(WOAGcje+5>kO_YBzI>aGi7Dp~d$D}7m|?>iR4qQN*o$uR zcVmb~xqSvqF;zAp2aqS-d3_oorU>!4e!aB&TKXOQY~h}ne-UaXpa{FWyMWgJ7#8@z z*RNksmi-1S3$;^-tfnoN2M#+Lb{k;{k&%%}LMx@Q*JwO5GBSAW|H$PTKnASz>{${F z;=>pSIV)@mJsYVPj_t(v3kHUUgaoxSq z7k09znj_}DZ(Ej*nVmX)x~Im|vo(r6?WF=%y17jI@|-m{WQd^=5ozh^=}8?qK&T*f z4@ZV6MN%d&G%b)v*c{QRxue5<-`3sUisx2m&z_AU!K=+pN=hmO3|SW>!^KTRw1$#V z57)D)r{vV*;#ChfI8Og>#2T7|OcTk}(?Mzd^%2e#f;bH&rKn|zrgnv6*sx_E5TBk@ z>Dz$x+=0J;>q9M`o{olwduAP&C$IIG7lbD|?pr8b>;E9y`b>M@*5aV@zY)z~!~tsW zNUqG%^Iv>xWyKm{j<7>O*X3WGy9}{-?7I0tp=6(q>mpCWMI4;YmGN(zQxUo<)^w=q zIamV#9Uu)7*@*6&rTNTHf=yH9A6v8zD#A z8=cScj3KTAJ*J{OJ=XkBc=Y)vJnDjy1Dg>69OXZDykdupX8Zil&%2n^)TV!PGvf|2 zaY#S}TsA(`J!9pg@=}OqdHS;6|2B2WptiX)gjjpnt7(lha#V=Xx3shX#j5imz`1%= zHIP)mC-v65|Dd9WH{k5bZ8#4kThrJ7ZD6GbQ37@`{4amIm)n=cq+O2S7`TQaknCm_ zRE>pLr+GTr* zF{>vN;Qdc#Rt_5<6{_|s5)ys-fdW`oEZ#@bs@%%8Cdyn@kYPT3Vt{NI@`Y@*yoU~R z-SRaahrkUv^nc)L+td+EMG^}e;NHHS1xW<~At527W~uc@7{Wq_2IT>XE~DrS1q5q( zKuEAzAF+!1hK4MaYz+i*lpY}4O5T+w+vmPLoQ6j&^C#LYrvvtnd1nt2GeUn-8*XCg z!^zbsG`sSXOhXe{QP|VfB0RcZS^S>4LyvCnwpxLg%*$A6v+_ytq;@wF!aV)Es-BVhl=si zP#J<%AoM}}1PV+M(@F(nLlaTdDj}2>A^iII`GpQHssP52x^Ku!N3wibP($5mXt~A4;x&$i7P&2?&7so0EY;nUMV(il6ebJ0T&) zeW9WFB!X^gsyfaX1o?_IAkBA}3R8^+_B2KTl(sfdI*wQQs=&sFA0l$%+)&&pN}}FfhDGbcSJ#R8`JxSNqI*{N60yy zR-XY?s{8&O-`~;S-(Oix?U#YY@p`*ZA4IIp314P5Wh|7EJbt!Uf*Rxt@t#M{1$wpm z$2$!|N(F|}Bmyo<$b71yaQ8PJ@^XSu{B+*A zzHCe?XW*YXiGq;G$(?5lvq5}?ZN&Fda#ij%o-RO;&69qBmeTSP<`F60!}Ng=O{ zwJAM!(DJq>g4`@R?i2x|MO^m`rAbpLt>|dV@v;)u%(FZ-4!h~ckQlHD{L~~Ov2w(* zGasTa+L$!CJb(P6%RDi&41hl@GBW-9cM-|Xe?S}}RcL5RWhFoK!4dd7E&?Awn1y5~ z9J0g8*aJzUwl7C;q;udt-9`!Ssb)E4)0O*E2gBQk;|ZMuiiT+@xog~~&!B{?cV4fK z!Xw2Z^UnOF5E8|KJ>XopK>Jo7l}YExq>i=o7AQ;xL?t3V$4>}@jgQX((=O9ul8#~% zh0qOQJ7!{X5*Zj$!y6UR>7PH#A>;s%b7MNjYHqvc_>fW-YC`F;VD*VUe8KcpGi;;@ z)n&>a9@PP)0+}ygo&te=Jh#sd-X9*G3L#ci7@BQSql%yw0bRszZ9ag-&@eJ)r`xwS zH-|J#?zXx>{DpJ)nJ%Bq;l5{oxSnvVG+FOY&nt*Z^aBtTCU`E&IotjyCA6m#G%);I zyMq@f0!jE%q1b>39lXwKDQjzM_P>8zo0^%K2Q>>RmBl8B-*eQF8UC zT9DE^B6mCN)hB_q!MVr-VFnqz-FY$#6fq<(frxF!&t|8(Kd^J4) zB@i-86UR%CJU#`w^7o5|@}CFb+5fNKMl3kRuUeLZN-zucOk{kbY#jvND0r z4YHIm;S85_{k)shW@kxh^L+7*C;B+!62er>!-!?k#W&Y&QNrrukrz=k+4*}6w1Ja? z36!WzUZ~!2=ju6k{$BPENz}9qJ!k*ndJY%q;Iovg)m%Dy;Zw|#+Bvk<3nMjB?5d%o zf);owfj3ka1h3AZb6bNo{DO|+H9YpQo-hTJ)hKr~XyvNz*}w1JlcYV+p>>JnpssM+ zI*Xe6$RH%u<}k#}=()pyH8u)n9NX6yrJ$5ze~ewn%)=W@?;lIfnPpU&%C_qi%8{bj zGhozYYVxG8yVP-a@wC@2_jGhk`yzHq$&A$c@ja3Q;c`A1qOI`4dAZ$%tEeWT1j?}I z38(`|{~>W*Dn$^P$|I!_PtO#8um zv>T+2dp@f}-c<_A5h-)ql8X&Qg955cZSClS0>7!67=8X~tNgs-nl!>uBb^tkziiWj zc9~T%IXq)BTko5Y9@i3K>7iI& z6;rsconb>_GQ7mzo-nd>e6*lta*$U!r%cQJOiNqGnMOQpS? zBikvmWZ_3U^Y2Gh1JSRZrFaV7a~6sa+oZ2<|NLaO#_FcsQ-gcAn~ywd^p|Nc0XRXYmE!=0vRNz3ue$xXDB zHKKD!xpUhrWyGSbl8NEh4%Ln)#_Ge?Zwb#b^~_tAeocNROzuH8)0_gDQj0NY={X55 zF-c92YU|Xxd5j*lKVB@+)6V66iK0yHgR1Yv!IqT+J6j%0U1G(D;weH`gUG+8ROtC1 zGpV^#Z5KT9$IH3zkGYJ;R2|rrV{*sAoXLH6eqXCxe$HbtYP1mwb+t7%E!nXRL#tP4 zcL{0pr!l#wQHHdOMvZj=`w?sEik%kmvdVj4<+?8ce-dpo3CZKQ9j0Y4$&;7{p%9Ng z>AAtS(wGeWN-FY=lKExcdp%iq-^4nEnrKz*@IQB;XydL$Bo=Gsu}jZtRQaXsty z#GpXJzH3A~>vpoJLfeJeDNSaf+bE@!PLFV{g;G!21WwA~>0PBTz>%Z3Nd&b#4yI3A zgt~L%l>USba0cNF)l1Mw((P=DFs|3kRHx*dkj&PyPUc5qucLL$(e{LnSTrr#ua;GfBr*pk=@ zNpcl$Z|_T0God0eg$a~5_?C3rjQoW>!N_HyT0Ry_)N`Nd%dSflYe|=PRVUvzx_3Us zO=LR{J`^H+%NWYZL<9>D)|+8!;LEMo5k3RZ#TDh7ZfQ`XzgWv+cDgotm~|% zpd6LaGMkK9E}6bHs9vEtw-y^(b@*wB-Op;jphPM=o?|*9IAx&6|Mq3K8nN=jI6JEv zmvnnG)!BgOm~k$h0S~MlE^yPC$o<*tCXMHk^^4T}8t@Dw4%|-*i_-sd^6To8xd5mK z5q0wd0s{BFG8sU?2YtBXXq(wRr_8Nnqg}LfOr}QQ)}X7Jt)b-hcY+$XKjyc$&{sY0 z9hQok%Iij3r*+p<*_3n~@Ao>j`o6Dk9I2qKZ&wsUQ|!kIDb|b4Zj%u`S2%oB$-3NC z!zI}j>?h<+-NvpH!BHD|JiFn+Tl68k#@>+c_BPRT{KKaON;RoA&OhC&d}fZG7IYWp zaLkfUo>30&?3FC3Vmy0B;@IW!-t^mveYg3(W*@d=vmxRq?G<%3>NP(-+8d%M``e?9 z=6p;$$7yfq%y?q5L-s1~0awxu3JRjsyj5$Ep<5Cjj7`?@XGh9aph0UruqUkWvLoM)9?#_`)Hlr;yba1};7p8#u2)iAb3_fM(NLH)llEw-8Lh&EfGN87|V zBHUaQB?#8If)`pBPusMn^!uzeng}w-Pnb4~sXHJ9_8VmUAS@wWtlvv2^ znac|S<@gJ6Hj2qq7`p%u<#jxU1Ug1RDO4>n045ztbKH#1(qZK@JEeP`ZtW;KY)}59 zok`boUTfcN2vC3)$U$q7-B0_(JDGaOP#h&E8oF^n zLa;26qf`*B&(prHK8T@Wr02Mf3b6(PE~2lW0vfPKV{Ut6V+TlWg|6F{MOLFajLB~M zEn^^%Lc-Ic+9HAk`NY7oT5kAnPM} zJ~X~QrT;elc0t$_v)&k9P}b^7`EILSo=Y7(y-crQev4lKAQ+_ zTu7b@!mp~ETP4&ukQzVKolL&JyC$fcf6A+7-H9KP;?Q{K>09nAU$B*v^uto1(vIW@ zdi8!CanDCGF5po`l3YNIy#?KY1J;FJDoW{&k4i1D zbjQaaL3H=1>Sm7~A8pV5%1c(s)ybxm3jbkQ5<>z!^4!|`x&t(M{6Q9|s_Tvkq7aWJ z$#@JkLAaZv15`S-K7b@ECFP#Y7eZ9+rOUVPcbnx_Az8BtRJ@}(OoEXl8h*bxQZ=~X zgrY-<(vQ6b1uYE(H*JR=<-KOzqa-+8sQF4q^EzbaR4nlpOk$y$e!!k_K;Z<*m#(}` zMz?Q9KthJx*?@v;^-|TgPTBB~9}enC0EpwXJUr@yC02b>%vC4+US3|Fi1pcPs5lur z@}s7paIr#hyxZ;x`N4T)ROI4aaBy%T2o}<@-0~o&aq^L(5-&j)g9PZ3O>J$xP!}K| zBeQZ$v3=gB{oDl9+`X+qD^BxYEKp(VT#!Jagb1%)`v^<3=+75bOnuw|DVSA}NtYN% ze$bl2#YgI83*fW!qDv7=L|mMnk56;Cay_8fayS##-jkz^?1vXyu~9oIBD_NDL=Q41 z9-f|K3XWcp29z-}L1RKhMC_~3#C#o9+YXtGF_?r#iDevew-D+jv!J)ifz5!Uv;<%$ zUV2vMCuWzpMp9F z-86_g(cCs*eMuakZ-X0{LOE76S%Z<#xBnUzYD#~1Z3<~`$*EjJBi$U*(HyLN!ANIF zG6-k1&_$A$mpAbF>8t)A$bFs_X@H=m0CHXyWXFiKpOl=;=`g1RNi^6S@Upc0v5tVEAWG)0s-5UbM=Efl0xC{wcY15%-xI5c;`R~n#E9%LFx(~-)u5zk|HfxSP;1J&*o zAjmC5MEIWa5{hQk^G14hK(1|#<5Puvm4#0MBVXZYfmBH$wO58ig1Vj&Km^KTa&JDj z4_dg2Y$nCv6Nj_1o(k*JtzogTpP(oZNpiK85-GEEL!sS%KD#6nQc9#0q~pG+46Y>& zo}3A*1W!g0{Dw180m+QiX$;GKZ#E6*%9Z;tGLqD{#_}lE><=#^(xvBJc`Tm>7^reBK}=oDpC}6O{z=lew^!+*H48igX+b%6>E;v1dkHtl$a1^8 zl|ZGL7Eby`V89JKTv$R$uP--E!32v$(|gmMMaZ!vDo!g=M%b?_T~XiovpJ8mCw ze=BNJu-S@3ZvjH=n)VGyN_gEo&A$A5VKke{+wT8V?s&IE+r&xFhK- zv|5;tRtsdSW@%)r@Fw9tJb&7Hvi>sEZ+?Kxe*p(42^w$E;!TdkBqThJ3pZ0!Q#qi) zf$GM!hv%P$>TDQZzHs3qVDrY};06Cw2V_5C(FngA}) zRpWVFsPhR*9;Fo(^dzz{T`V5YBYv3i9nYf!VgZ*>c#58cc92d!=?u&~Nhw32J4-bX zdfwO2!&!6l@% z_yQdnVFCAE<33E$geb7Oy*&fycZrz$!|wWwo|#!QxTt}a?OnF__!@71=)Q{gN`20M*UdY9u zFUT%aIkVz>`TAbGd-pDbR_TY^T$W=qGjEHEir^e@AKpZouR!K|0B?XB(CpCWrUHW} zt7NI?Jv$4am<;W4EkILdB_5u?`(3;sKmQq^pNNPE3)D6|cBgJMMKA}JlyF5bX)Ex? z=2E0iZbN%}ATY93AhZ+9 z%gh#UU#x6yBE1U?I+Zuc$jAycvO9xdU*27MYH1k&>$<_D^#rOZ{7x%g14U+Ci4RUA z6<0VnzhGGD&Us*CJG;A2jf@(gedQb6{ceKJoGzCl95~ozpkZI(rob17hU(RBJYcLU zyumvWBUP^JphkZ->7wH2=a+c=Sn1?6gPuNq{1{mkq!j=7=>FDX7f#Na$XncHS)A;L zDUZNfVI#n@yjIWYy`O7z2K0L)s2mNckXyW4CySf(#24`=Q8fg zApxTG8)!R+#ekBb8Js~7V--!#Ic#jbzgUp2l1&7Tu%-lKJ%F*?yg(o>cbFH$pu>KZ z*-^6_wv2(5!(!#r!t9t{js1svjUNto}{QY;oYf8ZRJ$GXLg7nIp{Q7*iFIU$Hx;M0{ z-EQgX>aP86Otu$+4HcV)AXsSJ@e&$Jq2)&cj0^m5BqTYR0$RwvegFO%S`w{y*9aN)bm&nY8IuXr8FdxZi&|^(biB$hG9hE zm)y|c_t$zJD?_6_;9Z&XIu(@1pF!v2uYrMy`T1tRA3&qmUp_p{!acrDLedJ(MXOoN z07as)5Lv--C^ec?X}kdo+<x+PP z0O$>?&#gH^0}Ec=+L{KSL(Gv?!I*$&1RAs8XY~N6Fco&Fv@DHO`GTWTqC@2XG9JD& zhg$=uAuGJ3s;YX0nEMVMjUk0;Q8cu_us}-U0xeq5a~OI8xcax?rT}0=nd2f6Tu&Z@ z$#V1Xj4v&t2RJs#PYmX=FaR#uSA)j|3n#p^(q zlate(tDC^8S3kD2lmo_{{~Dd!Hy?K8u84}HjEo^zc1tv;@5LKTKOP9hxEvku+`oVS zdtF_Xo%)R%H`?L_V$No~#^vdNtm+n<{&}b<){l;o;o&()(o|?xI5I-^RM*_>3tL#Z zb#4jbh;dh{KmPC=Tpk%H-s~)U9`EZk>y+7w*0XWhLfA!+7dlFzJ^TvQIU~jQ&VB0 z$ixt{zQymv0+2Vozl>BcuXI4i3lcEyTMWE@`xYCb0&`WhUc(jM=SwX}g%?fp8n+3c z%WZ~@F3bm*g=7%tZR4MbSa3mQY-6@7lvy_(0NbcxR@YbMhUpyhf{0*s!vWIE94muJ!W|xhb{mOb)TPpyUFqd<-GP=o;Moz zmRPyUJ9AnF2E-)HEiBXlz5&xAq{94}MSF>p;G_5qYAgP^F_DpSPUzZotN{)F2d438=EeF_TL0rIt~T*81>vs(^vLv0xW5!rZtdGO3z4{@@|HUHoF zg9srTCnuQMyg#)K6%`eb93vaLyCROzc*_nAS?#cCzpCB&AV*Q;4VH@plm<%!w1w_- zJ}8lk!C8IK2t5Yrq0IBR`YY`lTyisK7nk7J*n@#Sh=s`E!?CtZD3Q~L0ht3Uv>d5y zgwENO?d^uPwkx{2qlJ=wZ&*|SXT)UFy5OG56)kOTB!VE^b+FhU0tFC#VKCFM02=(Y z;t=jC9a*s70`4GO@(Q2#?>|CzPAudR3t&)f_vd<$otm23hv49sDp~FZ{JhyJ%@Df@ z&{SZW#_(1Mx}J+>;P9Kc`<#2f@o$_4Ra!hn|Cp1vw++g}7jBKFY@`wQFOJCts zp^-!=9r9s7`4>)G3%5W4fEx*X#vIYAI(^0*4C?u>vs82GKFFNE8~RZp<4;dkpIHJw zz?GAe6U_%SO=D9N4gkL8Q0bSKXD|LLGP?l`s$p<22D-WFNMzq#C4Zyx)E@HY6=20} zZ2^#Udc(h(6bipi-83bbI2(o*h2~OLc6QgkrBjc9=M4F)<91Y&e5xc&pm)tA;7E=Vzw0Xe`5&gIxnH7R{kV_h^W(m-;q&xM6b zEMd4`e}NwN4mMCB@0losD%l`%QGlOIEg$YaDs|gs1F7VDXXkZA#V)QZX8NY4P0&wQ z!2J>TAvWUl5LHBPDJU;o;#Sn+Ew85EC^`&8}*9SHSTH!on!tI2mBRmEgu- z?^H#OWkMqmhxxA$kUtcd_RuluR{KFNc>+sGEaW32BPP@~5WzMU`W44T9-h}L26qBE zP8#Hl9U#mniAgYv+}75X+x}vSh?rPDWQm0%nx;j2n5jYyM!1gj6iyTU9WqlNKF2=*t0X;o9 zgbWha)-2E<`*m>ewxXgUh60D;_v~y`?~aCsMw9v2!*})<&!4aT_U#pfg#sYcwli(n z_V=EifmE@<3+ptpji5YYAQl2hS9XUqcXx+^lpwK8d{-nuzS_+hQbuny=3#ON#4QZ+ z$xPK;8Q3@Ik%VrHI3TIdtgH|c0l^C4Gq8^=5Z~FM=cXx~u^GnL`5hw5?Rn&;k*ji7 zPz;hmxbHxP0>q<$+lM&R*B{=b0MruPUtkvtAZ~>I8r|72n(r0qN_5aX+XmuOsqGXF zkSa>uYPZPf=%lXMQv2EKkZ>sSrs6)-zXc%zz#L344ZsE6a82xce}9yh7YcL$G$aTA zgVKUv0!I1!3Eg3Z*q^Sj>mK=AZrgLD z^^w>lt4+D`NPkv+mW{BR*rL=Fj!^ zt~)osQY3!n{1qY3>yMk8*7LRZa7?L;oLctH4_rE{RWNg{OrEDX<)Tw-Yz#kQhK_S9Z}%2i3Qbb%aXzN7dp;N@rFtCA?+<~6 zjzs+CJ7@-#E4MeHdK|gZxg8Q53^CybaHuD+YxZ;9k{@4_Qvmq+!NT*6F!6>Cp)%_( zvXfutHj6y(;&a(xwdh#XuTG|=!`;$On@iET%Mk~qF03=fX0+OmXF0sh`kw9-VnzO_ z_3rQW9<4PC^%?cp_XqvLpz%J8hFmR(Vl%)2n1(9JE0~l*ne7xqfAxG<^}+S)9}RD?`-Jbk z205l#uk4f;*czlO?_|>S;GQ7}21Tzd)C0f1VyTqQ!D&{5TJWt@J#j2{%{7 z&`%DIuAX{_qjdBCF!kNxShsQeS~QfTLDmzZQe`l@%L-tB`$c!W; zGLpR$vO>tpUcd9(`@YBV>!0UHp8Nie>-vmye6DK)(_5ljOCDP(wsc)ZC`-GsJ@V-+gPHYP^RTB8#tGh;V8j(Wcnx?Cwpj#2O?kGnP zr?%J^>oHp)7$|B{BMKnH+LBO3NC}PlkUMN`x~;FTXTN)A@cGdmlnn99D0I zI5!-AwDY6vC_w`mZZCd%b51DqtmcU;s)4^y7@6Z@EhJb_@M`ZD8tLM-$vZ(zRDyeEJ^%c8Y8umKyEIu1C0~d?Gx@WqC|cyJ zOX(Xf5-doeD3PQ1EkhX&bl0FXHEw@%Bt2zfy!F~RuLO16k*EQmt<>d>B~e~*jpG8O zQ$)jR*%!Ul&@t4lir+ak+9!GcURJWvv?nU}k`^nii7za@5UCSIp#e6+^768d;o=|R zT+~pY9PEDQTd0}{v zGmBxeKksq2g@*Uh>%@A#lHz3;m;T&YBQ!Wgq9%$zizvXl@{B0r+*ilVw0TgQx3mO_ zZ>_7aD%6lNh`B-o6q2Sr#TE6dE~8(o?mYDp=L_iGb)cO6JKevP*?FMYVY&)P z0Q%7DuP;A8tH4ekgF9mpyE`{>*vcl>%!?XMt7f3a?`@Kv;=LE(J2my(6Oyi#rPir?tX;1?s2n>Wm z2kBuNsjSY{csF4QrRkHl>7-`tNmP4u@9=6EH?@*ynw<1!5Pl3&uO*QD`-5#8D|U6q z8!W>P9AYxMy|M3a)T_Zyo?g87eyEKLOrK+7dWhOF7b)}X*|XHZ{AlA^Fzi#zV{?TK z$kB;Yr=DF;k~{rEjhcxj;pRtua1wa6J7SciQRSl$bst}V?FbF!>058buJU<^^(Dq0@@0UyDaNd1ZH)R6@M2 zmyq$H1}obVh3_XSpL+Z4I7Y#9M)1O~LQR)p))z7f&Bpid-~S1d&X{eMhwl#*V@UI$ z4rsXacA`mVLD#7seZw^aJ`|N=d&R0ndBZ`Sq}JWKu8W&{GFQ{pa`aB3x0kEtGDdfM z!|Ltj4O0qrap@=I2L;2lC@jb#tv5>PjU*drH&#^c+@XU`LJw(1#QE>q^(> z7w|nU`GBYtZ&U0##mJ+=gQ3 zE4og!|F0xuZJuP6u6kb)|2EQ=eE3YQmBurQ4x9WvYyP8bypxUR+ib$wj9 zh0Q3!7$-LQW0PvM&@3mgFN2Bfb^#@+;&rRBCSAgCY#U7;3@6mr5OyS|17LjJrc|yO z8X6wvxDyWT1kjqSi*mZBkaEKjO|Z0Fl4|y*<#CSIM}=XHw*ZWZ_<3d@9hwld>DlJF zv86E~O3aUD)#uq=H~qY^Hkt}D6_(gHL&L*mkkB2MXLL29Qm&^VK%YQy`*)%<0N_Ji zct-appyJ&#t#S>UuagvHi8prVuk)Bd~RS} z%D}7dydpij9S24Hq$F{Hf_A?TANTte(urQ~)Q!}G=w@!DUcKb`=<~tUkOMk3@JA92 zFdSSWPIEia#+#c@%9rQ>@0OL3aU6HUUAZUuxO#5ibv5nAaAREDN2mE9kSKc(pL%g} zZI%yJ$~odW3{7xWncCgI|ANWv=re!+s=7Sdn8>K6!aNasmdd9e?Dx5*q|=DGrXE(` z|3E2)nU60NdzyeNu*WqrLy?ukLVW@PJVx}}(Ob8A*h=#9@Km5zLw{H5x`HlA&P=(# z6W@+cM`!{z)NJ|=x8jN3qY2L)u|@3O)5n*(&{cv09!U|z_J3xpwyeE-U9x&}gEp~d z^#C@5?$2XxyJ{mD9lGFvsymwCshHc zjQ~vW*t&XpjI2JFjXZJ=jsHq1s;a zrYRD9S&nyyw??eq5%@$o-^IX3HHbw;TqYp;STQ#_Sb)JKs|RIX^xSS@F)rSNn$IWs zT?%T-LBL_70GClbp-ZjD?!pyBkW;+y`%&T&W_mMbtc%zGh)UuZqS1$g2jXlmjHGi7 z<=N%1B>V+ivEjmJ?Oq&R>=SL#>^u{5?=xs{_!J6SthnpZ*{OlRH*?9`433DPK_4~R z6fb$>?VXi`g3}9Uhk`BkW+H?FG=7Y*Z$1A@5fHHA<;y!kqcL%F2MrGo=Nrrq*GghF zW)~DxVWF_Iv!e|N2nivKRl{FHfMf3i{t&EMUznYJG3k0Bn=(V&?=s=-0R29;?D&Q6 zIpAa6bcC<9nBIW?8@?j5W>!%yj!ETW>Kf>Fwcl`c(F zRiefvHnOZN0o-MZD$2<*ad7zKr?}yk?-)&mJwKfE+7dusPF`LD%wR7$G>-$?K_4y; z^eCsWFy-nA8l6V!aa$pc0%NJlcg)euSPcX@D+@zJyn*Q;$AR!43rz-&A&5b+C07r4}tyqeXA8kxyhe&FOv=D%P5 ztv;>Y$W1DB)3|-y7DzVLp+leXK5&oc>n1CU}(3;SgJ`t=J7A3s9}j^Z*KfO$sO2;C^!dgw>?ORcf+n54FtJUTD- zR7rw|@dyAt3`5)`vL}{Gw6KH!ix&ssK&%8FSOla5{hG;+H56IldSASgdOh7|XJ0G6 zD=6T56Z{IAF88%5{xi4UegpB}>fA2|l6;C8x~xp<+u1sofEYXgx(gB#Jo?b!;KR(! z%+D@NeTG%OH0wr#jt@7}E6_|57qi8${>8)L*GZPYAAN6b9KeSE+?~dhIZ>T$8u>T& zm|&O^nW9^ph%bBHIFD}k>hs*k`;KwDuP^6+-le(E*V1le(d`7XqzK^swAM!qHVsV# zGX{G3Do{P7dntS>P@iN8mvFa}Cr=J&6qEj1Wv5$_^@*@$I5_B4DY7d}$*|4VqMozN zTt&$LlGEzn(`-u7KT${%7y0WO4T0tW3`bxfR$QBZ>GJXmE9Ja>C@g`A5c>;|FQR>N zMnca2X#s?%=3#{gI0TrJ0IPs4;mJ#Y$|jx&xu_0_Qk<9~yu9J7NukYd|8je`9rgDE zkL)HkeZs=R(A#STF!b(Ty~~aoBfEg;DZb89Jh+ypDCqo`8U~*0LQ0`Tv?0D6qrx)( zSVK>O9VkfzIy^4qkC!jYM(+R|mdsQ|IdW>QXMnJ6xlG=?gMkg=gw#qw2 z@zHf<4sGXC%s*+uqy}?y^Oye7L*z7b9vS=8s=BrFU!F_)*J@XvV2v)l@#sa=Aa^3asN-nh3RxINwDhLC?b1P`?E zr0I_yGVYc6*C4J=wVl`@<-f{W9WcJ0?A+ngU=Fr4;r_s9+dn@dfFH|>PKa*g#oFOI z0F8f6k`HrSU*>jBDiOQzC}btm_Ww3mLzusVhroa-q~-7 z*nAWeqXdP`h`~MKQBgxsfB?({=6{5PgQI2WLh!=)P`#z+#GZ|t@_Q--%8q_E9 z@ld(&~RTIz9U4>yP}|I9<+l^DfY{cA9u!O z)a8Dwf93w`tQvY$W4gbLkQRUp=f_2#MB)JVr;@IE4luYUI4U?_NU!V>{O5384NoJ4?vEMd!tIKgI$M!D>5QiHFE z-mpNjLd0v^=(9EmEC6o0!KPp%lYBy>4w=(6Fq3C)zR|b6%WrTDPoH1`F;f66gDkA8 zkNo@;HJaZ+j;p3#%acq)h=OgW`}{KZ#k(~WcQREzVEOsq_?`LS2B1FxEsy&qA zO|Seb9$icMbbBuClc?YzP-%3w9~&6x1#RZ|KNpzR7{%kEznq`4o>?pR#b>J^oFonD zpTgaGsNZb-`a)s?9YVN>6F0`CoP-n*=q0IxgM(MZth~NIvUe^nV>2Ya zwL$^bR8=Ul9Mfc88Ty$Xu4gRwY}fEDoqynTqN(zMR#o^Bb>`ocHzxF@d{ldP?^a8} zO((RD6E}=KN!*sSG=@fxUBpTne(S{Nu(4_fW&2mqK_n=^bb*Du#C(_m{U_`K0@VD4 zRm&ckLt7sKqX#C^AKBZrE^JHtcCb_1BMEN+^_C+zt>tCcs?B!iAExXvtTDrC%-o;8 zm;rn{y)_&4l@Rp$2kR!rhVU2|icTc#%{<1br4K^ey z=`9cUW!*rc)X>*wxfxAA-p+AgE6dNe=0Si+N89fpq1b8vFHH^S?j{(p3U=t9wb zf8%aY${FcRk-&3LXak)?AACzQN=k299cyNWiK;$8e3O79mM8NXLGs4?a1IG(N)AsCq}10Xsi9_n=$O89B}WR{ri)whN`f)r2WIT z1G3Q3`42=Y8?p`Pt@(vcZTZGuTeE*B8_M0v4t}^P-z*`Qva-9y-%wWgO=rai`tufh zE?<`Tl6&4wAm8L=QO|`N$ZBhM6x&*JqeYHLKx7r-uRrs>z~oEPJlXEvH{~tV9(QPL zGtye=t0=hNO0ers3A)(x+i@vqnpTas8X?>o6asQJ8))Gs{PO@Z zNOTMhr9j%M72cyqKMEZX85B#Xzh2w&eu2y?2-`EqJ~{B1dJ=s-H)UY9&bjr{?F{r@ zeN*LkPyHy$vgI~V(Ap_2dE9%cLt4#}#gye$6-G@hz=6 zvv78nkLG5h^R$E+G8rbjsYN%$?ZQxDwy zUeWyGZzkD)dbdA#;4la=XkN)*26NeyGWvL4Dmln{sQ$27U^9q{==uPJ^)F=1-%?0 zVQoH438a2TSCVEVA>}bwfC9^uab$+EbluBG!BL;y?i{Y)&+PU|VgG1WX``~Ri=Z`W zGRHM8mqmvg7z+%3V;b$KFT;iC0k^-rZ<1^yZI^5A);GUsE7MHZ_*pp9-q~+^);W06 zHiL%$*xt@vQLE>T+KU77s+6L(_uZ{e)hZ!Hz)}%X`XDPR@A@nt(hk{f;cDmfNDDyHlZO}#;JX<_}HrE*7N!{O=fqXis~`n^dGbKtA9Fp<$C9QySWLz5D#)tg<|%KhcmI4|R+@7KQcG^fm_RqSa?UEiFpJ)k%As*{>WgV*6MFlr*N zfJ$P_ujGoQQnCO-$ju-ztx#U#gbze8s;_#VGmvi zzK0k=?IAZ?PUvu;BTBs*zy035d&I;il;XdT^nsc@j$pQXPi>QRIb_f3k0Y1j$nu?= z#+oPQ5<2mh>pM$2NZq^zQ-k{6d%tQuNVAKI)HB4uRJs1Q|BTAd{yN?_yKd6Gy1|vI zdE{-sQ<>v_GtawD*@a$TkG#6H|I`fLT&Ki($OTP8Q6)0w-}Qyu*~tR!16FZQJTEgdtnblYg# zC_anh7|Qbs?GN^uq<6-k7p6}Ifg-v8=Z7HlwH4?-L;PPFly0t?aopKGl+u0to1dNg zUK8p4ujylowy!@)yvM^v!(02vNOnc7g!LjrfExw;CwE~8$q3Il5s+gSRP*3&{ea5B zFcR$rFV~|@W$cG*mX;=_ZO%GV-4*XhZBLun;@LSj{G@)fySV1K^`2x-9^F;n2mt|s zQ}k?_iLoceRGojTTb|2D#Ttsn?ONLPlNdIq3@n1@thqfU26_UQH0k>&h_?Y9hWxk; z>1oTpj|wqDArO5Ij*MK<`RS5hDa8R8o1s^@HN)SV(}g|e7jv3*d`smkxzfjHRt^|X zziz2YjQwO{_bNczz}~A+G}Lxf>@deC`D3*weLlyKd3b1!G1BMH4a=3Zu8ZycwY6qr z!*fdQ=XB!qo8k~%P|5ciHbmEA=>TjOz#Oqa>6coP-&>aMT3R-u{%jhzCCXZ;)<3Q( zO5KA7?OV(meZNOAQt1CA*5u65#~JseZ&`STr=0&iPvMcp1xn9+S+Vg=`?kaEstO2X zoS^iY6Qs_s+KBEqCH4sSPc@rq-QPKtlZ=g}N7?6=M*r_^w55{gNvAA&ze}S?FuZhq zu6U`3`lQ*bMgbmEkGVZ4I2RhF4?ay7jQSUW@cs>f9R*Np~cKaoexX_1HKx7 z(a+A!y@q6orr;iEX)sT6=yGCXVe}mhk*1pI#^^&DIe9Ds;*GpsbYo@Uk@%TGD-8e0( zP%>m0$Tn0MtTJxId7>fQdE z?~nLDEk9J|dpm{eJ-8O5RLp#$hVkzvKofii`Pi0VlDFv$PY2~uyepNDGQay%q}CjA z76!zBwS1kt8yL@MCN}YM)oPAz*)`?^gZ8vA7UUv2?>>NT74D_gEAm*!cub?Zc(SDCDQRs4{Q(6ap|Mmt;jkiTk!@bkSW$l*yw|dDPy};8;i20x&cD);K}ene^ZIRmo_UO_9G??u;^1=Q z%n`z)0fCa3+v=-M+Lhs}mc%IXj;#JqZ%mGR8&uO8efTkULG_h<6-(!Zt0gYhp-K=aF>T%!39?tl}d1*Dv?B{pUg~0H?T_42lxcyS4&pYh@ zYaA@tQ=682?y-2|n`NgVP9W@O5H>)Rp-myC0s>f4$0j%@{4R-tK|}}lgL3RCTGUpc zXV3?If=7(UoEG?qLL~2VP)T`kKak(fI^o16_4+i|*(mejD;=GI_Pll9o8R@EShh6{ zyqP4o;o9&9a_?~C{4^@r?>)lYZ~~#Nd(7y*jHkZ!vzq3(_2_jWMN--7oaAenZF<8Q zN76jJ%-kQZHG7oBc2_e=iglQ8irT%-ST?%)_HUgsr9PX{=ELrEh42e&!T^)OZraw4 zIjf=_Q_nZ11g*IaBOVbOod@$vxV3fT2}}|Dh!6(igNy)?fGQ)N#ea5_UhoZ`$B2LILM7yFu;w09 zYe2Tt-rqk#WNEzL%U7;gq3MF`+7Id;D4rE!MIxX|O0@8RaoKY6+Fw0Q1_p-8%F2Uu zbP6!hg`=_-F5LQ@p`Le2>*Mn6FvZ5z{(KKk_hg`QBWUf2Mbap~C6d|sEvjQp4Es$2 zFNr6UtOF<{jlli?VAraws9;tph<^!)@>+uP%~d<4;bN}tycZeDXZ$#dNLY^!q$(Wh z-*~cBwos(iDXefW=>K^dcfCwYY}cxt)5hxNM(N%7 z?D?y|JIOpA`Ac4BdqDDRt>5wbj*aVNxt!MzvK}C144}BJ+*6g7<@eW9WmH8xveWAV z&n83J@2~X^mMO_p(W`4Svr?WO57xx*Esr#kDJy+kbE}#h7EJALeH6hnN{H8zh7zOj zpoqQ$N(nV}b%QSFq;nTy3;sR^U&Le5!h%P+acSBm47F`87#X}Di)_);EfcT|7KGjYr5<@Y6|Em>Pz zUO=IweeQjZ09P^TxE=@)6v#Uu9li6>F;F&`H3t*dG4SCV+Is^3L`Z-GZm!p%{~Edy zhqo^1M|P5uB2zp>>_HV`fSMyq^r>ZQ@_zin=kAq-9ps$Q>0vo_#_}si3(RH;_S^Q( z==CSOem&NaNekGI5OM>TN}lTRu|Xj6;lcD^5J6X<2q7FYByfk0Vi+2{|1Tl=J4iz# zi@A~8jN4Kv0XVr&thh@#-x8g8_qYQ(qio2R;dqJB^-x18iqO>rlo%MK9I$#K5(56l z255$(3{xK-f+~I?G+T~#xPMg)>oJ4t6uFMze}VSpLE`LS=oI#iBY(Ru zqc{VmyFn=pC1s5%i1;V_f4`Vvc}XR1me<%j_QXY8U|tS<9WZIPSW z@+Cw|0+j1Bd&%ZNg0CYs9KjxdzCfJIPpWDU-Oj?o(o|$)gqZ;W@7~$1daPtoGBPT| z&=@Z6A%+{d^5pGpSpdiIXPM5lkJeVLE&sVKBYcLtCqB68oAj5Kq&lAb{a@eyQ!nxj z4)jt*_eHxo=Y7qQN~|W<=#w9hp2Vgg`yjQ3eM>beuY0UoqSY89?6CYhJqwP%YIrCz zNBw~9pgAH;scF`oWqry=Dt=Wb6LO;nrv%~6OU8X^ypdBg2eO; zVb_!iWD*b(Iz&Sg@hAG`n;Qh*32N7{K5{{;$0N>dJ$#|eWD6`*HL&lo-eP`0f>rP; zpcW~0IGO};7Zg_CupeLg2kGJ{C}lOZ-L#{IjZEw$vX9T#+T2p=x|~csX7oAOabL&! z`vzm53=)`ff0TKMOHRM`%1>gouAmc~Gg>^(O#*aJtSjg0@;yKABAX4r zf||V%Dvi#UATs~;ONx-vV`e36PL*|a`yAJt?y9L#gO7#dj9|jRB3!{o^}7^X-Y!f_ zI}HLE9L_c@d`x3d0QB7d{w+3!3OobYa8D38kikch<~Yv<2X^k->RZB=DdFY);bUV3 z={S@o_ibz{`ubu~P{ymKL%Dhquh2ph*<}<;RuW)l#M~Bz+6@lNbfXe(>d5~g_CYA? z8$Sa_jS26VVKFY>Uj~Yl1d}2NCvU!GKl+hH2opE7rgzlDZB3hyfev`Ay7ni>sBgIc zn8bA628BAG=!8e>CT2_qihFE!`kO4BC<=k;^CIe5s9O`jQ2^aAh9yF;A-enQW`Muk z$V;W*=WVm8ZL{hhWZP*;J3F<%wNOW}7EkxD?d>8J-}Sq@)Gf2Q(bpAfTqrgT>I^4& z$6G>^JvQX>lgc(0X~C95m^57ysvH3Oi(=Pomf>oUw&Eh*+`wur;GVCKOsg|pceO^-LcT-yrGg`CGUS>a0kmt$^Kcx_ZQw0 z?l<7H_acBb!O-Um$Iu~0#zyP~M0heJIQUP8v5O&gM5-&XEmeQ@X^moTt-!7`^L7{^ zGuN*@go5P~CP0jJX7$s?m7amF2B0_LY9#=Byd*BT3y~Y8p>px`E#Yv4ypVluvyo{Y z@!jJWlo|KGuajb-8X+P>%)JLIgD?tVY>X0~DdEyFDWQp2)9h1ibRId(2T?GDQc&e{ z^MZfcud1pFL;uFRtm2}g94HDg?OO&z&A;m_Ogr}%yH0BQQgpjJ=emE}?C$Eq9AF=~ zphmXO-u1YrKJaBL=e@vCSsnZ)UJjN}+TUz0OK&mZzNH$MeQ8lxaDr>Qd*3b|sZU*- zO(hF;+M|~{Ei0PRl9yKx#A_CxjqE;2g|oVXQ4x`s1#?)KRF#azP1pMt*n+|&GA6`P zt}`y;mvONm>}%RA^h1yoa~x+6ftgfEPQ+IQsHe{b$w8({0Qy4qOkHX)vxaziPp zb$mHPne$9n@{HXgjoV2-Iy12!WdY~5Hid*~`H%gPipVqD3Xs~kp-yD-dZ?R_iwIC1 z2rg=2j|rzCNXNm-kIRon1u%-co6sPkLE_j_>JQRxZC!IT5u4;SWU6;Q*gm%`+X!X4 z;@t#(ws4aJK6V+TikX?2S18b6iW1FiTII8>+mofmfB4Leu@E;8#6S79qj;K939{@3 zQqt1sa48<7r?W%(u7gG8ia{G~8R}FpilF_I##i-4@aKI*VEx*(4X+G5YT2CpmKwgF zkY)jvAe4VoZZ;T+`X7nx3ni&Ua~a728={|ix66x@LUn?(kXAyMA;v6C?`etvdb(wjAM zq}$4Hc*%Cd{&%9{F3tFh7Bh4aLOarOx*ZN5UwZPfz5LD5d}0nXug==Co30-#utjx3 zC{wT&UafjSEnS+tHaoODVJQ2kE3b{=0#iq=f8Owny4yS z|N4emDAOsqLrgiZujEU8lVO_Z>t|eIGxmE_Q(NyQ&KR(Ezt`%|n$!=QKWowRE8z-+ z@)564Y@KXjH=IxkP-?~2N;IeO95#t)8NNN1$%fp?|Q1 z1}8(~-QEWjV#^N@)Zk(V(suWJgaV}cgX7~)jphy<=~$i1Yir_v7p9|6uXOZ1Zqrws znp2tI{Ns8LnGikDPtCj*(XmlCPG}1a(Py3Zz}1h!tK__;>xXXyS#hTH~K=iy@s!AX7IeoZzk3Tp?oO!Y(`8@kJX5~4VBJ?Mi~#CTHt213@{VHsAx@Y(u;kX4fawQ}V4lyqyStB< zPWtNcMVYL)+H8t2)Oa3w?l|nYY?I5BDZM2>(cJc2`GF99v{mi3$1%l=iO#uVE`&`5 z&a^6Nu|4VzB4b-AjiFmDMs*fB{N)ojjpRZtYM%H-S**IOoKt??h+%Yfnq;)Vod{|l zSOC$L5c3r9?4g-kE$#6`k3w{==*tK^o`^XBZmzRdz==(Vu}Or05yG%+gSw-bEz&y8>V)65!BE`+m<| zjaZVIOYQ(xwVXzdAmzaNLR=7p_W~m&^e|Wx5fyZ9aj7KYpEvLzE=8OBE-`b)+k4W#~Cu^Tx z-E$b77CkQE|7luYw<+cPIg(YohdiS{J9}p&B-Mnze3-obnfcR_*?s$m;>^0EuZzP> zENQKlP$4_EQ__Z3euh+r3v-u>JZUPC>y4qlwNF15&$PLJbFIUv0&S z-TvD>_usTXKV>$naQxE%LbaAKl(_HqcpfsI&8_A$1w*=S9Ue~(kT}BCi2_PC!tNGJ z349NPdgVMi%7g@wT;P*JCEfmC4T4tQXEmGn-b&!Mb!KF3d|bA9LHQd+>pe@`ZRmu7c3O|h|8ZUGqiIb5|7Q=LzqIX+CEn7 zu3_kD^-FG{B2E+&d4JUN;lPf<_#lGy#9EFu{^Uy>J>a4>`Mg=&t88l%2lTEyA&%Vn z#KD(Vp~J-`zDv^#H< zhJNI^BW6$H;IGqg3lV*WRJH6asVr&k9SI(!&@>wYqK2-c*HC%h2QGP=l*P9B+!?5$ z>AI4QMV;5gGNn~UKc5_%4dg+Y77sj2syb&6(t|I(aAeMOWSSmZNxsvUjl^jGZTg^EALl>3x!{wWn5%(q)lZWMnIA1Ap) z*)*}AT737LTOXFDc5Qh`PPx8Z_?s*oQ?`?p>hSx!+xuOMEVUi#40|O#>V9j-%TDz~ z2g4zR9$SJ^(oRg=E^&6FB0KbiulE@B z&g0;{;Mz*a1eGBOqeg*#8_x&at@qw!TAAgKyxkr{d-QH!RHPM^A~B3%QI0 zlzo0@Jdq}>)4QWYtm%V;OS8r^|Duf_PcCG-^i((I##SA2-FYTI_ugO8$3uBc-qoUwEv46Fy-PlEb_K10Dw!$!-F_VVct+xJP=~q_JKn(hJCnU) zQ<;rL{Zm=u6oS3Fll&d(3NdtGsm6xp8%i|n&*Dkc|S#E1|zxQ)SCnZxGgQ{m!-9mAwS)wz$0|4WXYk!IX2oXsh73!8+{7JKYsLar@u0u(R zP##LO%0Fj5d8P8aLn(`ypZldsf@_`@tkK`9JWsnlK7`_1+!j4*Jsu(d6R@EWWT#4kgC z)lJT5Y$Mzhm{dv7HAJC}E}hTdYghNmvAK%~7tBC4@uf{TaS@oQ#ij%7GfyHfyt($@ z=;?w6<=i@}n9B^+kL9mU-84GRXHu7IU~lW*;kJ$fmq0RcJb0hu(0&ZH$>LfZ=79R~ zF7#T&+!&&_fgH4Zvg=pjBz(NAipRMO!Xvh6`YJK&xu}{y;wSx#9tB5WmNZ+L6S{XC zyENz%U%UE)5_6i4zbT#kmglFfJ3D9~Rn6tQde$lY?^s^To&3IBOtiqsb}kK!(K^noE;=y6ZA6OlhoD@tNmNfvlY41yH~CS+doST`Lf+& zP4JNQ$Nx@{Q2=RTNMJU=DIj~G*6;&G0i3&$*775PNZFnVj@ftMfFT581kZ-1h6`hs zMMOpY{1>{AwV&L2_w|PBDqY#~$>3dl`!93f0M)bjhH6T9QUBLBbt3u0rPTIj{PEMe zJq4UHpPwjaP&t|RN{26>JkL+mo$!ey3{m5it>1QDR1dh5|IkkF34q9XP4V(;($skTAguuOf%y?W6u<=K*GG`&h(x8cvs$6tk zp(l@-{8V5eZ0p@1iYXoQnElM9!__Q%NBM>Po>_23#XBjpHE5ozWn7aqcP{nv{fl`~bM5(! zyR||T)ctb*vp1izY)YnpGwvadQ>h;lhA{c#4D? z4^3bSo&p$`nqSqr8-=*<=Dg9KbzUkBem>mj6wTUxg&BumOZ`g_ju@coAP$Fvq`E$z zvi7f2>liOnRnhVNH+zIy^RKvU-+mO8oXYh$1CLnSxDbvj6U59%0#d;68^Se-Z*9SL zBTjoO$>M7;=fm{eN({UqW)NWseq5ic1I*lnxkoq|LO8Em!RMEv;QZ*l0~s3B*-U_iqL#B!M{(qL4br0PEBRDv{z|jCJ|v$ z0Ad1-l_aL_jrWxZ16HjMqUs?AY)#!f5@&Cv(6Muz$)sTEKi;vyPor_lx|l!re+xME zkL-znVDs3h#CW;Nw{|q9dUd6)j~K+{u;2asgU8bvzkcA(ZIoMjy$}i~C2)^&3^MM@ zHP{D%H8GJCDtyB6Vm(|l%c7;)q7KsmoG!#HD$G}d@sa>sV6II>G*x$Y4a3lHBvRMz zl1kqt9;p<{9MKZ#D7AueAs*}Jha!J1UBhK(!*z`lDJ4J^U@F;bLVa%9_6+!W+Q$M) zfRBTO69mBk2DQL*xA}wR85eD80Qaf2+!OA~hp1;?xFFZY0dB=xz zx-;hVmI8A}W`ClJx(adP?{fWmkXL%}scUV-yH?NJrS*r55Z8y?(&7^GSG*P%a)G+t zNHpj5f)c(~ZslYz#(R-~yiG>DAYKKqhu^zn6o!%1;BI<~Cr^3kkOUq9$n`|Q z>2o0GUt`rn@%U-%+1wT&Fi3L^z<5sf6b4}C`wKh*f=3}9!FW>GpB&(_=(^hoyvZ7!N5qPr0qHQ zCj3frT4V0HhtY{c?u;kwBeN)@Ux2?syu>7|y+CS{%)4`i@go#1qWXtso_)=n5ZjC zu>oNU>u#g}>C*pOt;WXiU z;&hnsURh-)esJzC(-qqX;WClo^-Zr+s8Tq^zIeWp9R3#3IwqsuM>xc=1_`(nqGyE8 z;1@5Tr`(l_w?KS7ZXREM6o_HM(07r%?r$h81+4~mqERI-0C)=qm|aFyVggQ_NVB*A zaKvB7-amQf?fp8^$l$kXQKffQke@%Zo(+?dGov$}7t7-0<>U=b_2saEBNh}F$t(H!-8j9HmjyjMUy0JM!3aXRGl zMFMWGQy2k?2@~;HH2~=%;jMz0$kcXH;WQUlAehZL;GM+LsQ}~zaQT2cNuY4^B``SP zb1g97W9dN=&Mok67Sj>O`ZmsWxbEP*!1XV#i|?y)9g@-c$pKOm-DI&XUNI72HM)X5 zK@ch?`H4+8?p; zJmOE*ar}zFwOg;OY1y=#N`&3r`;XICzfEnF6EEm9GI;ZPLF=t{nUajmZVWFbhO#0Z z5lt98;Uq*LL^>xP0s@N4M@K76&r^U`J$Iec0>1zY#V~Ra)ILvYYHD7JgKd|_!WRTDA3TGcDi--7d(g5Hv=-i7a)uY=+!sLn&mDpNiA2^ z=cRO&eMz$K$E8_=So!tht7scuo@#xtK+89=TbA}dHa_GIUkN(9BL%5^08&t}7$iSI z5d%UYMnK^8u)*^~%(TEp4g`1j5<`Z`AVlCQ|s|1A2$TDoF*6jlX1 zLK;Mnp|xF`bQ&?2x%Shbuxr*B<8C8JGGm;a&}=m<)@Ed|Ay&ug(?LckY+!U4M6$y& zV;xC-dD}xA5IVp#2hr;8Zov`x1h9M<_4>ZJm~cX(bit|9WcUI67rNXL_)E2BBVtoo z`VGvAD4p2E&;!`uxuWXvy5a7xLwFm8=%gc< zCY43|A0MF;3x=w zTsr~v6WhaXEK{6Q^TTC5y+O@J_^6oSIVNTlK<0Yq&K*KSfRRjyO@zWRchlC&swh1i zBQ)NdF>^swlSHy>B25kXizLIP%raBlGE*K_WaOR_Gfh*zsOhg^JVr{8-F(GBn;7fL zPniqGIeK4C-F$Nx%GvSFy!>NC>yV~Nf2@wnoCZ6dIB=g}KZ;pUuR3LZmOL^h|(zw>gRoV}HwjO2Jn&c}VC zCiHe#csMmUiTBP6XYe5LWUT=rq7swEkO5r%NF9S(**ZYXskbAe-y-JUdJ-;Ie~e5A z-j9digO?iwM9BKrH(5k#jE54&7AD5h6MKCmHU72>$L0p(r557wWT!tx$*!Vb6{ZjT ztL5rCF2RZnwW2hNGBaDc+W)Yn)*6NWcJz%y+6Rig4oQc&GAx?Y6RO#7pHBbSEiWVU z-YlWHynH}BrP#^Qk=PMfI}i$i7ZAbmsmum$70hJG zkLq-4feJ;3{(V0ZcP+=f1&4yM;?Bc~|HLlzvVwG0=8I_XHyHpiBNh4)6HfZ)}WeK%xOqD7`EruWjRgw@L zD9Rt9*9yaw^>@fOsv~gB5l^G&QZ$hqg{S}idTL;^M>F{HK!)A6#~g=~$h8>Z6tsE5du{va;=oNR4VYC2WtkbK^BfKH74IlZUAMjjZo z8yTx_o#}Tobzi2sJj|g>c{M$Td3rxX1E!7n`rqYo-&nXs4Co)^JZo!gV0)Z$Xx(kw zn|!<1x0gzxiAQI~^w3*1=PqbC97^!i&*m&|x*2}0hvzqYxJct;s9FZb$4zYMC~I|) ztiv=42W7^NK2&8L)b%iW@?0czd1q=*^PZH+knVRbj13J9QqsA5h`!1+#9N42ai{Ty zKeM#bv6I6(;hM3p&jrz#yxE>3k75H@$P3+)8@b*h-t=n&Djrl&THUNYqnAR=SmL|) zy=HOO(U1(L0G%;?l(52iTc5Z?GE8RrTy{J!v7!{$4$08#|CRAzLHHYHu3bHuF2nko zS>wx}%Ia#BLM6r6Yog2lrv-@qCf&W_#>Dac?Gf4F^k(dNb{Dbg?{S?7IKKWYOf-`) zv!PKT>vxy+o%vTEsF&@~n%uu_+ddfPfH9d@flNWTJ6TtnKO-fN(wus9(kXQ{mr8Vt z{~0RXA9#$`WO#87eJ+*<^U7k%HyMLYYqy|jC`cJPNM^rN-AJk-PCHNeSr-O1P{S-Q zbtyo_JR+=;o~qSb2C|o(?OJxp*IL8C;S~|zh=h}>k;JsWgkx@FR4DT1WZ0MOoQw9u zjq@jW?>*2ivWF?c_sM~S#knYdlNHyzSK>5?hxyPltYU8AD4)4nV$jV>B^=xSV1867 zM>kncH84L{?dMdW|NEk2gFTj`)TrNqc9GnxlH#&^B&V8V=`OE3q{P!x;Fc0}lZEPf z^BMagR1&rx={%PCyvE!&VaHod`HP>ntGe#mHTSQ?@rZdGuPwlBJ4S}_v7d;iM{!)};^f0G zdhr%f9gpa`F4qLe4maCp%0yPOT`b{`xqm;i@@?OyLo(Vy*UvCWWJbU!ON2fDPCCdIQAPNqMj=Z>nko%sG-!f9w(FPwOg z-X(jc$b@02R|Fn)4=qAV;k2+?P}ceXd63$i56_iF!3-aWUsh1KlCJLrhS_y_;Jnx$ zv*gmkf0?!_rbC4uK%6WJH(!5dCQ@ol<44RLUP>~|ohXixiQFHlGkE6)U&q!5YU%y= zqD=`Bsx~MoBj)je(1XQ`Ml8O|El>%GC8F2F?FEuGHEjz@BJh*%?>^RsOzkXlOOX}6 z-12+SfB>c%`AjS3M%YoeGm&=vZ?D$QZa-tWP_Y6_uuAh8_3y&dA2A|3u9@qyxkl|FWy-^Ja=^^| z{F$(`P%B{w_AF|38u}}h$s5xiqO(hJ7PjP3EjWJ(IEA4td7wghcXuEWXr?k%c&~5^ zAIS_dfHDf2-{T2)pLK~q8-mJ1FNG-I2r~t~s1ItBXP6+@%w;YGB?oMtdCgq0;e=P0 z@GF6H#|xDNV^rA~8RIy>J{S%!LVm#EA)zsg3_A;(-81wx|r{ zD#igfeR{+cq;W>v!5_*44^nKzu*+V3;@dYCUajF-lQ^}l3Gd}V^A0caGm`9AfMWI)XFi&{diNhYM zt6@HOI}+w%bN@bJ;=&jVF4!Z95pVd-rx@CcQ=g=&sRExir4&E=_eVzPJEW|AeSHL^ zi_wI*Mo-XlsK=zFss3MGUjohb)<#W2g;Yu;+>oJU9tv?wnMDuG5}6(nRr8=ryvA`Ugg zenrLSNLb54xKbiP9lHgZsPS4_chdOWWo(0Euz8n1m+WfCIyN2k040j zc%b!cZ0dmVfE@2drY0s6di%@1gD;mprIh=_ffIqXa92@AB?%KT6EvnsMb=Sxi&WHj zgRB0oXx#y(Q+EP1c$u*Hu+t7l=Ncnmlp&%Hh6WBkCwNQAHu_XcAALI}koR3+WdY1v zus9n~?_s%ErEFOMYMh4f6t61T;O}R1>}NWqYViQj2Q)FI(1jBK5*pmcu$snksQ6~Z z<)r-gTf195*_pfv_Tmzd#1m{Cc0pvM3Nee1^qjZ8AhA9(>dCRCjo57@QTw3r1@w%U z`}*+)p0?h#4TlPUuHp&fk)g9<;tT$fXt;cOa+5;y{he>}9ABoI~iP#arVUjTMP|&cjA9^4A_Z(zCzVqt9Py_JNt5>fEW7@!? zyC~+F{5>>{JPE2x?~bRU{=f;Ysa_nyUpCWRS3t9r@V5r>k)z*3dK_ z%rw#iAz>4(R6?UdImXA&Uy7Y~6Zyi@%aGcK(`7CM7cEQFr36JJ_CWAoN0Vp<=J!5+ zyr!!*B`p1L;B)III|C{c00|Pf4BZccX%NG0BxR^4LlG>*?l-9X`DttX^!k=svQqK#TED|SWw2!U}@vggV{#%dnN{INJZBcaZ2 zxh6>$hIccZGdrZn`4FK9JrDnT_q1tZHgKb}EDBK<^bLoALIb5VL-c6Q=aSM?q+N=4 zDmUv6oS1wLXcZC!`4LeRQ$#km-G;fZyZbs`CGbjPNGc#eiNJg80;3314P_!qxseVm ztrIJPU{l5l>NRLDcF_hUknYAzZy0N^nol<-(_s7u`MQXos5u^jVL8%bpUcXAs5@YJ zdj{~SF`X*gg`nTFkDCR^@O=Od7RFp<^bxM#1z^s++j-<4&@*Bon;{nudgoaCm^;hM zd_B9Ct{whh!1_c(G+4vc#Jtf!_=$=< z8GS~;IwO;lu^<9~ep`*DfBr-=Z0Y^PWMbEM{rGW+__-sz;^bjhok?Mn?Stnw5)XGi{g$rre(;OS4c(KPzLA! z^Ndai@uNanPmGv=43LRZShT-Oo`%>z`UY`M37sX%a~CeeAkNb8Z7?9$3e2TQ=!1MK z4%Y!ar+hdhj%@6Q27{NETy+!PV}DU?Z2-OlN;{FTs>PYzJ3s9+%Llf8h%gFW+RP^o*^`Z&>D+GyKSVH&7QV2Y$@I_YzGo05zR zO_q^kjBH(Cn-!ZFXu0mw7D zCG%s!FaReu!ziyc5C=mrE3?@6(2ce1t;T(mlGo$ac#P~w;R5qPtB;@V4E%iBG^ISU zS0SuU9U~R+Uvyzm41mG_behCK=fM7(d~c{d=ugwIbXS%YfSo~vh{P8Tz%=&8=&M=D z+E3A8k~Yi=zmo#JG>;K{qPBh;|CcKVy&o#n25!RXAW0JOz=0lWDA=#@ z_a9XLlhv9ZMXsGS*=&QJt}sF_C8SQpfQQRM#N&A1xzZEh^~JGAQ}2qz?H(_dgMM=# z#&rVHn@k#kfH-^PSyy;6z1iX($hh73Bh+QE6XTZd(p`$ z7O4ude&X9lDCn*3Q>PxuhtUu$F+rP&Z|tbkF17bfW#0~PrT3hX&~YmY*cvzJi%~aZ*ZmvK!F`mK9!V+a-}^PW|lUTQTCvg9M+9+dyqt zkIWy}lV?qdC)%@whJh>6{G3)Y^>SoM2}YpDq&T-W2iiyB;Y6#9lULDho^Fql{+A;^I$`iRsOxDqfooOpxduIB~m=KcEv6bMM*n#V21x1h@Xf35-* zW)MF-i9r$abI~x)lPlqMt_6b&c(qAZ8}C4vY0etwGP&ik-T5>Zp?~q18gw!}ZVfxU z`^|CF&qMCecC)beN6pXlaS~@Jw0i`Ma^#Q}%+*-FgdZvKhQoQv+9$AGytY|qF+<^@ z!@@pBA__oVF3mjq*g10e@st(^UVB|9Jc{?IN-&oJizz&8HM;cJI;49fdI{ zCFz~MIG&(}1Pj%n81jLq2<|t{)3-wd*BR}9v#X^>W3TWcJi%~9M3SPnW-1y}CJ8iFky*R7^a#-6=566p7I^9M*3JsdE20^MN}^c?`?M zr-v?<#yWP1`6i{VV`Aj6`)_CFM9rYT%W=C80{q8w@K27n#M;S10$NB2xsiUpFqFDsz_O4v9G` zp_TKT8^=XtZpf*+_wCdDUC81Pd0?rpb0_($7{A$bF6)3HtaaSFkv79b7e$Yq2r09$$@$3P(A5fxpJ_98jM2*uVgTPKtS zh?kX0s@MIA-#o{3(wZ6Fg!QW|#CL^C_l%c)U74W4qug9g!JOq0psg^_i!Xc9TQxUh!H%`GRu z>t{R(jdD=eh)GXmR$WVb0hq)H>Bqo#RY zl!R)9#EOkwR2%KdXnZLmp-ehla1jMHe08eOm4&km55|-{#uc75H`xO0qqY6Lzw)2T zPvwQxH;P%4L`7P%r@yxz6F9azaAICHSVM_#L-H=m8pYQq9y#~CepMN<7nJ9IAslSP z?2h5#8i?7@Bqi!5qNWoTP84(-AG&9ntV{asKxKF0s_OwJLMGut5Qe|ooMM@gt-aq10bCi~W;3Z3TXF%qyrKo(>6|zy(Td7Jv`oJ(CeQiCLp-@VljC^ny%69m?_SfO-XPbm|1ChhA=KWhpH+9( z;8(G0oy^+w-iYahTGhdNUtL0?Mo<$+!3+&RI=+ZD#=;Q<34K~Zu|<}gqIR4L&_G?9 zwKgE}LIi)3ACce&;0+UVqPxD{TdvBI4ZtYk<+oDsme(w(3Ub>RxAnj16<_2QO1-DM zXrFb3_=Sj-1`2!_oA7bjy zSTqAi0IdD&4YMa-fH*P$3@#1Y6;@k27=b{0C{)4(;TlfDk1zpO3(P|(NNp~pEhK$i zpj^yHxVZdH0GIc9=#I#Oz_Q_{3O3s2A)7uvoVhunxR zk-@9fQHf8ycyuD^97AQq7(3bpqB7Oo2054a!0wm0t3$hY4ftG3x6hQ`BiMaI@WhLh zhZyYQq9@ia(Pm%&2Z}yIGpFvUBW<&U_$2yihFXujPLQmL7Nl+0myl~?I^W=RVz%(pw~x8inO#wZ#-+WhtK7aU%ssfg zW^&i94F|Vn?xgRhtUe5;e!jxP_-{2T(`_Y(iF6dyxGn5`0k}{|V-3xrJUZblFMwWX zVEEJ~cW)!BHBszP~9MU-%T0TL$ z8m}hSN{b}(lFlOq&96hNj4AK+a|PSAj`cf8C*0`v5*o2Pp*u=#ku(q<-OS<^RRW>=4e0(DwpY&br3@8jdZsnMDB%Fw^u%Gjr_|>eJ zbVfXlZ6%-d)3bXr@WT~x`vX=q^w7^i#TYwuF(~2IcB8!D`H|N59~YQT=9;h{e(d`6 zqXOSf6}6i}h2i|ivn1~Ex?5ZbSB43`1~~(m0?&DQgi<(X`blj74+HWyg6;!@B+wf% zXhY!?$gR9q(Xs#bA1pq3C)(?RM)Oo{?xBnQe3t{fw1TfT<#p1iGOMH+i}n?m3VCgR zOA!=vRX6Zd-bT;1gSHD)Pt1(1giHI^F4)k%b!^S?B$BulKHsT0_B{Sd*FHxts6RUb zSHJ@C(~nQCex}2`Md#M#w;eqe>n;}Q9~o+7?2B$!bk|lZ!pQhvN_1H!rM1W z{~&)bBh94@=8}xol0w6{eHWkoSiMQTP-fxd9212`C_~O%LZY>1@nr_uf~~q~&csO% z8MnB1Q2|O*Vm=DnnkQ<<*^c9Ek@21|MRe(TaN;&pRF;NH%b+-GZ}FjlgYWrK_xH_h z8y1a!c*EkN@8K~PjV6)phWYo;ZPDJ(!}F-<{)Hm_cf29_=c(?EMao(6U-1;uS6A1UuIKe4ulv;}yybf(Dsu9#f}{Gn5TlpT5jUTyU&)z5goH;8*Ti-I7~h z9oOY>Onj?II(Q;FYCyy?!oKz@9E@0Sl8I>@8EA`UmR5${uODZTl1D-N0Hj{_Yf#8~ z`0^3UaA=_dYL9ZLqbo+nPGYvW$awajTqS^y_ZRQ<*((pTIwqP&_DfpzTW8M)N>AG- z%kxUkv(R2Fmv73_EC{6hkg8go-TFz_=DER{b(Oy)y9_@w6Y#F9q;PsZ^?jyaUFC+# zSGpVa=7oDHrmqs&zIR-}_l$l;X^n+}|8#inn(BjJb8<}%@$0WEu1Vowe|Mf~$hdjc9zi)#Q= z6(5|KPt11nuSuTo+CATFYvv>pUna_{Bz8S~gI4!_#U7D9#kKYOx`RW_1oTx_JJJW- zxv%}CWk$o)&oRAMq$R1T!D4FIzd~wOwM9ZGb!zPA8_vw(fsyRi&tId{{D&uIXlQB4 zeM=@P;P>f)xf$zw3Whd>w?j_cQ}zB}*9D4aAC}N{#>&ng?fsNrW8>^t&;8&X52n<7 z%T}V&t9NPLmSfioT&fO_TIoSagEj0N@V7hq?oE@mSfu3qYE1oT_{k%c-al~kTQHr+ z@A7YNe|6I-QPyQjNDNS2vGEOBu`^eaW0UYW7uc2x?(V}klJa)_PUY`$8AMkwZ&{6x1-urVQw29n{CpoWp$LZm4hK7@!wXt zk(qzHSllwlPsNq9S$kUM_dTvSvTD`J7E2$gm9J%E1_r7}Ed;M{9ybWdHC|7>#=I`A z_tqd@eK%5gTt5ox%y&6ynRqow&KeK1WT1H))~(A!r6Yd!H&RJc8=DG}gj<_gT=)HS zCi_w$^WvQo&?3l82VkMAPG{uYq1oyB6YYtso*mor!kzxn8O62}KJIPy*MyI=rs`yD zy~Z{3c$(>wfAZYQtW6Ys1&=+=bjSGU?M*6gQt#$ilWmzFp?#!)ig!A1XV37X=WUln ztQoStQdHl}zxmI%nGNGEtok0SqXOF7C}loN`6)23$+jpMx~G)y?8^A;=#H)~vP5qR zTI-AVX8#tf9HO>+TYu@%r7ZT@!N$hkM2B5(Pss`yC8K()_Xbjx@fWuRP9aMu3P7NB>fExZG z1`X(fOl`GC5d$-}I*{?nNE}#gL5IppIvN;ph#5a!0|ON=6LUi4=8?7rmMpYiW8{Yd z;AROcaBoZ|>cH{=2Ri!p{AqajT}@4OeD|sz_Gw7Kh%^LWq@=A);cFX7#QI^~hLy@} z^Q6BNB5Fnho*Al5+@XFNY|?urqLv{|4a+Ne)>zwZAOY6m(TI=oL*>K{lPiwXlb@c5r1CJBz5@P^TQfUvIXrHNxc-8 z8<;0OP1A&@FHqb5UX}BMhEq_5HMh+9nbBIILpSzSwO6SYPx|=WGw&B-8K&aPy*|Rv zk|r|udFC`Hy%jwz#>kuth^adBx-P-Sa`0@T_}T8R6Xw+a2q~odZQGGjPPIOg;s=h+->HfRYu;T-ORhN0nEdlnWNttIm)oLi{Dt1OC%6iT z|4S*w3DKj+#|F`@r(hRjV>e37L%h$cDrZXJ5tje#w>Num?>^x5q z90qh#opyQW+~%{Fu`sn%bvoL(`+(d>_2&C?eV@BJ9ddJhSVpN=Qui6>7jRf0@>RFdON{WAdEzgOol&U>~0>qQ6M&%TZQwWvmFNsK{uui zqF7EvrQAKMG9ZJ45C-1&a z@k>#QRm|wW-A-QLcAqP^7G$ZP+T`phpO!!={NUPkgJOqThxYKXp)p17ZMk%fZ9hM@ z-Ln%I7QTKhlWzByp9Y6IvWh3ux*gSAhK(PN?y-)~W%6-&Vw(TT?7O38YjTc~Yq6@< zKbqyUSM7?qjB6eGGY`A!OO}3J%P#XCBju+Xr2|4AR308{Z)`lccicwbUv6AoUdMlS z?&;@5gN}-~A~p>=5EE4TjYY!Xu@g;W^q!k(;|lQ(V7PWj@|rk0-DShVFd2fmRZ@ng zo=Xjg7CTSO_au9_oIIsHA8l`G`S3Ts8g6IeMTBJ%&K}o#;i$NOznH|~z$_Q-EpC{a z<`10<8T$5W;ERi$E1|_>i~FKkA_m(q^l&i{!Q^JK3gO6uffpiU;rjO$Jr{5v^PvwaWYcpqW8k9^JH=@S>61PZ zcV8?F7m2lZu8Lf+t(*=|T`gp&-ei>N`5J_magE zjJH_4UFRGo=Zg(;Hm^P9Rq;9B^MPpU)V`C-^mD(mOJ*GND;MOh+{$7u=kEIGV%0!9 zdWKiOR zb7P3JC$BpHk#+rwO22yoWX{fo3m0CL^eoUpy0Vp>eFo$y*an(_4v*_8t{E*Q4;X{j z;L0NC1kqTbmr6tf^kni2rqw`4)ArdJ8>ts%JaEC0LPiCi8sng| zzM#brnFmIG5Gw$H^ijY@ryk6-fzEaV4LY&DFq0Ge^$hu|(Jw0x2YIM_ z-WV!0sS~l%-`qKWbNF~(@bi%Yjb}$i&AL7fuaRZUJ5d;A^YY`YEB&pwNVSmsUkj0` z_sZJxXS-~5b3Ld4d`ik5jwNgYbiawtI8;)+&%T>P7vvHIK;NaG22u(Yk?5eYKnC#= z0t*O?gv5hh1=i^n+`3vFv(U>Iv8>)ofl=c`7LK9r6vh~(465y|vKyUdBruDz8J>Yf) z!oz!ri9tV(0u~0kM<5g!^qvb-=V5kB;ysAVpdExr+5HVL{pS^KH1OE0WuY@{YGe_A zO0kvwu}N>dDp!c$&dvIWW6#=8`2|hbi!o$(WgGHc}u_MYxc13ln+<$pyp$B z^=B=srG{=^Ol|LJNloyNywb{TTtgg~lyayJeUHf=ZnXZ^Lz~HX)$(Yt{Enyp$b96q z5TrCPVEM@2I!wRk{O_?zgF8p!Iq3UW&&fQkZmVEiyY&XUcT`)Ph&9Lf#FeqlCUZ{C zucZVh`99h9a`TzI|7>he8z-FCaN~K2PSmG$8|ja=Rpz&E<3vVb=@hPU4B9sICc$}4 zYdYFZ848jS`Ul80xW0%uimfkydq^R|xO%bE5%sKk* z%X`mrlR_ygbcAT-IrFaTo#W-1$jMU`xN(%CLhjiS-k!0xpC8_A{`iVMDy$>3=JCRt z@gFvIY~Me7sT-IaVRTN7Om_bqnRI#Y)_Ll~@mJVseU8&iHRnjL5;}F`^Y^dr_KDdm zWf!iG*oZjr(+^R;lr9XO@?p(1n96^5_Ib_fRo5pEMJb9mrnm8Dshvr7Xczww(HHTu z05E+Ow9FXzR0h0DLyt$5!w)=t!dr(CEQf2rrZkqIrDwZo+q^L5G;sA+Sl2$6FT=wg zz;n^=$ZXJmgN-dObvit@c z{1PylNZmvvK29_&t;5RL=m^|;)u5YQ)Sutj7|*p++jrYwSn)N~%AuJ<{Ns5CeInsO9A zx$=^9^nanX?nkBbhnhaNXhw*;#`|%ux>l_CFzQ1W14|2Igj;W9hT9jRSi?2q`s=>* z*By)ARK_%;mEMyZ&6s9(*o^sXU}OW^joz5bvs?1BBHQcd+l?27+YUMC!rqy*YIVIKR7~QBF9J`p%9H6E&LGYnRy9 z0fM`B?6^BApYUA!)3+Z2&-eDP9lm(=M;lvF>9rEyA8RMqF@>E!se7P&_KD_x-561( z@r9?ag>%_-{bM|`FJ+dTc^IS=b?K{yZYpcesSCqD9#pW3pYWWY8yfiiJG0hJ%3fyn zV9m)j+PSo0Da8XXXNu=|t3s=W_6zOn+varPNAnFN=OOHUS6;yJ1YSMcjNB(S!8u2L zc4gTHGzsAo5RKk$+S!(dw5@*@;{s^Sr`VE6~^Q%Czz}`|Pd*C3&36`7Z;G1|PDC4BM#@Zt3GT z&7)&uww38kgYKIh-(wwq#IQb_Y92CXH1ee9j?KHY)5jw|>V!{3YFna&YiexC4exV% z*K{&I-RRN9xUWi0Y1V5{NOZjnW7WQhtQ%l6rC=%6C@3f(09TVnK!$x}lS8)xG0uZo z&=bfyiIL7n!83n&6mu#Jl|O{Uc}2>dx#MXSLoa<;^T{H^T3&kK@AGwinhP+*Z;@TFEsp zBn#^ZQW+MROzn&2XJeq#q?Z(arj=@!a0s@ zku}#3xfzf3auOwqY_+0^nOPy=2SrRJ1xu z5|aKvC|-w#{=1kdq^yL}8EvUI5}V}eX5PFqKa`W&aqi?H!LamD_8y~0^6sH(n=0zx z&K%-ps83AiVtp;W>P&j->B>e2j2!zgxSR15I^95)$sI~23&Mze@W-b#>77aX350YA zi2$lVLTQH+gGGtf0L3CQvcAj}*^Je2{Y@_Fd5e>toAeHf?U13lOw+6#ZE=W(p2gT{ zt9D~^vltA=h?@ggt=~Sq+zb}Elx$E;2c!U|xShcZhx?H(e(#jZM!kJE{y^PjSC#y> zmd($(>Ft)6p9#3QUNtu-+ICg$(EEZL-pN(HRlc}#%h4!-;WIJx>jj8_vD-2~n0lh_ z`ukgAjtkBSB%RJ=h8-&6D!&J6lk?JlXxu5`IOt>jagpr`yVu(br`F##->cq`mlgSs zaqm``x0*YJD-+8Q;Am#xUfX_o14kE5Laej3jc=+=$p-rd`59PtW+0D1$9x?WQ!=qL zHTvtpzt14X#m(K{7`2PRC@Jca!QwCJ6W*V=-f8;RB$*;%QR31~NP@7t*=l5DMCQ*R zgV0O24O#Pw7hb)_XxNdb0ERq*7T)>a(+;p`yK?Q?wWgo*0c)12&!@p^zc>A6XXV^D zvy_xY-1;*84R-rlD4jM6>RkQV#TN{)mIw*tXS$h?Ts+A7poQlG5pIX)+{DACpB!#r z2wa}}dI^O)A?6YHgmZAlj0KAUa?(n_sl>s`wM%>^u0RfAu3HxPZv&04Lye8omVkK6 zap@%K(wmQDAIgb&)9x*Yd^YdT^chfRFM}^iBmpxTJ7VwoB!<2wps2?E4qb7l%7A7XT&>);pZvgg#Q@;Av|*xBC@u&>@2= zzZL&Nv@iMMM3Gbne+zSQm$AJQS3vysQ5qdv>l*Q%f#ma_w%C5W)TNLKEC6z$)7UP= ztOi*>897AW1`uNiP^D!%xdmYEf*x=(a21d%%J3M3O96pH6#gygI1k=lxTE%Csrfjn z!UpXKx*`_#?YnUHh7=sO;8Z9fy~^ru3L%f=$^I($EH7OrtW|VQ1D0b zUd3$UHzjT$yUx`@=mr2-z0_VeYyo4Z@RC3rA+X1V$X~!U2smWqIrjjW&IXiDh&u3F z>I<=q$Va6a7wHj-kdA~{C^g#h1x_v*vrI+{qvS#_JY44DT{NeEVvgxpr?;?}dFeWW zbVJZy={NiDayicBAA^kg13IFH_QvWDgED|>2KKCsyf#(RBx;;DOL%1#C1qr{Edr6D zl2q*w!a)1^0Bj0yJDCYR8e0Q%lb>4EK7oBa40TlzPVN~&mCD;zlta?zcS*cknqo^6_y5rr$(@fszVmD5#r$gC!2W0*^G#*X zrdL`ie2CC`S}tNy$%0*M0LU{6^)|6@b!h<}Hx2SB#A;;TM2TrK8K8x{nUWAQ03Lx> zb5Fr@UPl;8_wYxL;8IagTPv!aT3l4Lo}K*=?vjp<4pLvj8w2#UK+l_CC^0kBcww>& zI?v>-<0~FTivYyxe=(2%DmUd=i;5jOORB5@`hHQW^WUZKlr+z$9*IeN%L=pn%JO3` zn?y>~40q-52AUM+Tz}lYb?|Ejs$bgFu2S|ui{$h(pLVzyz$(JBCW5%)&peQ@AqLch z91CWlP8Ti(*yjSw6~`;Zyzlnz?)zVEVKQuZV+)&ag8kQb2Z7X#zQvZ&O*p>fj6j0> z+Ye#y^Ybb3wCEM95$+d=J7lT_hTGzJ+}*HU?LT-)&`wC6R{hn+y?9HhZpOFx&8AO%6QlgM)+o7_301 zk^@IuaMpmQCa@nkN1X@Kr;`YP4$FziSyrNa@Zk2%nvUJ2S6gEv{@Cx?%$XLsa1infIwjyo<_zO?VT@dXvL}6!ztOc76Q~%qvJPNXJm3L|3(}q7>3DXzACBu=GCcEr=ayOm}Bg-tM!sjZk%z3VS zQM$vFYdNyKmjJuFsAibEcv3wkG^5G-KuW}?FyrrBJIDGo;||=}KpwQ=qs&tBb3g+- zy~^=Hxwgpg9;wQl8wm+bcMhZksh^12Pv^Ep@@&aqlVcTPzz=JsKgTfmiM^3gL1IMT z6vbl7f;5!A{7S0LKHfvW%JG<2|32kaEWU_+t6Y%gmHixx5w5sqMTHRN*@{Bii0`rf zUr$T^rEtvn37#7LpHgMr-EEzJY+tT z(_Qm&Nnwc!>7Bv#g9orix9$xJ=s%$u@R(&cnE1NR#r$tzVRt``{DRO&tIJHobIG> Sl~dr4>cPVYUhOx&`hNg_r*)P9 diff --git a/docs/images/graphs/vscode1.png b/docs/images/graphs/vscode1.png deleted file mode 100644 index dad68acd7426f6f2033bfa78a427f28c5407506f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10048 zcmeIYWl$Vn6el_fAq0YkAi*=ZyIT_66JT%&?(QCv0E35M!Gk*k3^oj|!3LMX-QAs? z|L%U+dbJOOVu(cd|B!au9Z;b4(r0RR9T1$k+80N`0FYQOyIIqF_p zBFKn(pt*fg(0ujk)!d5OGU}DoT}H=U!^zU!%f!_J;9%lz!R}_}YGL8%X6@wuFX>nj z0H6UVNPpDyPCr-(GSIkcmOQQ(&ZNmCRl)xrMf2kRnU*?h!t0#p?3Ja;BGWVn9~sB!e^Glsq7|n=daF=j~hG>X6p^H z0N(3jV}0lVE?+P&03WmK9RU1d6&oP^+~p+z7%YSai2IQK?3+9d0`P$j-wHtU=Kuff z|BC|Y>I$n=lRYGSOS%rZywp^UbBWKxMqcYrRX~OgWTp0QHqVkp9q?9)0LPSqE4LSW zXiLMH{Q4bH@P3AibT}8!J!TNPl(hMpC}gSfa=uZ8kP+shQP`Is)15RmY-gvMZnM?v zfsKb3Yd2jHUH=n6qgPRy(f2@`705E5Oq+JmzthvhYc*_qScAkUqcK^R_~^D78j3i< zQ#;1PEPhyDOPx|prlbb6tQlyCnl%xZUALR^TkY9bJm!@wj(9B9TI`}LWkp~m@M?9g zJlyR!;x*?z2&+Td2dv>_WHP>3eZ?W-N+0mvmi= zkh>K|O|IR~@p^7}005zd8S}}=WKJ!(Zkpty{!I#8MGoQg@mx}zV7+^xco%tt7_gFn zR5x!C9jH-pGLTj_Gk8|O=J>C-8 z`cTso3a6OHikeJuk6q=xL=M?QaJk1;Xe+ez=cwGCmAshwbIC<$C4(7Ug=f-Dq{Irq6}T458?#2*Xz}1XQm!Zf%^z2Fb#l597dSm%{kP~b zE@I96RC__pJ^$8mKI9pIG$32L?U!hp8zXi0=U<$>V-W63*-L6Y(xPQWddLNc6S z?nfTk9YMJr!DYhI75_+|Yqwxc-URbjlfyQ%5y02`^zDl38lzn-JP<}n%G5I-h75uh zf8C#{@xO*<18+`2N?SuzcU^ts1;fV|UtAyKhVyQxgU(k*r{MhD;UXi+xfPuHF4`yu zXb%^H8Vh?MC>ou$w#z!pttdboma^-+pq0$1k-*)N-Y_+szz@07yYDD2&R0j?z1F_} z*L?3pEhzd%g$(}<6QkQfN;ah}0ARK6dr&%ndNZ0h%^QPb0;Dd-Kp2Z{_&d3#3Z%s7+s=j%}mvy1+XClg3F zcD>FSIfUshA%HZ_ZVPF?{!EQ6Mvrv+Jw34c zEJM&y2Ofri_IdGT6$#(pgt(|uMG2vOBY+7Y4wsuY2QxQH9~YxOLjNvt8N*B)+z$t! z+8K>0n5fiE>&t{!RcR!yA9P{=&^f~oXcKQ(MS+<%TEPFSiG4L&Ec(&}1t+fSA_0Kd z^q_x2od(YUTohz!|97l#g6Cs#mZ{^R`Lk?Ae!QqqcZ;v8G(KmmsPI>9bN=C4HQEJ3 zFqjlH=*FDQBeh|yl-3w7Pf*7|uV_=TXvoo(&v6llyNJ1@4r})GO?7NHACJq(zwpAV zh-iU-Cdw$#Z>#gy)O1m$0lH4_23Bh>fV2%X9a2+%wU}}Uehr)6Q;LlFlYaXJ;C}^X zMXU#ZvDpz>YDyPZ=|I!AoWK8R5@YENlxB)EhP4uJ&D#i*N zfwBbELd@;;-3<^$u(IMGQFk>DE3CAKWCr?@RE}iaC|-->g^-x(^Sp@aGZtm(_z9D6 zOg%#58^>CtDBpW-%Ma;sJ6c4m*k8-2Ow+~h_Mzj2YDYnHi;FFOSBGIP+Jo%s4M+RY&1m9hg2bCrzD`ydl}<^KD)9?Ej7AEGlcZ4ev#;Q=NiPAHRq1?n z1!+(Cf@3{lTv%9dS2$iPkM-DAtDbd4U!TfU<&`0~ZB-Jz-35G(g#%0advQVK@vm@F z51pD#34Khh(r(i#cPuf2g%*oC9X8@pkBJpC?i6b+*C}6i!Fvo&ZS*kP+H5@s>tC)l zcWB?>2Ecuq_U5Kovjnw~m6hetsr=gU6O&cD;(qxDUWEZ{^*0Z;YkA{WLW|}W8x1ej!!TN} zPYZ9sq>iWGI9QRI%mgQ5ocJddoP-1f$hrQ-dE#43&%xIN<%7$yh(x0M2W&NIa~mGX zyiPQ5%Ij78+w&cf48+jTK`Er=^!(g^HJtJO;lXL4QAYaU;2_3>g41#+^mN`)o zr5-NQ`}=z;(;NZ<1>vh~kH3M1tu-Ucplivn12ID@dZ2)ijSW}ah(F3#JfM;PI_IXd z@@0eb7LBlgx3`-`kUxvV{10_rIo}0knM2tG>nTdca)+_M&ZkH7hJ32Bon#RdtVhWz zR^s;G!h$#l2V!Yy>13yE_8oz+UNVZI#Kc6Do~o*<&bEe)VXhmC&3=@u4N-EMQ+p}9 zW;d`S^21uig*!j;oUz)fG%T^0DI?&~$T64k8;&HRy>fHAVsRV!%wko4VQtSrx{O*T zMb(a-M!f+v+&z-yL~!G3gq6@KlIl1xFShNy2S*(=r)0#h+1<`v;7XMb!97-0G z__oDxy@6)7#%{nfHo7=&_K$@$oem;_s73d-Et_y&* zAelTcPN>55&1hFRVV2(^tXQKk@D!CZRWryQR>Z`_4zIrbePp}a3xL`Kw6af=G^RoE z7T!g!SQqZ^mTdTRN3dRaPr#P@H&N$B&d={}ZW5D_Ot(6FClP!JLS5$O>l4Kq`uh64 z2^M&N!TrACyxZ%f)luLVk$uiCd2F=6(r)L`Z)|ASVaut(WOA`owMhGC&z`lnx1%Mi zrSdV;(9ke3S)Z==p(U4UvXpDtL6H&<=Nidxmt*vMdID}*9|uUQQRSl9eSnoK%ztw* z1?Au@iHg~umH%)BgUxw#pRi)ZFK2$!D^W;UIS9;+=E|vMitSwgNApeiPq4a%20L+N zpE(a%Gzq8C{{FuEu6?8aIY#>IGr;{CSx`DU28Nupw2;x9eck1yXYT0C%*?hZ-4w-`wmhg;O${?idn@92@&2O~PRy6nNhd8yl;bua4p)pGQdOdZx;(H-^&fHVUvT z+K*&Sb8v9T3b;g0mTF^MMiP9nwq_y#fk48~4^MijjjPQStgVY^5#Vj;umo)mCLx2j zxA)J`P>IVKGu5OQ|AFiSQQov6*<2U-B!bZdW({zWWRsr0{v8SK#N6E6=;+GoM=QW_ z#=3oa-^QuUcma;_;Wm1j@EL-Mt+!1N>hm+rODINzDKzF627r{+iad=hS~hp|{QSJ8 z{=Y>n8Q4@<7zS>+UXA?w_b=+a-@XAtO;7;3M0~n=arm>ozRj%cZQXt^I@*9UW~ooSDIG z7P{cr>VI>3Fjs#k+30gtu;6%fa1d~{;1xEX#Pz>uxD9d5%0v=#W4o<%gcKBfjMY8Z z*|9;1-Oi32B-;lbwhSLq$m z4NFZ;B^Pvj@#4i`n&9yNEZoSg4i68Nk~!#s%|=T>Pd@VU|4`+sc9{-0*Tfq_LS7yo zAP`8A?Rj_UAa~Dh)Z~2)zy*A(auq-@sHCnpG&3_XflWwLlQnEss(^!8VKLr- zTX#W0K`7FHZ;HKFTsekO$k)e*U^J0cJ5Rm1uy8At-;TquaeZs6_srkMrg$K9G{z@W z1%Qu7B4z+@Zf>rr(JUMfIPzQCJ2)tZKp+(rnUX;*v9W4T28=NzTZjxhd;2IbSf{}` zJ1ff=B^y-Oy`yeBcy5+r#rt3keJP2Pgu`g z!^S{z@ln-m4Cdz|h^Hk_%D$(ciptQ<*;a0DE*`bS{8NM8H0gj?8h1FR)R9bsefcf? zJsbD?L6-8xe8Cx^gExj9&vTHQjm8P2_R?K4;ZC!IH` zWr@qVZuwD-D}<}9Q=qE#X;DEo_oVr1aqmAUF+P_lO~RFe>7;r zQ}0kbi^W`r8f^WkGN0w6zYrINYh)!?)lRwO&3*sCH>Uc$v))r=^yI1}P0x zQ0A~Of_pmr+lGc&xS!eUiK2p3%2qh|I?a$cvU^sTPAFk~U0N$r<};h3q9%T600XxU z3JbmIONe;PqR2hY*!pv*U78e|{pZgo(zaTL%X$n$$FCL#X#x>G0@TVtjefAQ+*Ou- zLY?^y-Y2+!E@&!VCec9eluh+LW21t!G|KzNGlZ3Q>vmmP<@8f*QTT>1DL(E`BGQ0= z>}`h#5U8)QGAtnBjUWOzgO-rFyMbr+5`UC?6v2%{{2RA3^o<*wg-RPqQq)>x$@v6* z1^;eW2WLN5H&+j-N;mBc>X3#0$6CHLnN{u|tF!ioK2#vPE4VQLbtCi6@zD)g*h}|L zV~D_Uiy0CNmcjwj#)2)l94Mn%7BP*2enCKQK2$SPNYNcP4QW;#S^tJiRYJVVcdm$;BA~}WQb#? zJVVArJz43P?A3+jY(tNiVruv+jaO*?YYf=1*=^oVtFrNzL7j(!4wXQbJ+G9HjNF2h zZC-H=wpR5~(RZh>@n{ABEs06EH=M>bgUm+=-Fs2lDZ_4TUy0Y+gSJ*^J@NJ%fZ|ia_Jx&IP&`;T9;x)+Mtv97c z?02$3ki*&YWc38NorOe6#lVkLtg^6AmS&wnsr2b{n!Yz_Y=rY0yR*8+N#b5Pz36^W zauwnuST+_=eF*QQ#ga#)TA3)R&c&@g$Pr;gQeb-6`dX`W?iUsL_0SXLme^Z7ks_dp z#!6if&Kgza>~@1)&T8jGZknnQQ5xuYOJxAG*%Pbi*`%TF*&)U*;CGkh`ulnMgRskM z-qRpTi(4hFP4YPQ6rqt+(qB;#iqR!uy)&^^JWu@zq#E&#f16u;Np7z<~3m!!Km8H9^#~vLz?_>IN z3_(e~g7&_uYpG_isgAOPBYU0mZ%-eZc1+#e(o($o2pH`=B*&wVC2dG$+&vdXHnOLA z1svIni)^e##y@N8s{e|QYgQ{6SopK7Y^Ok#m_oF8?&-LKIWQ9YLaI9rCJJFRZ|3?G z8w?aET&_*H!76q&@ihw6ns{L7GW`+nvD;{vPm+3>z!wG?FFrcEio#L7lWGt3t{pUt zKUWVls*X1%;a- z2;B5l<#ZKr?rdh^(18v1sK6)7a`=lSZVY)`n;}66oiq=(}?70Vv?Ob zRn508`UC8*G-4a*OFs{5mWBp-kZN&jZ^Kf9Bo+;VfK>qgtC#FRlC@#WU>TK zgx8BT7A}p}f=mxn{Eb7nV3=n2r0H_2qOE1qP^3 z_jJTz5yox>8?$|@IlOLvmo=ntMQJgZw(IGLH1Ktl?^NgVZxA+ys6HqRHrPd`T1{D} zVZDykRiH|$lPGQ#=?Y=6Dx0Vj&_IfAOj#R_{pvEWVczS2D+a+&@X&oA>y(w<1rlyY z^Ct>=Bo-_IkdHLgR7hA>;IGE@%neW%WZY-M(T`s6DK@P-5`j@}#QW$*3zXd{-{(oq zBde{sIrlN0C=IGs^cl@FN+TX1sLgcroPMDfRZy%r+4cl76A^We;SI2A&Z>Wv_WNP} zs_sEQGJ3zGozqED)R@Yrx_L8cpkGefocg|Q+&t%JrH_FjtxXnol2HZultOPwvcta{ zg(%;g4{sLxq3){)jFOo$m3LLPz|<~s$;H&OLR-B$pWaw@{mfy=Ap=lgR~s%+IcMZ8 zH9V|5bFAna1<|a8P8cM_8JgnC&t4ClGZA6FNovjGynmRAP#zIfg{kfy ztePF-1aZ?;nW-#mO|&4u>^+TN8c|AiSge)!dBmWq8rsh;tY6CB#n7bpdln|_VMjTn zy!bndc>i!F`m0b4|CLH}pR9C5<%KYL61sxVYToAV0n7&jyX!?^b4nUT8|K1uq+NZ* zlGb&B40)}8G(>Q^rv7@Uan|ojt%}MvMFB$Xg05vL_IdXHh&yuqR!TstGNy_)dbCTH z$<}K^FZ`b^kFV8cOUKrIc83@%`_;z3&H4d!U}MA6h>YP(e8kuTT8R@`xt2|t@cbuf zI=+c?K1PmL8bq~G6U;p*RHD8snCu~IK~z!YIK(mwf(JaLF4Kn4s`w1sl7x;Fm&=KU zgV{j*g~swYeo>Ru6a~(F;x+5Vg4u{f9SKx^_t8ypB$@dH ze)jOgw!%QTmQ?vPmj`$#Xs@%hE)AK2?J-#A0%uwLu6m7J;;EVru06C#S_}&VedJtD zV)k`$^u09k9()l7aF>7vA2qEA)j~gs`g`@It(L}plFlK~>fajfdq(B>t2`Pc)k%aN zTluq<_(@>!Wav=5041cBC$$!0ZW}EMo!WM9%=3UGr~X;4F)qL$$Ks9mXyi{36|G5W zH7GR!)0KTv_0acF5HTE!J+s|VNRh;DaTCg}pphvY-}!xZ{yeUhNAM=BF~Q1%*@@zJ zPku!zf5YGyb9J~%$PVf+_5M-}CK28Xg(UFX6LJBGp`##rVS0LDyL#QbPrgy<@*O@t z@_UbY;}7zM`t>qPHr(z^9hvT|LHeALBmJ{DS6Dy}I`*RjhmfZfN?!Fy_3{DaV;WO+ zN$%8!J?9KQ|5QX2pZvk3XU~@(b?;anf9bQR^xdhbE<$K==G^M2-NfF{jE&h|YTen{c$u4<fMZM z6wsvZ+vNH?KG+j6=U%1GLMQK;tUO=m-Azbn8<#Oi zrwr9;ahP25{sc2@(B~z<#_-fWii)Pxb;6w4Z_muqg;|Z+lg>Udz#`|ZB(R}BZj)n zc;h?LZz(w(*u-q#duFODSguXN=c@bLm6ZRp zvIMqTT#>G6Lqj@?{D3dK-+;T_(*j+kjT~uZd7t4*c1Ld20(;X7UDa&dibpnVTeU2A z`7IB%`l&WQw~Yhc0DzbO{+k7;sm^4c3k(GpIZj{t9e^6{Wp3v9aSVLh<8kIxb)q}x z(gZZRgVv9kF(Wkm6!&_mESvgf^0CetAB2HGPs_1_=r5s9{iWf3g8`%IsM!CSfMBm& zT~80AzQ*yS$*^68VV42;8wUU4l{_ioer0bRp=t;h586)9=|~apW}h3^D%rcle*9Iw%cu(t*Y#^IF3MFX#R!J= zL+;LlNJY!+f7S~sNjbjfN-O^ktD|wd`xR%GRMH>nv2*ez`kZdEC165P+7hb!X7xbE z{RAQM9ciCreZ=vlIKf=Pjtcfx9T*G-CtfxKv#$A1=0}&BKRb6Q+G}1u*^`3k+bso* zNy>~J2Ch4oUtV0xQn(B3#Nzu*@I&-VSmt#W#5-6FDrZkyLvH;B<1YYp4hA>1UjXCVN9Z-|-cEdd56q&G zEQYP*#6wqK;XEZKc4K{aIz3&k%V~1(FqB@;IF58*ScAW25wzOAV_7p36?MkhvTIhJ zm%MA{&pm^QZ{ET+=8;jxS0c?;K;V=h!(Ox|JMHmrg$au)z4EC$%Xb7RF%-6`6lss2 zW-=}fmYB(GV@MOK_NHtpNf?9^S5-?Z&#ZO%*>7!pz3W@<8$L+8SCrgFh&-YjR;Gi& zAm@E#M2XVkiH!o87f>}8+}(P8HaizzHnNM;J@`8qA6uJmChnUT zOkAN5>zRDrYvPNf*q_1(&0%U7#Y#L#@qbGGUH9v%b zEiFA2nll}w?|t3$q0I7v%t2{q(d|b)FG!oekGNb>9omH$+aXr}(c&q;>l|0CpmEWi z7~s;~V}Gyo(bsyZmqaO20#EtIe6v*}WdA-`i}p z>3p-8*vp-4gr~<`D;gW-Nn6;oK6bn^9{Q3_*$@$53k@GgDm@by&GI|aYqpbB!|Ab} zdgL(-V0#Lgjt;gHbnqVib0OPZNubhcz%g{!+P@#A5;7oP31wsbBe9Nx8amZCDi)V& zZeEYz7or2FlQ+X#JMeJ%qB(7wsBw>n=CU1CNo|eMqt`@`JVzf+LwxW-$-jV>uUA2D zeVc#lRWfFPYwJMv4_9w~94rRma)1uSN#QHnqGtAVHHl64kyl;^k^PU|h%u7#Cc}P} z-Lcri)6|W&DRv1Yxe>E6@Z+z_iH3&|?E$KL!UpQ>orR&fw=iM!-3ak~i(b_<5p;w$ zoXHZ#@nxZjw*L71`Uo2z@z&v~fo4madLC6IQP7Ls=b+Zq1Pd{&%UmCF#)U1Ig}X!tUub{ox$nF~_s) zK&y{7UlC3bga^`wIB-Fd+J-zmI^!DuVntbU&;7xD)@VoIy~4 z(~=tKoG{lzZ@YN2crgi2AFB3~I2sgxUvF)5ahAqXCe5;tBz94eMHF?*z?h`r!>Ze| zm)bWbZZAA;!KeEZ;~?VVvk&~lGQQiEyplZyr{K#&fCUkYlh@;6@H`O<-aAag%@_=7 z-|b>=mf~Lf7J;cz!mIgQ5xwMUHZAfptx7r_>_Rmv7EX@xmi7BXA`{6zWP>vD+{9%k zI2R|mT)K?K{7Vi8ePBWM^_6}<$NU;TcHt>V0gfGN*Qs?p>Tu)cJ92=LsM0Ukbo1#j zJG+%kt3u1~xIiF&Qbt7#beeSU140Ig@l{eIoIC>S?EQMO$YeP-0uZ^Ud8&@9F8&G{tpibc%$9ZY!nC0d|YS{QOV;(zV=8^x}DihM}}* z6`U|u#Vc)c+1<)Jxz3jmMEX)qxw$<56fHvlQR@}wm6kYpwM@bIuA=l$St)$Abp|07*(xR0#mUrvU(r6BZowmtKxPH=q{?Ct)cS zSXkJVErm_cTO4OG4QFLLQ)joYjwXQ3S7#FjCnHA_6I&;9JLkcq3uyo#0i;BQRNOO8 z)_io()z_I{^r=QEm?5cPAyP=f3`N73gebLwm=;yr)lYO!)LPrD-R5i>+FYvCs?L_N zS6W?HZf#Gm-5a#4Y^}~2IvP*TD1GSkw2$Tw)U<+Cm8?}{d;B2-z)0H>DcFp!UchM1 z^RDtv&z~>1VW`-;oc4_QGd41uSbyL~i3`G#2BYG6{T5XRK)(oYV5Yc|fL_fr43+~> zg<*3Y0xe*KL1X&iiU|KPl=@!-AnO|&qm2c+Ha4DN{_!J@!XmARCY*#hMhG>1^tj~4-BA?f`)=}adtKs|9f6cHc|ZznD*mm}jSZ!g()q;Cb<=S$as^(`{}{e=q8goIsNi1&>kO(Z1~&Y&c%T=09qz8*tiyMtKgYf*Iu^WEAH*JF!;I@T_e= zma;(f_giYJV&EC#aC5p@EG9H!9hyeN2;u&F1ZyS`k; z_z^VKf=WW_4D)LW8FW0@sCZtUQxXi>Pa+#rs-g#Xr~$H{@>349NP;In;okG}`6EX} zMu&xknc_Z)qacMbGuDiTQ4JL8ZHuDW=&%b!_o$TO3r&|QQpt`nld^k!YlP2*&BN@~ zD+>-Rq6POiC>q!Q%==^-2P@3x)?#8hOXzt7OUl07zvJ*#gj91oF2q6BpCX)}Tk3edt+M`pghqWiC_mf@>yvr?*uV+WJSt*poR$_zUDt2OO}(u<3qcLv=a?GjeU%NJ*kO${_T=>OMR!&)oPJ*a78q}V*$~3w_i730xOx=mv_(QR zA{XWXH{sBG$r1(K|D(-Cglv2LQ)k!I;RLp5{))`GDkC^M1b}Ex_?MxxVEjRVM^wzQ zgOiheYNt(YyTxxO*#*GG`GCf2cJ}ew``ipFalMA_bgv4jq;C!SOKvVjvlsy6 z6l*5od%IdGFeH{L7S8UuLP&BH3vhpiP85gDwTp6)<5dah)~`H#+h*`slUv}y4vdbD zn5oST*t95hOi*(@pTS1ML$8WKM)>md0KL#RUD|l|tV;HYXFSJ9l>*k=NbK-24H@u{ z)lfD}fh2K6ZYx`e1$qwl$7Uhv!HqLdqZWqAdY#z}dsU^Oqyh(2J}LZMBsOO5hdAn+95hL+X23`KT@x^1LmN)l0`4D1`xWZSB98h=`JN z(3lcc8bQlk-*5SBPLB_A;od=I?e(Qzh@w6Hatom)2^hEl*@k=JN&4`fkXC`h&K_z0 zEsJs3(_wtCicmno=)Ogpma3lG%uG9pa`!e{orHt32p}HlAE1;A(t+ zS*FnBmJfSQ(Qck(q5mS8cw_YsC0UB1rb!SnfKg7Bp&}ViJ~TW+1_;9DgRd`r1oNls z$HCUHbDIr=L}w#ULV|-=i6!yW!lxSe50 zB$|!jQ38OtfckNpan~w5kn^2=H1Z;8iGBszLOmF@6(Z_5R?rEbS$Q8%L##_lRry@A z(>`rjTU&Lzh$=maF*+ZHK!&+4i7K6a_)bgRhL@1n?=TPt3INb7t3R?SD0|>l>1?I( z^1kxvX6qlFBoxR?9dWIm!VInG9G8}tZzZx6QC=Hi0)X@EY%@;ck{B~_=UoykuWp(p3kSyL=379w zyD`gg5VXYv|Br9cu50#`{R3h%L|p1Ci$}@|Tul0wkq4e)XmuogtmLw-S}uifzs%N* zQs-PO$t_rjAKJ%sR83TaP(N@9c-ZcY8Mlb&V6N?Qa?Z{-KKv?5Pi9KzO1;suG2g+A zkBS)MOCFE4!xDVA+73(K#MQJivaum&GBacBG;?)V5Bh-C5Bg;NG@p?gqAEmj%39UNH(ioMP25jz zQlvn8Gr~;&;dYVu^jfarb}=(^l9Li>t!nLesn5TuXJEECEBBh0wJRxWcfL#?7Ox^E zA(=)cK6~5~eS_ixR9biG&%@@}Oz!yE4#QJY9Z2Q$iFtQ-z;a4eYlh1grd4-^M@QX5 z1^ix|B#v)y0s+9h;_1nHmxOD<*Ue;t;x$p;bF5r4>E}t>{<*n*R@WjdV50u@HV?<< zXYX1Y@~Cq@RnF0knOUhA(5ymVslj8lw=yhnr|w1!B%+xkL@ErHpn%HQ|iw;2?E{nC#WVkAqBG6o6T#-=lOUf8MMbR~!~Z zN$%=8Xi*r4Hc$hVKByH8T?A5WMhFbD1Qt0aGgsZCDx>POy+_rdVio#feR^p1(aMV1em0StSLo?@9^Vm^(I**c^Ekd{r7_72g&@?&my}8e7|fE! zwbeSr%8cz-R%cg10nLB3TRwAA{W%Wh=^}G|QfYmBsbLy%7XVPlBId`=hrflEI?34t zp<)wN20p3f^!5e;FKAmTxJ;;Dx8idi(^+)kgHVO@t#oFPOA4<>&D05gENi^ZF1E-R z8BJh&ZkvI@pQpaHLE*pyA_--h5#vZI_uaZcMTtI)jeT9g)uu+fR2 z=a62sfKmDq41D(?gQ5yR#!sX}NZ zV-p}_gEN4G4FNW`Bwsu6g_!mJE4IgdOHlyls`S9g+R6%s1|xtK5bz&t@*>p{0(1Z7 zTZi|o?m&^OKQbrYgG$sd*uX_a6x-CObE4;LrA7qGGWOi7sx}d4|E0ZsVZ6 z7c}b{=ebW^#_iazlNrBr$(Oves}ceHKLBo07~rBwuf*KukV~C`dvU3NDt%?vFC*Xk?*`8Dwjfj)gV$ZU6;X5QF8d%!fgt`QjJ~Sa6EVr-Uf|1aHB? z-5`Q9bjn!et1as49Z)s&i_e!s<@Kq%4PYL5UV+zrCR@_wK^e&GgLr?6T|rdH2TGEi zt4egxOyu!svg-y5YQ*7nJIvGgW67~FyG8!(rP+D=(daSRy@k$qDDIQepEh-aSn_5% zz?+|VaA#7td?y|-c5E);vZ8=`JjTZ>T&!m1Ntq12;^5?x6rIDo%%Wv+=F3&{#K+V6 z_NnC<6Dmg#nuL6(wx?<__xR(Se#tFEq#*=-;o#&vo^~OfcY}HaWV4X z$xP#ynP}T}`pW+C6y~&0tt^-p4X4hXt4X)Ww`fijSxYA$U8RM6lt$V0y#QFM6rl6| zPCgqFgOu3ajKPR%fZ5RGZJ!be0KNn)e;35T&9X}#oSY;%=xi%UnIzdPgVr38_=$tZ zQ|b-}P{6?&PQHj(?{=V~4G)&$y#fGa@6Q~g3$f&&Lwpa4Dcii?v9Tn=&P|>HcK6b( zVy|43CR~0BghiRly5q#=jqKJ#j}D$PgPJvn$+g%BimI$MDr)=IBq)Sux5)CJ`M;h z=q*+-f%whoMqjV4>exA$ittAxjRH0>uUEJ&yJ_b*frOb|7Hrc^U6nHqFJB6~2$tkK z5F%ZnBzW)IVj3+)EDnPTDaFPPN8)nvnK^AyF^!+vO#p;GvQg ziVZ-Vanm#x5i_ycoaOE}$CQdCWpP3`lx(W2wJ>hLMg3drYK6^$1K2bYNgl^}f{yU2 z%JO7E(78^(nvSMp;>v!26oO_U_p`PxmH`!`p`u2J4LzK z)?WCG06@|^>Q#Rqj{-nFwhp1BnknzQcWp@7>3nz$LlF7=sZ8I(=)l$E*zu}5W<-)mUTtY|?fx5i*x zQ&ZD>zIFfX^}eC)?Ck91blok&$mhOzV`17A<@d5p?Duw^jSioNOtI@*lb?8hcN_$c zQ6C5XdAA@XSm5Fo zrtKf`1_ay!rQzW928wzqtNjs~H$C@|JldgNx0};Y;{vkp@Tj~GLL+f#@M%S&oeh3Y zk=@;crb2UQj& zh>h|}X(UIRRXrgtIdQtc1PsY6WYDBX{9*=TH|@qbP38Ai+s(Vl$;q@dJWYLI^7;J- z{&@poT(TYE5nMv1UZ>5bRUFODEZ50;U`gCyqtRfa=IupEC_Y4gKp!rt;$K~ zyisMjfeJ+xcI$xCR(i4_YiK(@27d_1K5zDNZnSq%I!^gq`WM=dSbQx8CP0;Uptox0 z;DMKyb0)Nnd7e%U46B3y2`zRVyj#!Hf2sT?)BnFTm!XsbLXZ?-GbLq&hWi)%^D7y6 zXsdmi?QU=wjA|Rn^L7XqR>ugPh=~7PIfxYbD;t3H12J{XC^6%|h`-ihZ}Wdpa{jMU z&;R=XqpQAqF7fGdytGexCmnKqKOy>j@$ITGLZb|E(!guh##)-^r@~jFqFHf@YwC4& z81>sVwul-mQMBeWA{j~yeCSs=m(4(8hFi8jtjBk?BE`TeO-sh)_VpYgmxZW|&peh#eIEWq5Uc7OSKJa32TEilZZ(j6u2i)uRTZmqmbkc8o}E-@t?C*ZRg)}eMk z)=!FfIAN3O@RXSR{te$(!n3x=ynulHZ*iW+Bj9xW$TXZz)vJDEy32R0>Zx(UKZ13n z>2y65%LXmhI z=lR>ZHj8+Vf8+u{C(lLQyAkG2q?TEIxs?9<@AIfHK8~5%x$MULb>vZv`ydJNfSnqA z5-UF6iC8pitqXpQbznbM~q5_qFqpw0%3wNWEwPI$bPZ=&C!I@Z?(ICH)pGU=%ox$GH%1z~0DtxZ+gfKL z?uS$az@NqJb3!*Ew|T`8ei1q(n&{M6;@*D3a%tZ}lR!0h!{*Ye765o^NiWmY35kew ztfe{8bV)?_`MA_dmmOnl9pWeh^;Zg2<>dQcWlM!?O9=WlOeg$M zadOf!`dL4b&>lt_+uxZM=3O$Bk{$g@Swc+$X{F5_Gwb%et+zcHcfJ>l+TfuH+Iu^a zR1qxprKZxGiB2a>dX_xYWvr6PLjod4Nr}d9ye+P1DIOMwSRy+V91PeGW#hldx#t}_ zd9jQnJDBDQj4Y;HUNw}g^xA%XmYWDxoOB&}dh2;vUh%#LH5_@5?VI<38s}x)tG)#} zY#dxSS!Uo}9y$5AfM7pA4!fC4cY&fg|2D1X%*rBo?(soL1aH^!q0IpgzkJONHkkVQ z&PZj9_~5=RO8Dl(iQFlNE;))`*K_csk3vbT!n0V;B@rvC_w4{L{07=eJ4ltL5}OWE zaYsb^nGiOXnf$)&yQf@YHXD*sqs&nP)lI&vcVVwbb{4Y9E$)%?YeS7Hp?ygYv=O7W zaJx7Da{4niE>B|Umm8@73u_t%#HLNSM{L|UGOX1YI~f0ofiQ{+Zr6OFDtj$M_XS{6 z#Kyc7(J&<@r7srwsP!(c>M*1P)PMgT%3WHxuxR5bbCNCoZo3Z2NQ+6}x0I}#JMo}e zB((I-aeD9ec9&dIzM|*eFGg+S{kAbv4|zef-28EDn!`@`fWb;xNu8<&00hTt3N-6y zk*G)>evzvsuNq`c0D#4y``e=&R^o`B;;2~p`rWVS1ZICK1MGrI-ST7pz=ncKmb%U& zJs}OJxPW#Y=UJA)?_r!S`{&uR=|>$J)=uzj({5)=S<|XrIZL$nl=$6;G_;Ki)BP~6 zXUpd8NstlzHDfdLds|S%fdA%piygee+x1SL{Pq*Io5}BZKu|n2E;&^L9uVyM#4uN2 zOV@;*?R52pRy%7g3lAjT(9I;RP1vP~@Ysa7`dTi>w{bG$v^5snNV1_aN=Vh@S7z;l zkp_3_9)-*hyA8|1`yc{?WNxhZdN~JlTYr)}Ct*Z5+beUx+)0WAaEzHh3En2{6s#9KLmM1dX~5?stxqk5F`&wI`pTcBDQ|5o7d#q{epYNpF4s^75I-!UHwM z`TxWo8_B$d4VUagyTf+J_TDV&2RWhpE_93v08nI78`t}o4B;=#&lf*m zqqLSRT(~B1*b__qB80n)Nh5ywiXt4pCsVn-j+Ybn-mQTJ0nn&JQkp>zj__payK>IS z5J9z^7!01^=syk+Vn^`uw!iUy-1mpeGzLS}X?Z_y3srBleGYqFu)D{@RZg3kiIS7Z z@_g)tMy}^b65`4|BslD}Py& z!Jl6X0iY+Aol!9ssNn)#@&vc%dt-u0`7OEECDgj1R>7-Ghzz)?Z(e6_mRqBGs8BW9 z7D-ae5j1iu?bx9J^Huh#?;c?rEFeL+qPLP&Gwxn{td2@RU0W9+>YrhF8O0}~9O+l< zmRa{Kd)E_F8B^38;aD3E0GlcCZ!x-5@l<8?d48HYmp@P(b%2X|%cn7hBnr-R=3?Dj zMONLH`L2$n4S0asV{a@{b+3FzjR^2}%NQJH#G5gx0*OcttNY%WsHjCyKwq4!$7y;L zaThIEHxzcw<8IEwr}I>FVbutwF5$PrF&M!E^}&$9yCXf^P+1wspsvbME@t=cqa3k_ z!ZkgI0i(?Ki6^su)rt=c0M_N7N4#6G1-DLLR5I=LyD!mo{cH-axE^N~B$NxT zd`@=(!2XP&=2ADrSItZAU6a&rC7JN?*&9$)VqAF%WMv$8DniWTnwsf}zs_$Q#sWfU z2-PNhV?V2sfCKe63CMth5E|NB=|)2~zxVzw{u&kgDFC>=1-M0a`57J;Rb{nyI)4rC z5sV0=qI4n$02&RFSuG?u~A`aj1)PUbM467!SGi5GWjp_S!+b=N%BlEP>6pLXJL4Oy^^Qr%Ufb0$< zD8O|k0<`yeSvhQRud~kJNGN5jK#?F~ePhv3OF=@jl>VRrgd-E31wY7) zml?pB0q(tsNVJW(e$_QrpCt*wDRRR|00}OT^#ukp=7{~Rv2aT+xF{hRy+BpfXn_=c zVE1RutrwKm&NaAeXfyhGSobo1AHsicxJLUOF~={P&%!}avEu?Xphgt2dDwToDBj?+*I~AMkup@AprVuu zn1sUs*;8N`yW8OcyrxxPKuz-?VKGz>VL{kE=QU3})3qGo2Sm(l>i!QfaQGd>Xb*8=0TNc!A;Y()prB8>G{WmOym$Efu;ow{6zE~Nu5)V)t^vJ1aw zL-iadOfjrqXWvONy)c#_8GnVl3h1E?LHzutml{mrNh%0d`^Njk+X0Z^-%Rkn8c6QJ z&>01m$H((v1`_}ny;*S!OkjhUpfluj!wAx}DwI~_QoFr zuz!3V@<%JTAT&egTLwwV%L1S5KYmqD6AP{s!)TZzP<&Beg5f_Fup(Q&vdOa9J1@ML zIf~fWI=OXSwANcIjVNav?()uegyp;qz({J^$7t!<|MQ7?9=r3|_3OL!m-=0wo>R^G zU*L7O>I$9utLH9mTNV=iF$^V6jws%9ZUjB5V~=sSJkSKXbEZhjI6ulNiHf%G!vayj z6BgLerxP-8{tUj2jkH7oIdU;v#j6MPo)<3a9w|GuolcVhCD6hLykc0zI*$7Oijzuu zD4nI_Y9wnOFEwE3NSV~1u}c#!QRobO1-13GO}aP;RE1N=x||zW@5UO3llZIHTPTQS z#6tyj`2gT|ENEgUId0gq;p$yLKq@XAN@nRJ`I{TFQ{LdYWJmkk0Ojhq#vegj+q@x=#0CkJWL@2Kn&k;M|+V~Hv1p>y=+Wb z6l=Nc;zFr76$_-9#Vo!E1+1%3m*c3p;wvkm`po(ukJnO3vw%4cbA9~L0~f6|_IwMm zr=(=xE(c`&hqpF0E`Jq=&s~Ai!>g^s-P05$#`TvxMf)TJX7lizF30yAbMK$|s}c62 zJG0db$_QJbqm+NGOrio{bHuL>%WU&rAEcsnTRif`u*Ksj#tsm*=187vWSUMq z>1IX&!0736TsKBT1DGtd^>X#{{FRxE15)G+jHN3+d#eF$DH*rM7olAxh8^qMOkN&9 zmt1vrGHw=PR$U4SreObIzJMJY9%v@~BMTtMr<>VyeezX*FsL+S#@pRr)jK0 z8#(ZI- z4jrPOfTDj>pTMB~;O{ncabD1kQRg=_tY6R9dCcXu?$?f0?=tdKd~f31;mLR$hV8@+ z08_3f1@x2+9VFQhz?3cDnD$5c|)^ZyvZ_ccuW~zKZF39B}Vg9(~5%eLGe5 z9Moj(={|v<4hHx$t-g;eT(#+yzp+-#jBKO|yi+;%y|`z1CW3*z}}I2@!Fza?G22^8CU zI&XMsw~@DvBlC!S(!kFe@!SiW^*Nt z`7AoXyRJaIt*l=}%!7sq7$)97pxf*+1c^3RjyloFw7AwiO^pHT<4k_D&PQX7Rc0k> z`=Q0I5@#m@tE}wjTa7VGo9C}&H^u2~F?_fAMNBaK1;%M)yC}}a>cZQ%s_iq5TjO{~ z0HA4YeRART@cOp?evd^+xVF0bIkX`k*G7Z+Lawr3TNg`enq4k%@LGh=F|$BZP402| z=u?w>ofA5Hew1NQ&f3_VL&d^&e56|bha)SAmlU@+Q%#Nwm(>QCa(Y}>C1%P-4vrSP zH_b~5Ld+7XkVY-r3z)`u_A=<`Z7@LPBfZ_9RWe{mw4_f9c_EuD_zW40lvN2Vli@8l z>kJoF2vTD3r9$a?Okgb|5>C+y>`A~w7Ym0P1yWxo)$iv7)(v?Ci7>hGx}&~?0xGMx zd|CGf-K8oy(ljp-p#%+$fWYYWCT8uVh2sZ`PMss1%>As;(9rqW*}*4p|MmBn)y&L) z23mxpY?mF(%1{3WUMAgu|Cwg_f0sD^m51?uo^BP+=pfSdoEhdF91e*@DfUY4B>^?%nR97hgX8y>D3+uxjr zZ;=!CPX=m{Us_`0#T#rL`(q8*g(2Z8g}Q#fnZ~xNY7?&*OqGcKz$S^M@~K?i;7?Wc zy#B#nvXWh|^1iina3i$$FhUvWJL`{2HLwEVRxHX%Z~nYk!4*Hn89IR`;S!2jZm3rfJb4!q&Mm z(|Q80+uqHJm?{lE2Cg!7Y@8nnEpp`Gu+a+0JGw;Gg&CX`8wr-ibJFHz9p+<0<5fqv z2#SYFXWC{g)d?~CCm!d-wP1j(^y-PA36uTYorByrVhb10M!qz?_T1FR2*?So3D3$= zEFaNjzX-=4XK?HrX-{mz4>3yWrd!XJT3oO@H2f7A8rO}uq?Ml_sIJO_y1Yh?&X&nq z385O#)ZzM@seEn&ODwt1dCd6YloxgH6dRxb#dM;@B3rPFmh$ucMJSQw{A0N4SHGIaJPAytbrxX9nGwAL>z-s-#(esV@>S}hd`5AW!7 zK0{>foXSdC+k{j0>zwpvOCHL5ta^Y56(}&2oZj3(Sis_1E0M&1(lB;*E9f@7HYpTagl$=ZwgKT{l6uf*ZYO&Hyh$2)PNC-G zIpsTyx5o$CinGc7U>Aa6Wp?;}y$d zHtT7mhX5OR=}7Z+il7V|<6ZT`l{kM`ekMM`q^5p9THh!(D}Qlz(=+M{qVbGNx)nst z592B>9JsuD*LL6DCH)J&&}ET3!|%*1!w~*+uUGiT$rRK28Zd}8u+ivCOJZb#@-+|r zS%tLy0!uatCcUrXZ*^;3z5|Tlf*NTolpTIzy_({dr9{p?-$@yaSTNoOoT_|!AOtHb zPH(ZNxjr_!zVaB`1iU|81biH5powl5aCvu}&i8r#W|}{pc7CX@qHJM1uTKC7CMnsS zNlHhLRN6EDM@b;x*XHlKwPKJrjZEbsM&?3#OaTLI@?@QBwDFt3#bOCLE0mM4=HKyp}*^(pTa)lJBJ)fzj6{^Jq z!e^yca&--q&J>p$Q>;Q{P26#hB{})8vp}zNv%FbDb7)ur;0*0UqOM~=Y&&MLpx9$j z#BE%m!Pj&7hD{XaF)m5GKr#GzAhT)>VgG&(YC9 ziH#zb4RJ;?SFOu+TO6c;{sWB%x7PorG~LSJqDtlKL@;(453o^xKBpT z@SX(wuj!E(CdFGn5{J|Ye_Tvm=EWmZ%j40}7ne6O)cFyfA65}scVlJ24#A?HqOPGu z;gz#Z7(7S$W(3q$0{R0jq(a5i-44pfz|+8aG+PkR1_=nt&(%#jmzr*x2aHv{ibB4o0K3bWNWtrB|^1-tyenbV>%K7RbxvT;}t5 zGe$!g`E0e>VMogtfy|mTN%We6gvknxf^C~`>#sCi_xAT)87Nnb@LD6R5Ry6^Fh88) zqQ0_^9XWsGHb7u+N%v}H{@3X$PSelz4l7-ShcKOGMB3wiD-Xeux(Y?0AU~ES+e*hI8nJ1m? zQ^_B9U#P@{7MH|;LMf#o^KF-)-H(xn1H5j0hF`%1lUq-hP7mQIfa-r@ROAG?2xy7> zEgI=MD$62q-G~zLyt>wkaDAGpjinXo$8Y|6zPh7dc*+wCO`=BNxmVJqaI6@)KV3b75_t~S3-OX>%Vg>fPH>q(cdWI)dm7x7yp7s*RQ|FN>xTh~hYk+Glm@ZV0K`zRkYR>yc-2MCy9IEGz1bZu$a}?~WqsHe%yh*H6Ay z?|pSXm((ae)=QT`r*^9dBn}>3&%65kpNyZHZrhM=KAP;>{Q7Qn{&X<++M~_M*S;S$ zraORj_P%TN_*yg!JO63J7;%f^eD~Tj-Xr=4U-3BiLV=VdI~BYc9sl{MfiAX#)X9=CN*))H9!8CXhi(@BS%vXvQNDY z&(7u{yI@I@gSNgUef8x*jwBY;MLyyO-Et|Isw2Mf4sNe# zUFMr^okko{{G~d6dKfn8(#arqHlHq_|CbGRt;)7n|Kyyfg`4ckWoSc^q|!8Kj9ltU zlmu*F)G>l|P&Hu@5i3heV;@i`{9WQqUXFKCjzkXSRI*4{2OXtn`FCN`_YuvBjuhTf z1sO4rBTC58YBBKJml^>N6JtXKhDECv1Mjn3p@iPbyArtMS7PzI@15nl`XUFfzK_Q7LqT=xd5?378ajHPxU3SbxA*bn z4?CoxgGi^Sx*O$RiCKGPM$col!JH-|Ow+&U;77Fke?syM$9{6#L-b*1*iK(IYjWWIh_1qkw@^K%nJCR(N{ote^RPZhLE-!H6PJ?^3Z%YI$7z3!kI z(|*skDO%t5R}#DH;!70JxdmOaZU(SBse4zj&b=K{&KOF#C zg)AQ>HQ&4Y_xEw`1lqbTusmn=7QNg)cPt(7`))3wR3LK!LpWFmAy@dspHMlZ%1k~T zg+7PfL3F)LRbbeQNQ>;T@lKn2jjykLlXoHmDp>Gv&*rrx%f1d-T21X{&3*^T8-t4~ zZCw9En`8Xu_B8?gj`QBKhl8aJAJ5Y`j7M=)2@ZbH(+OO1#>=_d9hTxFHR=M0>rW5i zb2E;0l`dNpR(i=tfV$GAF4Z(kDECM zbJz<749L289@?5b`yoV|^1J6>ONV3AvXa8ZyT>R#jK7pKcwQ7gClS&ObCn?*h@yj7hQ! z#DC!W+#e47GC6LOSlt_KSVjQ#rnUf($Y^rPQx{Muw7HgXZLN2937<7t^y19m#7V!; zjsl>XjxQS66OIp8K^w?fl#PbcmTSR%R=?RIzFHppA0~0-zUXWbOk;^Q;LUja%?N>V?{I&eieRy@(B~R0wf-`Fje^@cF7_XMO_x(t@65nkbCN zn&sykFSc8Yjp2k=*3?l=P6-;@MaH)_dbQivx1TY0cBg07n--6_vzwP6bQ=U>qr$Zn zrA4Y|+%|em#SJN`-Ni1@^cYlwCV1j%D)fjr+Kk zW7N|lB&=mugXfWXP$%E$I)Q&5RX|gdS4xCc{e#_~iq9y(z-PA)LO%>>(SN=>?ckbw z!2VY8bMZE4Zjam8Hvo1AvF=CZC%suOk`Q<^+>#Q{YD%nSRg{VhXBMl0v(LzY<5kt! ztB+^@u!7q@2PiV3?!6QAZ^$a> zE$Zs}12$IqV`q(-MfjzHYx-chH?y4bkJsPpI>-S3{=w^tQc}%)OmpS5Q>*lOlmYoK zp^r{;NRG)96aukDC1W0YAt&%~oB8eZ6P=xxx%K3IOO>SbppIQV!fE}G_B*p4La}xm zX-JEEb(=#sMv`?F>&~-t=0B*?)22b;i@X{LkO`co-)lyUr;QWUK>zxFy9J@SHU`~M z`%RlKLht7O+~e8L<&~xx0r~SS^)spqVcu(u{G65K{<{wsFN%65S@5I_dZH`y5dDV| z1Wjs?RK0NNJ+ORBE0gl_nak?CS#U&1V}M_|MemK|&re#5?lU1!s36DhLp9sBCU6@# z8WjcrsA6DamU9MW;}cyOSxE_!SQx)X3q)1L){}jBk1L6^kRc{RQ}Jp)AFC+D{o!#b zeS$egH;wbqzd0TLr`t$uY50AXQNu!Nl0}GQQYcRcmI^HNO*C{ylcDk}87+|VFVB+; z91yJ50*?|GLDrLw87FOwXN#N}Y|VefT*D1}-k~+yGYw*aeA;DPpl4py{Y)qzhp;Q5 zu)bGI*l(cul~eR5t&{=S&(0a!Ae^W=^Cvp4ed~KMn%SF)RnKG&_vdTZ6;0o56u&mM zEA#c@0qcfOi=ZwAKu>ZNrPMZ!n@p=Uih%+IiGG6*eU$ln?MOohh&ogwCl~C1cyY{+ zCoZcrCK$S{3?eWAY!iZnb{GcqIHc>bS%wS{tMm96eS5F{;n48w5ZQ8Sy8awB+wreeZ$qwLR%xJiVa3338u_%=IH>B^)8UY%{yofgY>Tx>nrhWs z-a*~J*vS2JiP=? zN4>m$UF52#qudu8$iQYqc?iQ_(i~;^%by87IfsX@Yt$8Dd57Q9M-A%sP@0);7aiYL z`l*diJXzPujU?j=dh3h4l;ytW{bwA0g}CWoXjz>_yk=#PW77&sN?KlPmsDUGhb0FC zc6JQvxJ6>=qW9GmrBb!kaY3=~#7NG!eg)gz|Lh-1mXN(S2Z6jt&#LGz)5`^;WAvH} z`yPEwJYt)l;*8>D(_PP3ueKvcC0tFZZdK$QmkDjDXc-u?aueC}k?~kX|C_J4!*{O! z-w8VD%w^C#yASlh9I0^gI;uGG+FSY8=x9{|}v?@4(M~d3)_8g!46;zFF2wb>8v*uY79VB=%39&68}B6)h8bpuDl|V;NqGmuJ@V&uFUWs7f91pktgkCix-ipT@=KgoEffn9Rc9#cwTD}LcGhS71Fv1) z41NzGkwg;n2u#;8wz4bj)VDv*q+7a%Yq3?Dk-J*;JB(%~?mAy#{eP?P5HH^EuRQEf zoB7Ey<-UCWLpB>{F4A~W5|i>mPA=+| zNJxJA%MZ&BkZyzvJP*W{N_~@#KlVKwz6&Fw%sHEg6uE;zCV)fxmc=~!wuh5|cJe^a^11p1~q z&_R7xPq`Jg)ua8(`8R7J7BF}+4IxW**z(Sle{;>WRA*ZU|G@m{|4H%jQ~E1Ycm)=4 z;detYKED5afcukUHg!RV_#FS9f-=!=eLjceOu;nh-U8_Zuu-(xI!kjtF)n*7!|@*( zgr@TGQU4(v7!mMXev#+3w}k?|ZIy`mO-4oZ?WpjifUge%-fx zpp!`B5oKC@mhGSa4O=*QcK1V;=_uWbJOeW<9sksjgQ-AM$&NRq~5$Iq@a z>@~>j^j$!^G1T|^s_yyj^*Ve-f_28M0o3$?+bV%Kfp30h9n*a4f@0-E zk}Itm*o2#%_C*F8+3=kpD|=FNo-g$S{se1)WA2dZ-Bzvw|3{m1+Mta44wsn1-(!g1 z(jv_6I_{TB$^g_>GNZMLJ#kSMXA)SBU9%0(_xNp{jn*M@qUG9k6^DnC_ZDzv>~mlH zv-Y2`97u!=x5aOlL!IrzzT2pmhsS2WAshrWqn`gb=X5m*C? zgf5ub-p&uVd8VM4XmhrWPOCURT18R!i2kSR$If>iAD?!KriWAP?a#m&TedZ?4sLc@ z3$JQ13MrqQdSw$Fo7;WkBgePebslPDbt%iMS6q5x=~*%Q2Lz}A-+O&ZOnv}XtKN33 zzd&P+f@g97`{i`4_$}7foR0c6IApaZvtFeATj9<;qoz&+*{X3>J zp5To8{Ee6GRFl@d+AcqjkQ(E+?L?RB9pLIa$Nid@U!;bXITwE4I2bZJo-lwK86c+>uG;HHI{J$Coe61eUgu7B#lheJa~e)a1uQQ)-O(wycaI*7I(jBaz_wwH4_I@ds==T1g zFXdTip&+Bs1ES2t1jC2KfQs_MCNauSKksQq^OS7WxoDllUY)rHR|TQ^?P<`P1!Sq5 z0`KR!%c8FmkCOkee~%Kz;oJllhQznAT*0uG_FASWmg4s-NO&t^n8ffAAm+c4lplA| zJ$DM{JJ(xqsdReQrMI=^{$I7dRajh2w=LXQa1RzN5F|Lk9fAfA?h@RsaStItaCZsr z?(XjH+PG`uaGH0Y|2zBN`+OJs;`B{FPp?&7YgN^(Ip&yB70(5uAzBW*OyOJ_chiC` zTL8O)&EBvhpF2|ffZNnUjp8$Xk90TiOO-gF{W0P0Y}BQEuHD5a2^Mfe?Nje{OT%=& zhpuMr0fO)QmJ?)_)m(`H77?wlJ>fBozV#dH z?MW|sG0vm{Yqvczwm0d-y-Yk%y_v~^w%VobzkTwjdyvIs6j8J@yu5~%tBqzv&{z2@ zP0r9sR=pNrJ_|fqT|HP!pFV&(SNj1%ED1P*7xIYuk1K@h&tLmW82WEvdH9M1+_n~P zd6Fxhfi9bZPykB3B3-R7M~{Z~+ap4Lj;qPFJTT>aH^<%ZT7bIo<`+G|mgiH!43wHF zdo0LekNknrQX_(SHDNm^_}+E>>Be%I1F!9#9V7kAj(D8JkSjA293YVjtLV$c2g=lG zn>kmxvPLe94Ic2IK)=rIihFg@u~C8rzh2wrOTrN;aYiR-X5oS+Dq7m>F)xk)fRPM< zD_3A8I#cX2e_jeOx9{rc0?(0Fvlm6%PJFgIR*WWt^3AG$j^i{nOR_$j>`n)7m3tX2 zD|5NcB?>Ls7Y2yTmFsXT*l!BiURkJgZTAX7SeH-Z9#J^}(n4h@uRP>5KS$X{4VVZj z!_B%g7+6T%r% z&XmCkUK$th-q|3?$AkPtHYxuiWlpNk1?bi$v7Ku=ym4l`L|9Y zLA-bdY0hJ6f=)gHrCUi)1AR8kkQ!Vf+Nqpr*T}?vXb}a-LppL3rT`S_b_cbC%6WZi zt;f{YPD-3u!00byVu;)aI6s zyo}cC)FnK+`pbE6w|TMoPkoP_TQT^im&tLp*=BNE8G;c0pKi%5CRqTjeyeHe1%_lo zl~TQ>vF=TTqMW?Fm4%X10Me9o5CQhB#5-eZ=t79I?E+t!_zUrkqi5@SM zud$h}GP{>K5E6A)Hcm&D>O`+F?DIO;e9vl0;%#Gz`nSRUnPHmbgPl=bk$Zxl;L}nW zyPo6o)?o(h+bFY$cf=~%KGSK1+|uNg`#8E2<#-vBF8lLxlr|WOdp6M0YqJ_(G8h6n z+|Ik_$0Bs<3^w@PCC(VYoWm+ z%>q#-{E_XnSA7l4eaM_+$<82lO`8|x!Be%i4N}eLBWvy$>hK>$6$O6^35I>Rba(ix zE!PQDcDt;(K_K!j>X(l$(=GVRg6r$kwm#ja&eYNQ0&EPyq(D#!&6l!1Ts#AoHotChmGFyy0%-RhX&<~ugzT-T1Y+%VZ_p*PS5 zx7Qn-VZRbJA0!+d`K-2e7p~bP9i&}--&A^%Zclxk*Kw&&@VZ$%vlSGX{swtF6v4%X zO2fzX?z3AL?-P0ffws!Z;k#b7$|N-!W?W8iA6Krj_&2&&YrUV zP2ld??^fG_Bup>E0g`@Ie3$sgezR=XJ*9OgS{RHUTR$Lr8D{~Ni1jY44a zVYAIKdI%w5w@8iGB7Tqt4rcZr^uYYygMxD6r)?C07jfD5gfak#M6>~IiddbOv2buy zl$1UlAqnlx|0E=6C2ozhXn(45##r9GWJ`Z&xrHm&9(yoM&@g#Aw4Wmd&fQkEHoh!u zG->24F}0t1=9KL|C}rF>-tK^k?jO`gCql3xOIOXNCy)5ocf-dg-@Vl01a{UpsLSH# zi9CgNaIW{tOug{+&6TxXCEk%n4|y1bdz*$K^S~}?mv3*s&*%PV2-4fBF;qq#)ueb6 zU+Hc;%=RH5FS%9`lr}=dEp6FkllEJ~#-aDR^9AwA9b!+(O%F;^pq;Qm2O7}}hQtyn zNT;6EHTTP!+YF=gZJEUxL~NXp54y4YPN#^(2yYI}!WO}2AmKAyADGTsOZx-sr$ zMJW!dd^*f@-rtOqPCN7G=|_XwhR8651E?s(zwl5}2z(MvEI~j+jK$er=Q}LTrl)}-|@$nEGa#rdztJ4r*eJL$5I(`|?|B+_}h7miI3&u!z zU;!mSbn#EjOQxuIW%A@}CJ{0X%GBSG@QG>l%i)0xpM0} zFUP`H)8yrZP1Zb1uR4x$^F?n;D6e3F7e^-4T-K`L-qD))y)iqcedO0MHnjl#pE)|DM$0T&W6p zDo4Oc1ug45-0Z_3a0u)BEzG;~Nv8DgbugOrqMl1in!d26^H^Hpp#sST9dPkg&B9r` zBo*=C3V6-KzGr>c)hXs^5idPwIxaa+Wmiy-FXc>F?Cz{=pS)bXXL<-5w_ou`XSZ|U zcdXmhwNk$rooI7o&7E}!w#Bpj9%U*c%|k(}^=K-kM$~TB>TYo)DweSOWz(k1V=k?& zlLFAq!fY%p^CFWZh0s@~LD2JXCGv}c*;9{`QS)O8GN5C8Ptla-PL%tXUQNTOZEe^f z(zJ|%f0tHu{p_{4*5jG)cd^UtA5E|NKhEb!&DdM%*?9o7(8YFz*Z9By0f^gCt|b!!uWa~XBVa9`->tvG!Ea&{$75%%(XE7LpDur>Vv|vnyBa(a|!K!K0t4^LYo;)aTFf28T56&o$xqq%Djh8OiUV08un>NArxyL$sq* zAzX|ey~$5P0OBzfZ+kRENy(q?R5`g094THh?hkihm~X)%HyXt= za04p-xQ+8&xjIKHyJdAbsD{c8rzbEv@)jo?9=x(aoB1;HTj~bnJ!eNIIk_}#SPN-` zhxB$1_1THp5@}P!A`k$nHiHkQm!{|8N+6PII)fU~L z2e6%giJrji9bakwkU=4qAvNU%-s=ry43}!}lcJo5Gm#`lR=S+%ZnB$Sn@= zXSd9UO`Rz$Vi=!g?nZD3RT=Q9y=_?1e%nkIvA^aTx4m28Vzsn!e{{rcblz>D*YW?x z4Nunn^&P-l5HMh%b`dg1(?~mh5Yeh|8=+al&UP+nyW&@2PQbE9ojxSrvf?)&_PU|e z|JYs_Npu<+8>aBk`12IdTa)(m#JBs>^ZXm`Li!&51>gPP42QFYF=P8u^7Q4yhwrJG z!CJauFXN9m3^=FNrbgIv7lQ7}P=L(fl&c1#PPN-gWv_SkZrLQRtbF$G0Uy6ypK@lK z=4HM3Ha|c&J6T@yM+6K2{Hu7K!ya_AZjZG}^XZl}SG@&&2^a3}i|!Hy$n`pz)(V1) zqQ^W}@)}sT+BiS4{p5$NY!cMwP6idP# zY#PU{Mp;iI9@W?u(&^f2R##9SLv7v`N722DwrcN}p*jqo|2EtO!Nw|oW3p<{DSr&< zB^n57=Q#CToJc1cX4g47ZdSIP0pgBt)9OB*jrLIicF5cLUF6&+C*`oYJ@ZTTBsC8jvfTe<}u=QY!Ww15Y$N35^)@df-%OgKobnX`G z7gpnd2d9)(_?Nkv998MXe5{n@*uN!fukQBdDto}2jpHx*A*y9eNBiU7bN5#AvDdX; zw}){NJDTUZMkDsd=HuF}qVh(DlV}O*`C3nc5CG!#!>m8Q-7nsnQZEE2*wQ)y?j|~| z>1Ni+@WEV+wLQ5^srjYLw=*$5l~RDjT)X}vaH_q5+^J*4=HmJ>7Zp_QE7)eyQ7!)T z#u`ULes3>#WJ7v5wL`X$#;PBf!%nfoT&WEnI(>zAc~rbD)@rG|-^3PPJ$t(It0fV# zH2##)%=WaKg{=Csx96_dd)~p(c3tghEUMpstxkEeV)ec+o?TGn=KZD52i!CLz7 zQIDF+jKke`k4EX~{YRcke4(SSxIOT7G#-n6RQu5ytIgtC9`)_jPj<#@ilsL1o18+G zRaK>3t}3PUnXAR&zXwmtebZO0K5e7a1PEP!W_A+}CECi3LKt)}!kVtZ=2n)U$PdsA zmQ|H@-Ra^^Y9cRw-bI{DpPs9JCXp`3PTW3pYp35%ZT6|IJ+4yvk;_C&{O!*!!Gb>p zYB3}0QUIGrT|G8=vH(j+`#0GTraHAN);wyr@VI2{NCDQQw4}v$&F=Q**OOaWXG}nT zT5QJ{F7atB$p%$vJWw-Sed)-uh&c^|mHNP72RFi*{EXZBkb9_;$}A=+pTm4DniAj} zWJZdGg@w-(W=&}k(?x_MQOX~on8>C8$jaYikc0#D&~zdmnkAx>a;GIE#P=n%9x3PN z7mgFJT`Yc=!z42j>MIKx)5CNOK=pSK!h9IE-9G$SQpPRjYmue&M^GeP3Qc z!3w^YpbI4aSDzC`cp&lnj8oe6rr-gO6N_-hP?v9ymdFxXt*65Ji|mQFyrHg{0c}Yj zpI$0T`w1ssUQOcbZdsx5t5M<5!uRsV{1qU*yNLq(^2-Lo*oR*ddHu z7EzjXMoyy2I>%P19{a5tov56&p8U1=F1gs0j03$(wVj*nKnqsk?3PKCO^3{!ITm$7yWr5$fdc}2xmCW!R)4Wk$;YnbaYEwvH zq-CG2mdhzR&ECuPwNHOt`l`r}x(k@*=j_va4a<1x82% z!m(z+#}?w7riphN-#%~H@H*IbrzhlAG)6T(O6-*&9Qarxh!xPozKpehpyb4$Jvu?Z zf+9NmsD&P|aqYYio_K;>WjZ<=+d6ks?pWUXz~?9_N$hh#6((^SKURo2ful9N9S25mv&Uuw2qM>uvv_y-3$wgYY3Iv;p#es zIlNdv-yZBk-+IZ7GJe8LucK7)WPia)C=I{hMW&*r`pHQ%xT62GK{G*RP#YX&*d3~o zbf-IYf7!089hx&}akp&JEjXh==iO{{!3WCB;t9l7Vv}^x=1~J%1iF|+2L!U8Ph-?@ zUPNa%Ey2&sNT-?z6OF8TyWyQ4jp|mY7cI3_?i4WL_IKD+tz#>Zq7alkQ$3AD#%0 z1@C6eeC1Yx*wH&ejUtJyj*@vMY=)sA_9b1_sp~Wjjnu9a4VtYVB9Ao)`3L%Niq$M` z9=!^@fV+1-^a6pKzxP6lqaDaeG27aoM(gph0L_r?oQ%E3 z^|7nspP4fsHhzL*{pR;;pkrWk<*V_z-VHkZUGeTd_RBbe)R40q z)Z)B3wYc(!MdUWeAHzZR?x>DUMVY3pUBHuVgVTea+IR^EQ;Bt({yn_{W(G@8vE0>~ zYKj&&XtCl>lz@;lx{i^rZO!Y6LC`m^daVvWuT^PGd{83)v+%ps?+ILlw{_kJXssuU z6_p@kvdpTA3$m`eaDHRV!l9mvsz?Q-(cmESKe|VRiiA(5>vlScL@&Q^=q+MHhrf?{ zv(2~^?932+RL1nlC#Qdp@cYqkeK~v6CW^KCNU2(;ncTo3I5bR=qC7Y?e!)3wVA_Y& zIfEMPP#OW~OkO5SeyQ;WDtWK1{w6#%U#H*>Wg_8#lxS{ea5sJtNzrx3KmWr43TN;+ zGZt-UU4GRwXmQe5>r=Y~9Q2e)_;^@+#NZ&#j{FO0RYzVIRvV@@A5~xUTFq&UKL3I3EkJXdoJ&G zBb!EeGnRi!Tq1EA>!7UCLX5h$y?bj+xO>6H^RB55=jpnB4nnbbW=fTW!@~E$GIIGB zyIRNJxx9z5*50(1v^`77P zfA~kzZP>6{+sob=y6!%gdaRp0Zbu<+YJEC=T25?+*7LU8-0{2>njb81IP(!5SsGw? z`3UW+ydzN2a(@g-GH9PQXc9cE6AVv!cUP?W@$^d1w@~ zF%7MC2~3`<=#HA~&8FM^@p|~R?3ZOeE0J(_Of_lRE}I~chExGLtMbwa`l?F9esFu> z`q|mjl7^?Jr=cMTrpT-glJ_& zDje?);TtOIo@n9lM>x=yL3UDpZR3Vla36y`IP?JKO^zoL_9jA))L=#?PYFk zGMB)x{Y$C#r@BopQ#zST4sp^x%Lue=Y%;_R;b<++Gm6jejz2l0h8|(w{KJ&y$g9=Y ze_B9qqlU1g11|4!iTyGDW;kL20K`*oX9Pex_!p*$ULu z*4Eb4K*(6VqkuARhY3h_H;VlmZ@k?k^6MWy`2V#3ubk|l3)9I4?8yvxujsACI&Nmw zBmr5r#Eq+973`-I{ZtI<>!*kaqwWc=1cizpHwLSAY>;dWe@A@EkPl4l&T6C@77GzC zxZK>0kB^vC2*s8a=J(_LQG+)Nr>=X2{VxW@FRpJauq7h}ox`B`eIPI`Bb7jzJIR?Y zW7oplDek(|l|lyt!erl#?L^?vL7hLu9RZU=RFCfx;C&?=QGA%+M&%n-h>WtRD(b15 zmW;=UUaVQJF8hwBwbv40>}gk(IF( zjankl=bR*F+%5BX(U=?_h0%BrR^E2>CB9qC`gDV2{9|YVO|A^TSb0WX+g;SW@xD?F zIiSMG3rs}3SD_iMbu1tYW}17y)(7LuN9AP$9&wf5DMT7x4A>`dD^}gJ*amdeG+NH@ znu;$m1kw_H0V2g0s$h+E}gK$eBRZjc3>SZnO-2 z^k+TE_-MB2+Msao%GxH1_kLMM4G2qOM@`Ndn-n!jr#-T*!0{txvZ+3H&ESYq3Y+a9 zBzFLgDuJI~c1O@@0es2&Ex&%S2J26@eHq5vxYbsTO|+ zAz~>k{-GTmL59G3by?ZbcKQH$=s+tw;WT0*{LK1xB9fq7d|a<6)OUO*fW=YWu+`vG zalMGe#l|}_O|(fDV;r}Cq1Vr|kXR>&RWtVHu!sh9dDZ9h*@2|{vT?QhrH{x2lu7_= z0ASH*r)RJY`yTbo2LKrKK~ak6G46a|$#Un-nWiq;l1<`vM=duX8m9{+N*j0XFjLCg zVMxiw;p$UvaW{Az%1KvM5Ds-#9Cs3V6TrV)ioyoi#(<5B=H)d;zwL_2bB-P{O^n30`5J(GJ$idgtFiaY03oc= zu=Gq7a27MV988mNfseWj=M zC~NWR*pWH(N)AQ!J%??q}q z&D0$-WB{UmQ__-uGH#=?HH>SYuF8Qxw#)DJXH$LOHAJiUdO$9`o~3w zPfyRvg_M<*ArW~cbbvHHcpFF=0?4Z%5D=6>0@Sj0|Jk~?mqVw}Ad=^gf-S`h`NCk4 z`FsMIS>XZZ%o<2paRjn%|Nrp~ez&li-1+G_(+EVOfzKo6%ba)_!+BUWJf%EX2EVc| zfyE-Q0GpbQ`wv88a^p5i7tj#_n$-MbVQ<<%7nbG(g9TZQVOU0AF=k)Eo(LHGY;s?Q zjU~u$dy~DG%q;nyUn<-%%N)3A67zXqttHasM?Xvo3bEun7mrP3>53!Mqv2#fAnZRc zTkj>`99X*)>j3qBM?7m{s% zK#*F(WazOg;7Cw|<6)xcr=bHB%v2hFf1Sj%{0k%EpefJ&3-g~tOv?WJm7%dNcpCa6 zd4=R%u)|w_cAr&+o4hFPV2i2F+(rI2lI%FKYiNU)hgZFvCE9l}sD;Q@IPl<8?`1Pf zXwSM;pM|*dke1Y0rjb&Xgfk`vxACoO9s1bh*Qv1NsFV8SeQgyBoFVSL^X9|xR+Jy#ufKC(Ng>CM1m~6$8w}@DmGb82k*Sje>SfsO=YOD6)>fHoiJ;;)4SJ52EX}C zwN3rnwG)+fY|3DpzXqK)t-AFXVG@wiUF(Lvt*QAG$gHF?(oqA0llSnIE)Hu_M~t}I zi%JYXJPUgT2kb#?BjKT^Mw(Q09Swp|1c=uh!{G+bP^yrRibf@)nc{Zqgf<$aK3LbD znESlM!PWB*wwyng><(fD`56>|oOj>M`_s_kMI)b6u%T;g)RCw>csI7`>hCyuhv z(aiH!HF;1D`-@~{uyh|$t{FXetLuAV4?XU*Oo5QibQP-^AK&imRK{o(sUWKW{3S(} z_`jXUBr*hVqtQ(68sTRsY@)mQtGc#D7>j>H8HLgEB1S$=`Cq+sJ#dpF<|x?mEv}~R z$}i5@?m&9}y-C;g?G5jGEf=LPwqrd7S20vjUnx2PjK>!_uNa<(=^qhA`v%HU$+41B zbUSa=VFqR~a%x0Us`taqmQ&i7p2AzbLiQ^>XV!jZrq>#!>oa<<9>W59a&~a2zWMey z*-9*`J*(2G9r^G?yw((K7a#z#r-69pCmtc8vp>u4V?B_k*`Xn>#w{~*$)s7g#e#q1 zz;%kuargy%#y`B{<$_c*8^JZ1IScBPwQ3}VlT3*jg*dUglRs!4k8G;3H==JA zfm5}JM28Fk(W?p0Z-XZ8yD@Syk&|1{nvZ(6?D5QDvW4=@Ac=`5D5YDtIJg3>78Y;v|>7kcli6= zFg31+y2aWwAyOW^6zgc0$~Yg38bf-Wr-?)sM`8BVK&;=5C7!HtoJourQ9`SM?298B zz{R6;DR8QhHfHnh;6vEwM!-j!PrM%Pj@=p|y%zm<$6cmADV*%zqa>n}=>*vc&@@sx zjd288>G>;?rWrI|WnNI$E;Ph?X`1_~{{W_U%XCsQ2+Zq=itKtu7_{pZ1s@zt-}V3k z@vjFb`juZQ&8ildP|R%isC%2ijw6tAj3=$*tyLRSXi_+VhfvDf)$eUrOfaBg@hv&| zT+W1_b%Eyn@1tI_woKPj(!Oh5ZZ{dEpf4zaZKh>SPRuTN9?NHM&og9{K^%%9*ZmTx4;GyFd8W(Q837NeU_&M6=P#d_n81=!b$xoRJa2TCC#dX3wqaIjiv)T{l;d$Cj})j{pq~2dCpqc3MnE z?y>D_`mqFU5gx+~6)RVh&XY%Rkn99yb(2e29hjzg?6Nz~O}e&8p`zdXe-rlaSh-I8 zVX4@UPPMY&0HP7lG1NT+3T`!B0@THJ)}o7TtpOq&rsL)n0?nPSJh%Bg#A*h%(D{<{ zrZSQnagkYZ8x73wKG()zEi7hrr?Db&d`%hQtChTpr-uTFiath0MowJ4ZMc#8h*C>r z5UQL^C#|RZQZ|1SiK8P$B`uB$6qs;o6lF6y9Bli#ae-#F@hzIqw@TW>OB4r9vihTM&&yTtOc z)@|vIzQBlBMN!z%qtLqz0^3tjiwn1`e!XY>ypu+oz^8-F))yPu@;w0d!}Wq}z_cFQ z_c4g3G1^9uvkg26T5S91F{drNXj%7C7NR={5(}dB{CndrHVG%731DQc>Y%j5{%%@u zGUb|~;C3>*mnkiExX=CVLq?CN<&9g1(#iRl%!mH$$0y~=)0Utw&fUY!CHxPpJ+y`w z$bGA}MvPiY4f|^|xAnX@iDec%8=6|*qdF6w;H?Ja~5tz)>yr12`>IyiTXO(IU)x>nfO`|(3UO-@XetB5|k zAXFzX4$g#{gxa@=7l*?F7!~rvK!6UAm9vY5*NA^?A#^|VO)+uc5FJHf=ORG&v6Uhm zDv~a+t`%PYII4jV1t7pW49x{AxqnSXNrnLap_^%RDI7A=Wv-_a8g8yvybu5^H`=@_5 zb+Q;b;6QY;+D8$WQMb-qjtp>@8emGgYA+-8@U=6UKC|^wQ)x0i7(9lkq6i+syHo~H z^iO74mqY4@ft?i&dW_u&^~?o{GNwO5`8xhz_`a6^MC5_97r_fApq>1oe;~9dhx75m z%kBB&bDAD+NJNCKl~qd?c!wwhMKj%6kl6_XC{LidclTER!leYg}%j)DzHbQ@~goKcVjU87nV>WGQNJyAT`tFi+ zC9`hOPMn$fK14MwN*CMEYE_!FQ!{?x?=oz`AS}ENLPeERIMn1O#Uso#vne>3`TQ@t zBbQFE4#Le0xM=-n3xYAor3!KyQ&zRqahsJIXY_sn$;$e1^z@H2jY4^cIdE0ud;t-M zCDXKswp?>*1QG-}-GU-}G(GC~JJ7?cPIxPb*soX?t9 zZ=0bxF(MC-qGS{`8A+W(EjIEZQcVRr!U;O^j-%`si&A&FS%1E_;_IE888W z%uHsWwdu$FgR%lapc>Y*(edZ|a{ln0W;yMn9uYPhuK|45;eZd^Z`NBE>;+;C$spxd zzx|3N=l0Js9yCmpvJ2KO|1G{O5>UYQ;8ErH2bwffxrrzrJuZ$@c49qGDdIliM_B#ycyS*~ya(P?IYCiGam&wOd@;93neo3sJxn_~HYxij>;`3P6wy zje5KDq_V0xhenV6BHi4!{2t)rlg9%bYi&UdNqs8r?1M2O2SW-0gQ})rHLK1TsC{U5 z2+G$Sn4zIpfcJquL;d(ip_{zzXN33gfN%dFFw+Hi?gpb4it0tZX2@FN9_SYr+{qAe?p>^xjj0YpeKc2P3!7f*j;SF+_`7JDGZub?y;dR~n|2bIX28j*7CKLI(k8LGs_lCT-E-t|S z)!we(8vB3COj17Ko0|WB-*($h70XmUkD_1WkXHD6t_5!lnuc>#pm$!=2 z>mr;wDL>|IgV&q@sm{XCG09H143p4+EQz0k*aqAC z?&y*_wIT+SlSCV^IUgio9Qn{I5SxrtZ_6g<1XQ=^1+|mvm5T}CJR&^4`%7ZOeROwU zi&h2*rDCQ24G(Bs28bHDckW(yXcf*WUpJ@anoi26&gvjZt9D~Pt^)IA42&fnLrK6md?yk5ocT7NH^p_eaGAZLAMS`sN z@(G0D>RRsFfB2)}Lup`0wbMBO`hd4Uhji)Y+F)N6?OEx^%_0m}sJXSs%hcX;-QTOz zhV4|K-6wbw*ZoTCz|>Hs;G3U~xG-VZSqsp)(U}mai>{GdK7nDr6diHN^YZ{%>aZs!(!`9Q>2w*Tv%JI15V|2 z<-+02jf&_0%SAs&wjy&>tCkVSNb@Jt3)gh&j)F?FcpT(pog_Uv!WrC3}dDy%e=)x(Aa7IAjH)w z>}N(HL*w+p1t$gP0R4q4?Uxbv_frfLCY|U)f>C^sYnUoA_eQekzd>ET;|eE2$1_Py zlSI^JY|z*d_%e8Gi-O~_5WlgZcB*R1ge~VUGsXwKUtH!2ZRrxP_Cs(w0r6^IK{^Jh_zkKw;O)hv|+xc&~M?~6LLQ+ob z%2Vk6G--m;90UTJFtLL=of})t@qS`^DJ&wyfvKroZCd#Y1- z9$C!{znt@9(W{sL$txhNjxvSAGfJJvI~C8ISpHM_dHK3}~N$8ECP4sPn|>eA97 z6t(5{tE{N_eqYNKm%h}qO;`YdtblM3A4vp-WSWHU+Z#EoMh)+Te#uo_oSK?iSy^c; z1`X{wqkKNuPql#Xc0$F(w#g|et2Uhd_C);(^=}X2pmTNaNfMEtnfWz3XUsC%Su5Vr zjAmdWV{nQa&fL-x$g`YrKWU%A0J&GVj47=;IK8khj_|sPn0QfqZ@w4@_3eURfvKr@ zxx7BXWv&kfB+mt{7WVt)8+Yl6e65XLQZ8y_7Qi(yrG_MY{~w(mIk8U_JK2+JFHHjf zIQ}!0k+w>Efd!F`(N1M&}skx diff --git a/docs/images/graphs/vscode3.png b/docs/images/graphs/vscode3.png deleted file mode 100644 index 28d0575b46a7229c3c5ef58d14d6a1b005093a37..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 53379 zcmd3NRZty4_vZj1!2$#)1PSgM+zIZ%-QC^Y-QAtw5ZooWyI zR_%S6nwgeUeNT0tpG>H%w8&?;uW$eWd=?WGlmh_BRRDmfhJge>K}RR?17D!*1;i9! zU|?1@Wj4UKSPnue4)WGU4$iuEhJdB6gCUK*zMY|=mA#3z!(h^dH~G<&ZPG7?u8)UV5)%0=xtwblyI{Bp&eP2-)K<-)SLGeBPMRwsX$& z=kZad^EM`AU0q!tWC57(4z00`tpLpT0Av9GD}exf85Glz_51g#*oPk$dec^eEGnmwfjkMIP#o%fc(eSa#!8aky7 zLw!)3@2^-PpQd}H<1Na3c^iuLOV5b^`MZf1pJ%<upY0P6e+Ta4FT2C23^&-qEo_H*a@-S~B9W**vlfQQ(9NNbkcajm9l z@%Y|urqufTYp0erGufyky`zYzVlBQ#z0?SC?^ZrGzo|EAMw4R0+$+kGo^dp#!>`=L} z2v|+@69|gV2`&@(5M%xkAP5HCo*aEp9g?xO=A7$+0yZ%)&SdB zSvs#Yp^yNAxQ_uJUBXt5;lk^wclU6y7!E6c4_znIzUsanEqIq;Z)}bs`d(GC@_Om> zSEp>yShn<&=DZ5`ucI2UJ&tw9;m9OjWY<4E7WdG3H|@{lJ0em~WUW1&P|Y1BW-u9d|5mG;My5Nzps0w77Z!7AZ=l%9y9~>RXmfwQki#)C z#@-9!X(Xp))TAY6AdCJL0dr4aS9JvxX!m#`5z8Rg#RPZqIL1H#{J$w92&w0wlhYp5 z<;fjZQt3SIX8*2~u>rou3Rn2+DxGY4Lq(lh6rKk&dAYC>A2vJPpXZ>v6L`+U7qlMt zeMe|82uM1n>Z3chnF7|t!AbAw7H)~Qtuv2eVL5Q);sYM zL;6R>FECWM3EgA66)`1Xoh;lV9KB35kG177Guy9Y$7?Mx1jlY5Ncy z#zvEygtB&*npmQMzeIln0U&_dO1v%xko(GMS&jwxT);$M5V`8}d(~hAd^sWNm&tT@ znOy1aES~F_-mWfr$rX7hct<41jc+b&Oq}};PjA-i&8%(uV$!G!-OJw)2#@kz>Ps@YJ z+a!k)T&MN=``7lJZfqeR0D@PqXVps5?Ne1;k}p!OyMwM$Lw$GN^_vHW!rxS%r;YDgCY*~iInteJ_h)nQ8@STZmQSt1 zD%|iSUp0(PTP|kGWIB_l;Nqr`xPKHLkC)E%k}$o;dGYX`mx%;9?g>7<-qn5^d(5wr zK6Shgj`H4d&ewDWZAy827_aYQzyrX7lJna}Z1~56;_<^2k+r3})3v&IW4rOpkugb$ z$ARVM@7yz(Q65jl*N@=ezLyrKxK0%$?1YfIeG4f4gwd{JZ~Si8K4`_eb&DMOI_x{ku-axybZj1Aa?d@e=uf~EN zA-J92aTcYlcB#S|~|#o(qukDLQ-HUxpeh{?$xh(HDaY%aGtGE<82(bDZFit3dE=#jmFsF?Ip z`0@SZX^nDr?-E4Femak*zjW)(oYna_Hm4}-I=1?{PJ5|@{?vB;MAqI9J1ViS zZg?86H@%9l8FtfM@mHa?Uj#T4*S+>0OoK25`=t(2@&rZ6B<1AWc&=S4Yef7MZt8~Y z;>>wku6^c*f1B`T5_=4v3{Cyj_>3O7&usV+X>Jt#+~Z~d78H$;(LsD|qxSD7{0rW? z5z>9vg4cHCUnU}7rC_6ag3z{&`kx%vvtiXi8z0qbvmsa3F5X(K-ak(n>*56N;2^fO zKk`ALUtWwLiOBj*8Xn{02q~U=oW91>=(Hv;m%@Fzv3m8jNFZuI=3v}-XYsz;`+2Dw zx3}ddZoiQtT4kkZ57ioa*pHYFMNzB&&`Pdxz7OgCwq;eVecPDp?^H%w zfAIvrFG0gZDDs=AS5~ZFI$N|c+wI)?a~Ug$$A0->3uAItd0KQ&HL?Qy1)=g^3CA&GHWPK_rCK&HbCNd2}zmfvZg5U69F{wfIq=j z_kMDa91R&O_rt6*iSRVl=7hF~%lT}v^2FkO@z1AmLgo`s(?c9pYG%DTWnM1yK0G(m zHGHpmC~n8?O7FE}R?B`-T_YCW9wV`+2F^dA3S*}6)VVOr4jbkU9E3*JCWs;vaid`RVyiq-rmPqISsYm-fpjF;_yBME_G_c zX>^`XH|GsnXDjlLLD{Ta7s43ugoan?@2=OCy}WN;!*o>zIKT~WmDK8ATYyir*y>?3 zTOxQYgJJ8u`4J=i)}poWTUoXig7UB#JIwXv^%r2V@+Fxu+OTm#3=0SUI4Q35(?TdL zsz#U1)q&~Hi5-oX7eitjMH1zwZ)@P=#_o4~x%Lxy*2-<|m$TYnzjHPEvvwx3)-<28 z7uT7zGewJ9$O@~9ieBgjcTmkZy8B&#r}z4|Kg4xc#rRbY)|S&stWCc2Tt9 zI%^Vrd)?Tc*|E9Z$UgUWQclDcoRaZ=9xL5^RSFpc6?obNONk7hkZU=g>~D|No_%F8 zm!AE!KatA+jmf&Gs!OhcS8>MKDtC+)l z*t2C#1@8%_lwsB!H$(er<36diHh@7_0Y$Dr$KeJhZvqyCPixxS64F;Diu50fp#3Sl zh9AckG$Js&c1S2dN`~a;k@&SYxLkjdT)k`=_6vz(Pkd@cr{^eZwp6cfNw>ZTB$AfFLEk0bToFT|bt!JDOUw8!ke zN4}9bNfQdL%LrUjiSMt@;<14@Xws3SwkxVX4QId4yFB-kSk z*cz^#P|4Dw@CGfQ-1K@rCh#VFY;4pNz)@sy@juXPXLVJXe8BRCaArPT@l-SdfZA@Iw)tt+ z>hy!xppELo13caP3m71Ww}$MLk_;v-y`Tu_-QFjAirbTTe|^kL^y!`=N>60A&hb{G zynlUMgGQ=c`2$|_hp1NL)1=JxHZIU{P}VY0;@#Jp`yNEre|d2i?tmI~8r9+${hsne z)iuc7m`WrXF)TbPxyDswx{6V9nZom`Ewy$wxXI+}Vy!AW0`UDh;S1m7lyg+vx;TaAq;1_QaRuP63H9fWRG7H%p2z!wLT6nt0> zO~=e7t1XY2sn_C^L#Cp!&_bD1W0`B>o6eh1F(2!)ss;NEY-ElIzv(Pzr;p2GKCJWz zNN0o$bBbf0OXXc}H=-WD&E}L?vBKt06meMFHi6e4A9N3z?L!UloZyG%vR`&BMoyX; zO@=vBtM*T=le>f!feYOG=5MP35LOAVYje*o0ENZQloxY#|EEcq2so*=9 zgMDxU=&;?+bR4zf!==2Y*Lc%8w3`}b+%izd8ZxOIeRCxK5skg zZ88l>I_*I_ z-Sz%{NPK5qp7G#0RpI{Rp|nh4^md}!saYfs*EG#!e9R8~QC%2?TDbVTZLiI~RF)<7 ze%5(87CH6}d94HPJDNk8s@6izHbK+MenHQ=GN2)!KQ0b+!;^fe*&f~~A9pM%qMerK zH8kI-aTuFVA`|tEnZ}eSf-w9o^Ul8BZLCdf1{0g~5qXTaIMWi}#kUo+!E0h~!jLLU zO66@WxCNc+eU3q;huO&U#o>xIHy)F#+U<6lBHD7z#;`k{cm7^AJ;vQVwyXX?jg3Hr z>uUaZgz$43{`xyleq5}i%fs$7XKVhLo6~QvZ=^79o$ke=FcP4W_`oDDlm*;1`*K%d zxgO10qp!v8{M%Wefv2^3W^Jy_ztmYY5>1@Hyezc!C(b`<>}QrapTuE|L-N5;Y~FIu zN<-gOsc+q}WMEA)CC|5Z&*7Mibv!yzUF5K|We3q4-mEqcZlK?_eA{GxmYEo{Gp=Nj z(-QM`+vK}@@>f2!z{LL1ZKepMNRk46Nz=r9>ofU@^Z0|ps+zg>P)~R=gE_(J>;z~K z5PIbFH>%bftwYGTEbgaY8WwrEAb}J+=TizV9mj_@_c*v-rrm(e2bmH@mi{se+@+KH z1%hWXz~|9y{I1h0^M~c>0pA=9g>ARlr)uSoS_>w{U!JK?Y92{QUQF*Mn_xpzVF)OyNlAC zQWJc4N{j)z)JKi*V4U%-F@cRz8Dq_wm_JKMyvR$pd0278zGdu=d5e;RMl{+eq#pq} zp4-j7DM;yL*XiL%aZaHId6Zz)FfVq6(dJ&BI~8h0+bcma`Mnwq76R8f?ry>BOKnDM z087F5b8?64TdMbdX|wg#l{VLF+4Q^0v;aW2l+eYbB{mv>uM)=*rX2XY4GluM+WhQ#~--+IYnHmsR_e6oF!zD*B6p_niP3s%y52`Zpbx z((I=ap2S~fq+CYaEqdj3GJp+K>(CgF1!78}jk0)UY|O;-j6D-~&Y{h4cNvSY*1t?> zNN#^yx(=B3C+E_AYx1c)ql5d#D=Y@NUNlpGsl@36VqCNa?+u)5$o_1-pNq6X3XNB% zmKukb+q*KtpE3E|&wPK@-(G}_9kZSH4>)W_HrFq#k1JD0SdG=@04n-YAO#+esawK z*(?OUVu@?l z?rvU|tu`tVSY3;XNGwOLF}FnD9tV?fhm2xpMX(P@z5vA&?^l7C&I$I23SRE>NW6)( zURM!_N*;VuzZu&DayNNxlyy@?AN9+^4@h)bs-_utN zYxNrq-)`1R3!VwR-i40JN9HW`*6EL)J|mb{yuZBpTFm+gchMwwc-%i1ASFj?-uBTA z1@?W;5RrYjm52ZXb_=W9$wXJ3rs4K=TyMQq3uotQjmNu{ZKY*g;KaeSdO_>%iERBi zK+f6n-ZoV8ZF!GmEu*8OC^ymm7FIztP={Ll@%s!6mw6#n0ps0M#H;X$A%S~uB>vXN zxhktX^`|6biOrgAMU0Ker4rMHEN!zfQSPE`pBZDkkwcD{OJyW0mA40NZ#Kp0BMxdx zwOu;1!OlenGC%I?iCcWUCfSJ*@`gaDj?ImrV5N7Hd28&o`f^hS625c!dDu)i z&q_F*T|NT39p9Gm@R<4lX!Nlj&%a&sb*#CsuI{vAj>`R-3tYm+1Rt!`niH&Qyc!aU zwuYHPE44wV!B%0W4uU1h~M1EzmI8R*mx zGw&Ae&oX^>9T>lJp^T|p`W)26e0ujSxWSp=vu;^T-hoKgYbWq_rR=?;Is}nI>+$wh z`BnC14=FkVV`+_6T@j*!jJ3+`GCV(7UBf?r_KUc!gxJ~Tt13FK(4Xli&!~c*j$r*k zEBP%sSgEafTd<~E|Kay9O6@DNUw4~-_c{Aft#nwMmx9N9t#xN|t>urYyJ|6=y|T@j za_T{ar}fF8x25BN=?c-^;J543?zS+N(DUjIJ|qcHpZ>bV(`){DHnUF!qE6$)zn$xr z0SwPBf3D^{&5ivG2n+^Z1jsst#fglKV7FbLSjE1EbvxDvb`Q<3~*>O zMI%3vHXh1&zn$Tg#UFnWaQ@2Z(7hb2 z41Nq*!HS*`KD|w{fhIE1m=|k292RpwN8Z}a?#rrLIAOQh4r6) zVF%afkVo}Tu!y1gFC~NGe^oLd!TtZ!^ncgDZ&HW;rW5VoD3em8H+Od(AVa=?U3&g& z62$*q&;R4l|6eyCurM*fiVJYbYJB=R@Qx8V^vLf-FO@oOV!l7%2KNm5kd z|Na(fz?L+A2n51y0Wo1mr5IPlvjIEl&@;{hXbW~b-uU_X-{7!8>*@*~v+~;_&+?508jT@~ z+T5ldO{0&?yDZ-+)Q-N#yAK)*qGfd1+;XdS6B}_6Ec#YRbF-oE>v-qRkdd%%P;D*gt{U& zS;utfqil1DN58~X)ph`z+-AaUc~6UU`?n~~Jp=7h0<&0`6Z8ZDviRd@3CLF=44ZXl zJ+b8ixbS>ohIn~N>BzA_3`&WlINRU8;uxo7xn(Q-ADDPc>Mrtf9s10B?{QkQ9}{{( zWG*);znd=m{jqoZ(-T*^o&?7*O*73_P0iD$Tqr8#bF(tDCk>N2G`QvV*C@`6|Bc}{2q_V7DrG$n# z=b%W3tao1hr5lc2s)2PO0WIMNR(JQ;{5HjWk%vjW?^x>YKU9%2Qn%UZ8Cpu=_qkq- z13r-l?4lc0Pf>AP7xtmSmUrZq*CDnALqCX;K-P9N6y*HwD3f0@qo(rw>vgZ6rXEoc zJ?c+xy#c{j4s%n~tKmbZ=oJVJ*d&YjQdsT*d|wL?lV{E0j#cC^(7u%0I46cs=&am+ z-W3vZlw7!gC4rBEL5gXGTU5#vgPgRg@{i@&)Q8M{(fCF52_S&S&96%^sXTxHdOJ#E zdHM;ZT+0&OgkZiKZzJSGYqELTQw{d?|3=%=>Wd4KN@cKZnpIK%m5&PDODu_4{9G_n`&LjLQ78!^J}YEWaKAO#ejZ<+f_7Yp-chTd`od)+7_oVoGNpAGK}&IPJO- zF;<_ryUQFQAv-#I*}e45*W`bA0l8QCx&CINRS6G@AL-qH{C=P{WQTZ);dkAM$3Vr`K4yKN+in1})Z1;#c8DUBhfv-8YfKdgO;H|mXU;;{_arUozhC`QyLWN|3J z#I;HQ;B$=@6U9O$V4PK4_)6T(01HdBi)$_hB^>bFQg>We@5mAV;|D1Z?d+Udq?62& zli9-32m|A4w$*~EInFJ{#1~s8lvy6!^$>qj;(n3A<}&m-sSR9a5}s21nQtWw@G22w z%VAexALHF09!&K;KA{k=9H3`Dvarm~H>m6oZ5c`8B{PgZZT_f2$28F5@+lhT3M>@~R3adKM!GKK zjE9T*M(UsL+6ezWASi|@GQp>ELo$lkNpd#fkx1=mSb|oQ*80a4AfT;S;QYKxbcpE) z$X23`rlEYJq?*2I@~1=mihZ``@HSZ@_Yt7H*=n}U6>rH~MEk)g*RR3mQ7-Gv{XhT# z+@SAIB&s*l?>p{l#zU2k-Mo-%L#wVabmmm#-t-g-1LQ4m*QC%C+;EPd5dxfCL^P!g zc9(`QXrDMWCnJH`L7%Jg(kMwaDq1aaV~Cs_LN_CU-oYFy>|Ig-C@La2w_A{n+;MYr z2;o>Py!22LE`b2T%$8A%O7r|ArX@IOZ&%FV>ChMf*=6c9PM*PRTADL%&jR=18<^IT z&*TGsS9_*R`FVdOqR|+$hzOxZ3$YJf)ev*)qOuvNh-ZrlipOKWLRIFf%z!;Cg`Wx1 zvA+=nx9~J(h<=f3g%cA$*~9(zg_2oG`#1Cb3{~as3Sf@{S%>+D`7;+E#daLp_C6IY zCBw26^#O?W+kuybJQ38UoeT;>#v-rmnwI?^pENdpY=Tm9)>uXvXKCd%lfp7p2g5Y@ zdH|S9Qf2b<_ZVlLz1-UPqU&%S_>(Lg3lA9F6N4Xc7L;fh){tM(fxEv;5@^RWv9?wQ z)&|rSdQ(K38!>-qca+H6APbnluq({!Z0y%|pe+Cp}1@=zG)UaF+en&|N*1#jx1%H5HZO*WusGLI5(fTg-{PB}p z>kL|TLJTTE5umk@mLWaB=d)Ni5L_3X(V#ImTdg^wuz=m;-?l3|H)&3VGeYICNd&&p zGOxl~(>gPlc@+P-fBsZ@lob1mXU)J=apF2%Y~8|#Pnp3dlf5FUV9zG1t)ngP7q{9b z4dn-G_Rkwfn1y%H0P-XxvRI+sZ}a2kv3WBDfZW;JFekY+1#&#_Ll{~N&_1#DCnSLV z3oh?hobZXF{e@~kr&jq!MY+lvszyZs%-&M#)B825e9)-_sYJGiABf(YH!qvWxsDjh z8X~~OF)^ootZ14?!9*jcrHdct7Tpu~uYZmNp_t6uCxnM1cTvZ?$I*bSb~W^iN9WX7 zL^mb0XVcN)T5{WZn7bB&sjHG6A7yEF9i6Wfi~}a$G4|oWo+h8Ug+#L>ak@`YGAYO< zcuHQ9bjW^zB>a3}@05$DV`@j?0=JzXT1*%J0;7&qC8eds56Dg7*sj!17sTPzgx|jl zT;9WCjOw##YLBDt-b~J7kw$4e;G(+=3nc6CaEYU*xW+ zu!rYQB24P!8LNV6|B|682oWWPTKOR8soR3$@S0qHYyIs?Of)XkNodk(j(x=Cm3ayT~q_E|;Kf++6)n)*{7@5AKVLrR4^o;BXJ%Nrn z?T%)RXZ=uPeS^QU`R-#|3tq6jz~nL_4CCjN(`{R@_VEK%=m@^#opFK$}pkD}_~h?z|}p8!gg zuhfkl8GXH}?3IT-hwxX}`Tfz;c*AA;KDIf^i$=vYZug&q8Mo?|g{=~_U78l#n_nE@ z0h`atl*@kpfB#0D8J!lEAtpzdn=|`FuVzvkxy`j^GTJ*P)>~+7RLh2IXnRJP8r0EC zW6#s(-=Z_qL@mGxz<`X#e@rFDKu5ydIbq5Z$Do~Z6H0zJPE(1|Ez?(|1L8Aeh9Yvu#@M0Bok&t~Xs0;L916na^6f z<<$}X57jS9Ijt*F%X zDXS_E?D`EZp2g9lz%b~HVEl(1VJxNJ9RCzUW~W_$P#)6~IyI1xJ%$#IgUak0l?DJC zN7sm%w`BwX5AOhcnE(kQ%4dT(&uTs>!uWT03*dHLA%3zlCW0Gdii z+l$Q|3NeSFNK1|1ggm8&Ytt7_SE}e_h(= z13pZ%nu8qjUY2Ii-{l0!M)5@;ffbFcWW}6qh%OZ^*@BGU;we>-8xELA_|4Na{GdSj zrPg_$>8*s|3 z*KNp&eo9%^s!1;-DQl*)mse3*M|`6(FR#R%)IpSwbB#+wW@7Xj{~d+Iwv8VD$_Qoi z*>LwM#ztQV8VbczsG93dp! z)p6WCe<_ECusS{$tW2YX!o!j_jG27x60-Uoh0N&B4I~iB!sf4*^&WZh4=)tld^+n-PTt02^Up>toAIBchq*d(J54+lR5i zY9*8nm7>Jc*I3^gTiB5r%Z834eDlc_$)uV)bnE=l%yqkdrF6yV=>LS9X;`kHzrgDB zb)0s*m)_siXwI$5CLyx_&phkLdEb!K{ltD}WsJMmD^2G6d<~}unGq_nu zec;e~SmGUw{=WlVIXf7p)T3;Utt0eoEpfHjjjae^5bp)bI6TDp4-}^lHwR_{i7f3>?|!U1!X4D!x0X4P1&Z<{}UU8Kgz#g*`X1{|BbhUMo<2a z42hBN`mf;s?;G&Dw8HB^2~lz7ij7o*c;kn;NGz(5J|%}sZj!}M5$b&Auq;&KRXB9Y zdsR5vgj4G>tI}vuD8l)pr#@zW^G8uE=57L){bxHm*qOZlUv&Gzz?P&@Dl@n=;KyoWNQP`Lz|$alja{Wm8L%=Rll>LcjX1U zyTk$ixRr1v(EaMsax(8A)g;}8k5Fr&$3=STJ%7;>334+ zjRs?d*wV}LIFlNN528Yu;WEw=0z}2Pq8qM-cfaM?1w65KUj#5?w-8FV;&MB1?vmTu z<^IRzCB72AvpA|^GII!9A+Kks^1ki-C~d5u+=7Z~i(hh(RNmq8vnEAr{1pMj+`FB| zT3k>Y&d`SRPA@-f@mvN|->a9@RpP>(!tHCCoV2tSy<$ZIzr5Id*10_VEnl=&od;$5 z+Y+7>Cm>r|AhJE?&daR=3lM~>J9*bRofn&;bH_9Ihe9XKnZi%Y!`YQC-e+t6VWimJ zkb;x3GTMNAk0$|5 zCAsCYiW81QAE!t>eyJHYfsn;@D#BLW8P%SI?6#Pj9rw67fOsvw08wsmRgh3#-q1^J zxbmB&GV6V)W(R2uG(Gy+N}3u%*w9GwMA${45UHowU3UVvsu~8MAXaAd>u}}HL?tFt zN(-&(>h`Jtnsm?1bZ;%8POpfGCYAE=tRMv$dQ3@6J6W!uCIy?7OJR@JZ$7S$jz_8r z*I*mGlb;$fKw5ujSd*(=sb>9~Q8%DJED<*%v7810!1T#2OkD?P;Z1rpaGQtM)If7# zOrw&e+b>|_aLglNl5tU#ul1m5;twH5xX#asjGVa4%FZyD>Fzj+NMY+)yp7!3BlkZo;G$$fEAkJL*-*RgM0X|mFZNBFVd0j zvMA-G&|@dNr$MVkTmVeIpnh`LYmeA6^fL3Q2+P-0a@!OAtsEPOAL?K4aHbp5t&hfv zA?)@-D~o!p*H?aFw45M~DAKlf%D)+bj%7$F9MVQ>6CF;%l(S@%;=1Z)jt++|ah(kY zCm*0g#cK7?!8AZ*luVRz*i&`Oj>dgAQDnO?F)hNPVxo;1CtD%` z>W8nMz_j1c_e^v0t@ynG3Ti13%CFwO(%)37pWrGY8pz}4+uK>#M_nj5i)YblOh7mj zq)rJFjtX0#83kFjl;nz%!a0d~OO@OX48B^7hWhsU`b-8@0FcBGc4xnSnA%PrJ?b-O zr4BCue6GS%S-6G2gRx^~Mh4pUl0x~=IGy1OigNplMI1f=i0Uh~-wk`_mrR3QSg1*D zPJi=J527aG&n1*%69ZkB0v&G=pkTh=9LrgA)Q(Vxdd>%-&V$Jggdq=6Ra7O@vUYG(jKrD z+`$&2a0q~ltTiHy8X53Wq1R)_&D%JVP8()!TadeV=e4^$5G5CVNvGr18?a9dj$|fC zyNjjvVg!6fBo|Ca0{sZ>55?@|xff`QioB0_C!oQWC0$}QPw1$qozCK^C<0oP2E$U7*V^bI>$LEzl*AuOjt}FB{2NW8 z)_}|{o2htdmYj$PpQ)Ksr?YISc$p;fQPl?@Rf%}05ht!%*JunN%JdLvo>*GB;Pv-V z$6)V(q@0(!(vYvkOVcEa)KRn5<)@O1%a0Ae|5TpaWPzu4pBwF7&{{6ih1lTROmoiG zY>@SA+g7GW$6Kl)3WpXQGJ3xh7RY9zT1y88{|lXem!P1t)~f?}Rs-pOTUr zcYc4?Tup25y;9|1f%l5M#`3Ue#e%bW%KbIo$nm#*{B@}Xs4iRK2E(P*rc>i-EHGAsmj>R{#p@9bQ;=RCTKEy zYQW$?(wE||>>SM-K|%q}g`-eXM=1P$vvk_%E_bN}XAcygR>RHa{ox{Ze;pA3==?Be zVdxVEYNp!OnVzgRH;HgX)GJ-!?f0HU5tLuDa>1coT@RsWhy2V(U~WHWy{sTxnO?62 z__P>m?D8dCT%MN*FT4}*AWkWe>XI6P5LK(j{ojSNB?uTmP9c>u0ONdnxk>e=$5y*C zlou;Kj++4Z(0U%T+^$TNd;Pc%JeDU7DpB}h4kxM60p{L%;Rv`BebLa&?5*UthEx zgRDW_H+tH6ZxO>pi|GJa`LnFiyDZZb%K~o6!aT<`YN`EH?d;6diQZ_1=eV@tEcm1( zrJ8HQ4niQl-oc>sA=Q==U*?Ok91vo{>WDH}GYWClSl{-GS2qZT=hl4)id zE=>iv8@CcB1k8KXs6|#DjiDQHUYcK%$7a?El9Q$y=(ZX$0)xe-!*92JbCuQl% z34A7XKhS;oBw@fuVr~j@7_2Un`h%vr5HxUM*cuT;Zfk(nMB{L2&7ifoPV}%r)vQFY zGv(J28s7V%?i#d(5XI~#iy(Lo?OOW2Jn7dzdNWjs$Wv z(6Eyi*Nq%?k182A6jK{cX9N%gkpL(x~ z21q0VG)+4F3$8DjGf#8=rwBm6&q;*VZDMW}HA+|C9uK3;+y&LCVbPW;xrV}e3wYGJ zUkwH%+;;BQ&2GWh&4*_`u_%C#)7agFTzVxpXCZf%*Em|O!EIiRcp6yGm1EYJsyDd1 zloYPFscAV;pW2#A~{vn9XsDaC5KUK=QuEmfx^s*KI0~b(s zVr!Q~YxTI*Nc1Zr$4q5p6r8V@+w87m6q-I-|Dc4+y?Xzliu*#yEYNss=2&S|iJ|~a zXbMhIV|o_3^wPyFO03<)(XJpO5B;dGEbgyk>L34`C;_S?{;B%CaNLg6!m{H2zBRzFp~y`06vWCjh4@y z(aK=6{d8J#wkF!C0Y9?<%o1M{IrQ2ufj$FDvx*hZbqW8-{=exF2tc;}v<88KIY?NB zl!8H)AM!n=(mr>}!>X~*v&3P`W~BN2i6=>q{k}3+>wEJt6^Gj&KI)ITNQbSHLg-Kx ztt-P3d1BULFa9u;8d$AUbDe7`jU!r;J<4in{PZtY-%q8R`e3+wxn_F&<;%4o5P1ezcGD4Ver98hjI}`d(14CTB5swWB%?urIfTz#L8k83w!{qL zeWr|_-e-ge&Aa|RLjX8!VU${)pOBk|rJ7q9zs{ctZ`oJsveqWPEx{VPn~OuTP*-9rvOg zPI{(K-vg|uI@+Owcn=>Z;{m{;z1c%~WI;V5^DmYT&$D3o@v{|E$4we|+KiB=iZh8yZN9P)Hg00KXM|4*qOCayv6=i}?^oz2az zFkzk>v?;i!hoIoXO=CwW+G1MM%ZUOcBQ zlO0C^Rao?-7Ob5jGX)n&M(?<6URCNGOVPF}XkjiNZ?$0!DmLNOmKmN^E31Dyat~8- z@lzTBm&WLD{P9Wykg|-tG7U=MwR&K)&&OO&{?P8#o)tIL(#c?l>+dey3tSiXz4H75 zG9-NG&WosVHohOIX@uG;$nf00dx#?8_o!Hy9*YOSp-jqc+HmqD zNA?QYu^_Gm)c4Og^ftimDZ51||1e}_)|=B|{Tj61_p}y}VA{+mSSTk{DgbFXD^+SL zm)hh8N^2heE)f$K7!ehojg8OCUzih2t*D+_g2B^jCDe9ewC@kb_0j}wAn5AoFx6&P zO~``x+f<}KDdQ8Ob9uZ~VQkm)McMT%yx3~2NpFja=T$OoUM+@oX+KvQy)sL7gX%0G zQz_LdKH|esE_D|P1&(UI_Ih4^mrF8~B*>+Z*v(p4u%g3q5%(3FsEn+7I@rbSyGur; z2r8Q!ri6xV$*sTu^GD7E`-tK@wQ>5U!brB)sOYNh97K@+#XwlrbYvq`;D~2K0@CSE zPfXbukf+$cvz*@Z?<-v^Px~;Pln@P-jw|wZCs>EHMMeOA?gh(ijUiOH);T2c9SPUhAr1vm}ET-rb}07KJ-(sghrPA9^t~;9a*B|I-tSeJ_p6B?nge9z zmGnf#*XnXbS)C?p0rWBu@~PPktR%He*6M}eswzVDPk$|Rmt5+dP*{I~xR-}*M0PPw z-F%|K=_60QEE15D(X8i7Xgtu!&XJ=i7LFo9iGEfGlTrjX_Ljh%Hl7D?b1}GDWl+Wh zxk;%FkB`qQ^b$`*%72!3X#w)bp7!!*8NXTagKb=?s1p>qvtl!zWr+BLL!#V;iqh#g zGoD7U=DO-D>gp@l@qI^Rq)C=E+{vj)xl^Ad)UNmEY;k9ZOm4##);t{IB;6S}TXUv+ zYch*v#XpP{20j)>Xm6D!XG>kx%4Ogk&M;7Exf?zTwp@8M2vemuT#YH8Dc`bQ3Vk33 zssTVw@#LmS_I{l10C3dvsH*}msDquIT!gWF4QZ>f?(faeA^W+y2HE)Hk{yA#_iEiS z1u)MT*ZFEj`M8X_cX+)~hmV91`Prq*r%3PL}MlB2+^bboFZGUM0O%_^$yw%3rm zs*AzfEu6L8-ig?|_>Ox+67KDG9rQdao0RDp3!DCYa(o=0SkOKV{(^bPg0a4#vEi#~ zHK5`%mu$v39kp-5U0kVh@30?9lRYRFs{a!N_}ql1Cv%OhE2za(P*`1M)OmoO48IeD zWq7r_VXEkU2`XmnCADlrrMJuuorv<9@fn~Ie%=8{goOwWn&#yDe^-Erz_3Bua%+G1~ z76^d+L-uFmi&=;3uzLO;mcnil9#@kZ0M*ioz`CTQs$b>MhrSKBm{hL&<%ktlTEJlZ zTv&uB=By6Uc4}$)xQr4RLmEN~;R|pL6#;NEWZ~nto%={$)>Mg0gR<+W&oS!6e2#e2y zFeU!PCnh+90wtt z_gQ=Ic*4juzmLmfK!9vwgBF&}Av!*r?B2Ui`_8)B+I{26z;J-DY7UBxYe@gP>|(Sb zv{juT8i+j?%J8(1YJ3pGhW*&ISg zH76Wd6!~9#x(0-^R(ZK#5fJiE*#2Y;Kl(QAQ&!XG`fPgY^%B5>jG0Sk0 zePT<{N*P&MP{AoneRAbx!m}Rn;V4RI)#R-UbDuwfNya|!coog`rvgNMG`8wXsyctP zV}YCTJq|ktOKNQJS-}vXG-_cbu>}auPKY7Kv|1?f$Cg+-^E235fx8mH90)2o^BO`&Ed_v zg6OQm;-Gz zFUz^-z(x+QQ@;yo?B>3*a&deaB{UWxs~>Cwj9|)%d6)U)j((Lyi8-45`@UsFM=mF) zcinraTkleK_p!J_3@MK5jZ=x^x@A91lPdy{C2qJCW?MDwt7s(6melEgafRffXxg+? zHbsW8J(U;V^P|EDCac`vTUtRw`KM_pK2?uNo{ftmLtgkW5=%&bPK}BuJ-5oV&59(k zO`cG<50tu}k>59juK0U15kb)=IHE2 zdny0)Ob3cJE;nx`7eK&Do;dXCr5PB(`*nCaApu06qAPSxb6zA2S3&xoD-DNSv+CT~D z)p{D+4ixTv+ung$S7_&HJTW2AohPUuemK!-g1c7oElOXtqS8Jh!5v;&`HxTrSmlZ#2aawvHlv zlanpqlPUMQA=s!nfmA!GdowiOnFmJ2+EUs`*Z5vj6z85-euAVFOFmv!#wBManWILK zNjE$-4wqyz^mcj+36ARvgXWNM&x=LCKP#AcQjR z*a_rMchGGQ#0a>aEEb;uoS(S_H&*h4upo!4z2(?ZQF>5N8d9!gha`qG-Aj!$&uL|l zA%&g<5sj6ZiHqz)4aH?PJ!R)FRj^pUzHe{0IBvC#iv@iHnFLWv+7}j7X}a# zgNOP?4VKw~{(=2+zeyzZPUz3qz@?=BY{L2=sVw}qr8iVC4(07jAH^Z#65h5zG7*2v z5Bk%@hX7Ktw=F`Eu%uK(Z#x=^-gm7|sr8vd2@NPKXH4kGbTB3T**pD1RsyL-a0+*H z04cQ3%cQAq3O&i2{=)IhanqFByM(?sff(@Yw_oOi#U|`y{ z>8-d#)cei&yzUaLDzS2vX`~$aKDv9HRzpjGPSo2jYB4{EsgjbOwM$RE);NYC7a+ym zBfBhcufhqa2+2E2SCbgeVkNtqe>@}T*M#}RnI@tzYpE66vEv(Fb=_rGk%D+uA;#lf zv7gn5;5$h{q?Kpb_hS<=;_XHd;Fd_ev(s~p=LW52k+#kya5IT~t?t5`?_5Y0Q5&o( z&hPT$NUwEU5fXsnyvO4hG=!HXIpfHwdRpJPi*5`M>;pq(Nq&w~0RTgt239`g*~H$C zTwa#K0!R->BWyV?@gTIqLjxx8(Y*rWq^(~1h;Of$ABEll$g!M~FLKsQE4lqyG%>J% zRO#Gcahf;FcKBUb1sPUa&Ux9UANY0EE<$=X7(@3yhE3FH*H)^}j2Vr+tlhSQTEOBT zu*@vk?Pp@m|E;v)bqi;(Z}c6~ck?+|T#$d4-fs*)#hPC8^R&FIs1xT-1*P8#W*FF~ zs1YY1$!+bkkw6B-H34s0W;{#Gg2L8!POcNWjfcWcujL%cP05{HSC=+%QSq46K7~+K=ugLV2&P- z>mwRtiw8!XP*uj@Ld>+Fxu&LBDaq6yeJ_>eCJgY+gw}m8q~mO@NH;Cqjl_nCsQtonM( zhGzZRV?)-SKhsWPdEMI2ppM`7qU>IMEXPS#XaKcZha57mI6Tgsi@A_FCu=b)Cl}1p zMD#yLW1F;+B_92_`bf}el zfEL!ADZLSkD3UU0UTZ*3LPvj1uoDQvOYE&$O?;%b(hepo3wN5~*}!O4OTtaV#nnL* z?UEg0oj_OS?w6;m_-4ayjtwZ?IpHb4DjE#1j2U1MA0L)vMoTEyVUK`wU*oq(HC1zX zv4#e)RDD`&7vC#hX`VP0prcA=Lly%)bGlR{PWeI7Qu0E949<=FGS;`s5qm$LYbZtn znSRL)aKzXR>DYR#s1SeymR=1#JQBed`Gy;Bu134hz4750EQTkc zx9ex_w}VDuO~Z<{$RWZ<&vaDbv=uq;`vsHlR$$S~fGo{~)_Zd|db??UF@l4O)9TE6 z33#GXkVP%nhdDKdYd7{m|IQ0twDiREv`3f_@;hcYBDCC6&PRaYgOQtsnS{f$tH+O) zJQ{#`GVR1?UWOOX_%blTf?nGRy-&0}2eSt^vWv#AD#0oZRO`CBoT5dy zbE$6(%_7qcatSYTb;Yk>haU&4*s!xyO*K@klN-P=sjNz|)6C%DL_k{rtsr1bY6oqq|gWymmpR*sHoJuSjR3S}(TD!sc^Ot+68 z%HEz$K)}dO5k-G!J_8Exn?qxHzaInJH%NDxx}`AmgZPm)%_YdUl9c=oAX(65ug%s* z{PVId+_z4AzUrvN7syoAj7a+)olpq~nF8nK-qW)u%y>#w8-1=+$8>4Id_(@>Z?+j*(Q(Alnk0!&SCm0P?w(q?5O6Qzqb-Tv!I@*CpA*& zaC--_1Pps?;?K!%X@WDSKG^7d=UmZ!Sr2}J|4cfk%8mOZ$3!{DljS~ZrtTG@7J+Xq~3i|Tc0!XAA24<%J#j z87Ejm&iRcJ)#%3k&-)J0GqOJn+^uJPp#TbIp9>9$cZ8q>1Sz7k6t`yCT4hdM)*4ls zOw6LMk_B3FwpalbY-{GWenh1J)_8kEg%T;{{%T9;XT(c@zp9^fckj2W#EcgLW1?v# z4IukMr9hfG1}42uDzGa_NWWP2?ZM_Ean7N!JgquMZHQRFpyRl}6H!7d`yk6DPWPp< z-Isf$@lqW>?WcL2HO-z=P7Ge=2;bHHMx&Q;$WvVIm#p38Gn!h{8hnOcaDKm_v0BY( zE%E@vIpfE2;c{mmdfcSSdi^3(%5drF%Neio=z}sY>b}PSmi$b=35LjJ((tL2%X4;S zuzdnQI~Z<-()VHqtlM(hA%+cYNwK6-pIKR0njryb6~eE99|DnlKjl+{YH{A+z5_Fe z1jG+tftKpT=|kG08{@*eQD_I)kxlI!msk8pq9) zQzb&x(Vj@m;U|_U#SxH888UaVObYl!4)0A30dUN(Dey6y|6P~6^(c!6(39WXE~~&s z1K8>dUG%V%tSr3Yt5BLxLD30-xW|GxIYeON3f#iRRE^XJJq7~%R#$;ewRZB?^(cl7 znBM&CGUux-`eyK4yWA__KsOhB9gwQ+!TP6P!h-TCs!;gddj|D#EejftrTGs^)unf3 zT*T3s>`{7J)h4HVtGAqGBLtqMxsL#utg&}MHyhtDx+mb#7#9Hff~V28;j7VeK}7hz zO)JHW>&BkOIRxq5JWNx^Ek#diR^@u*uP3Chq|F;R(AZBuCC~6Dl6N=k^xB7(^;HhW z2GrXzRC#YV&eM|oUiUOKTtzV-bfEzyjte@4Y;Kk7t~AJ~_^%hg#wTd>sb;Exheu;g zt|!<_8;i$0Wva=1k0^RSym$Mdf&s`8oLN5E*D7MKRZx9g_)>|Et9rME5=w``$B5mW zQdgxi)3}j!kd@jtRY+FM%)zo;KNFjWG>||&FA^)SP(FjZmwI`5x#i`=aynniY&;!X z`II^&E!WVZnaYuvRA19G08%|Il`;!14ACbUpLJZhmhA2%qSJkS&VxQ*lRh}dv_!w{ zz7UU(vD{UdIN$!Des-VVhfSi-KGj6K6h4E%+*hnd7mnm>j9C6H6+*Znmy40Atu?F! z{r2q*#5><#0c2B-`5h}!`>2|>M#L4YAq?Tsf8!0~K`}<0@^TWmJw^0ONa0d)N-B=q z7w~pSeU4PLQH8&Q&*Zj#{HVrK0))${(F}-{JX2bRZYkov@qtJ}ftSS^8afwhsH@u$vVp z?ttE_w%Z}pg!Bz(J3u}CijUhqyG&lw;C_SoAU1F^$MFaHKmGil*ucmC9bysWSC}8P z=`Q59wDCA>|5VN|eRqZOMk|neOm@i0MjnG|ljvU@tR{Rng{-vbSz>A_Gz&GibT#CoOy zkKr22*$lAKzlmjBWrYSGv0{LOMC_kS{?5m(9u z>#U6>(|an3g=7iDPn`K4bm}ID8i)SXDlEHjJV>FFb>@AZlo!Bi5Fgaf^fTK`b&BC_ zqhU?|T0-Y{pLsb#H;Sc!hMD?{o@S|L08`1IG{cbml+alm9B_n&kEvkb*+~TTHY_5O zEW^rys$6QP%LPGPX{}X%r_yKX^Wc_iuqc2wtB!LZdmD>v$74fZi7b6N z;a%K;+qv%yHYhLiDiwe|j(>iS4xp|WYLt95_3%)GjQrG2QFgeN5&bD9Pyv~CJ~)KR zk~Kv56WGNTzWZ@)+H4mG!P50Okhg^BpyJ3~@=#U=!xX+G()-AMuGMuQ2gD%`M%{K` zl-`2(muj;1R_-ez6j39nxsIRg5iDP_bBaS#w zifZ1hbba1*zD#&@0E2F(SwF~YmC7v-=Rq^PaVus7z*^&tSjt|IH#sn0ypy*83SIgP zzTGcaX2*pDX9*D~K`?((5uu?L)4F2+h12*#Ep<={+~@Igaf|7j%MTz(X|a#ad*x2A z0G3^k{rRe4`RcK{Ti2HO1M<&=|EyA*S z)K#FqxGg3BT}qrV3+AoQ7JSrDJzq^nHeYwm!goxwE7*I1tNUn{?&;jEHu?xnZPVsI zKssy~uv1LxyIZ-cp*2HItEHBnCa;Ia$hKy!^^q}m<1U2(ZAQyiP1oJ{(HqlByP?DU zg7uK5sTHHUHg_xQ5(Lv7Z}I1WDm#J=1KXG+X1hY2??5LFd0~SyL_)^OqBO#0Oj{U9Qgyd+cv37QV>aHY%80O)F)`_dTnDLOTq zc|ut}4e-e+Sayd;h~qPWpZEryHWy;8ic~{X=D&l-Z)wLqGc=e-uMm3G@?t@(J9}T< zC$;S+HSz5d0lqyGCM9c7`LE?!>j+HHK8^3&5N_P}H*BMu?JLJhCbpORtnLN^u7qp4 zvZ;8`+U^x=z8yC>7D4{RUaGbkib@&vElRK*%b?@Q@+rMmfhxWyZt>Wz;Oaj1wL=4R z&!L-EJ;JOI{W({BtS+graF(hiYg<2Bs0^Mg>J<`jgsj4x1o6#rUIIWi0gQBkl=^0F z3GA*_)p@=tQq_P2TOcoEk3q(lUj%oDGG|LG)X3Cw-{t4d9iVvjOo|&zjr}#*T0kmn^okCs+^zdew7-8Hr-;Iqk&u@J2u`5|tAETa+_vD(OtPfTP~HWiw!6#?)buJCOmB4d}?^mKhqahLQ5Ujqom7<2Y6ZwPjH)L z$GG{kRjmKu_sdMOMU;Wd;PjXAM;8;vLqzWgoy{=+rNYdiAp zX>?HV;HDejAjFFC}|)&XqgiHTN$uXX~EGb)4)|jVQ5%$qUbe+S(!(Rg{5aP1YbX`=1ex_@kwEz%6+v$A1edXOxs1*F0 zB$>z&DK)fPP6af29mu%jC}7?*iE54f8!%~UE)T9WXyHE`mF|b_$Nm1|O8y72VEKt^;%>B*<=qX`!R{L@yGc7iBV>GtV;JkJKP7ftUe|{@)vVE zzBqUQ}IGe5|Sf!NRLy>gNr>OuQQQ+^T)lO4n3JYSSpYHcO)GyVT+ z$`Gg9X0I=Xx|266u~+YTn=94uUFh4HhY}X%c;Ct8J7yJKAr-3F-CyLN_hBBs9T-Sw zMWl-P_M(0mmF}0D@@&kk{+A-Vi?jTzpDU*B=m}9~>xIl|JRt{0^lgvc_cO?5x@a5v zZfih_*Elvi?v$=WTs9$!-*|J!GI$KXSKaU@0nSm)S@-YWwAzD^^dp`DroU$aL}$76 z8uked*dF@{``$NnUwwb4jX!a9*e2hjOv1ciNN%rd+2m&}EYPZw(&*B6hc(yUp70!T z(MqvUf%+XyJ3b{b&z-xH<4No7Q(Opq3U4Q< zG02EuElQoSPR7C_0r3-yXyn_ylvk$_nbN(Gmp*9ZUrs&wK3Kx&9#EwYpAtt{^kIDy2mT?C``f~nEci) z;d8!3;~lGSoX}lFf*GSgdcmbGGe2k9qE)`sxzfS0XjR(%n`=JHq(CmnnfId}l=FPm z7D5C@ikY0sfE1CP7;vRS5&@8xX2yhjy&Q&skNCJwMJM2X2pKw^l0-X1#d4gb_>F}Qi$azr`3O5J&t zPrN8IRMxSCP~Qv`e*QdF$9U81G_ z1*!wINK)$q)`9X4Ru6YkeIt;Ne3=Xd7Vzo6VE(?9eat%el{dgAqS0zJ{>OS7 zb*~TRe#+O^fn2)1`!A%uCc71nQDSA_szd$3NheZ{zrGD<;Hpp5pjV8|Ay$`RiRce; zuOP}Ez{e<<)M@b6*>Y_-HN&ut++K6*G-_Y_Y*rOb2f=Ho)D@~7M_?$#cR03M5z*36 zzfdWFDUz9O7-k5FA*p)t`Z77HpDCHfi2QDzNI*+%u0BUKFqbVn4ZDHD$A_}*O5LB= zETjUPpdj!Q4FDHZPw4--Z@WLxF_@6vO`(pH!f%z7iq&P!Wai8oF*00ZVqx$4>G@5F zLiWKbbSe3IcLM+Yd^QSP@X#)uXZN}3mFare;&X12RllZsyluUvnPkVSYlOdR*QIs; z)m9ZpGY&vi`s8*Ms=qc+KCEeHJoqt~g8eiZpz4m>#A~6)zOeLymb-r{uqXo1-!P{0 zupPP#_VT$!wyD<+{=M?v&Yi9p5UuU`xE$OxT1@$f1L*!rJ*>L?Q3UvX8(4H&0iQIHrK!?b*h>Un-70V6J)X+*+Kw`CSlPD-blb_tTe=yH zzg0v4pnKoPK%KTH{tw6wp9m3<);^odW$Sk`bomLvedc0pTjw%KXZ<$etGV%+a^SV^ zka5+03qlBG#~P0h05GsW$!Eo`i+ES$GyB}I;4~e_#eI&t(z2f>x;;Z|yK4CHIN=++Tq!IRA~DY$wsZZ$@)~ky43GgeU&$|c z^9FJ1=-vYuQv;CH8toBcd|JD!{?hf8m}sAl9*&l<1MbNm~ybX4?#`G@-I5GuJF;BN!P5GfM64RrXR zka(Wk&&ZwUVH*-skW*~IIQqSVVLuG0>xb%OJBXsnZ;<{`R$>g7pf)uG^fY4S8n%AX zcvyM$wH+J8g8)b^m>OIq3D`g5c{e;>T1AFM7ZFmG1%G}ya$%2-PX7k*&!vK^5ag9> zB5W$0UixJh9#FWQL#Zbp<)|X_xXveRqm0Hli}f)ehlnGfaHW-q+H?K=9R9JAppwa? zs;-?-=CxmS(=i(ZtsDs0!W*Wmm}Ha8!&6ct)vk`9jV=bci-Lt0t`zmiziFR2G81#x zqJIHiDiGkkSqzF+r&)txFFwA^d>r$>U&~ysW=_guVAI%jYxx2{TBv2p#uWGsx%l^W z%hucZeS|h#j6+F(JXw3*Fj@CR2Sfsu=1;D}7UXVx*b;C|3$&C|KX{uRN2lPzYoNJ5 zrRjbsc}WNgBig6od0zX9{oR-XO}uRXmrZ9HE{j}NB&r|Zlv8uzXK7{^ddd*6*|6*a zg%O#Jb6@%Pr$lz;b}XR~dO0Wq1VFKcC(DYGR?B7^%~EXpxJbq6`)#wQV}<>EB#pig3*(M<=@*$<*w~c+K{EVSikC>?lJw|= zSc1@Z$#tiLs8nTq4wMO{D8&BkfYA3xFtzH7q2Yu3sNTY#j3}d_T{XjuCProfJQQiG zDBXJg2?E!h`#!V3p zZ%~DVyzf)a0`qf=I{=I2v#i|=YVu*d)7Q1OzQ)m(0X=oS+Y=e*&C5hwOf+yo+AZ(f zfN2GERxdZ}r6JxQ<>qDR{(mJ6c#@OJ59q8KmrwwdTV1ske%I6hWQVqDi<99mWL6wa zRqAS`Z#t)uWRd1;AYnTUJ7}y$LA5lXyB7D z>>jnen8+?;LB#vNuy&)}`*z@B>B5&}etJ7P&(&q%=;PKJ?tc(vm#a3TI1LtipS{e= z&|l99JfBW$!>8-cdVQ8Z2?hIq)+7;+CExk?j6Vn9V#*QhX?x{K4v4gyBKz3Dph@vAON#r6TN z-%DGu5<$zMc6KS#CJ!?Q9(qyJ_^mDL8jkj*0ar9IcT=F9d{5gSy5>Zf_;4l3YLd-w zJ~DxzJbwQ}%Peoxr|0Ee;Vc&wJUhlQmb5(_XFMnXb^8rRp9cq-A8r@u!Xea634~|) zE*uc9i7BubkH1QASYDPoG+`>`RhfT+VEkf-A?!e|v&jeVjuGyRgdjq+wXFJMZjJXK z96`X3JZtTF(yuw;7SVw=iwIV-5Lr2d#}YslL9o_#AbRM7o34D$Q+);Bv{YS}-8;qD zD>Aj}EHpXqKrL#tp~t5hV)Lw>cfYKn(2jj_BG~To{D8|#7R=)#5}uE0rr$8;+IW2y zHEy@fcLX1AOZ7uwp*RP$nzKbn4%(|#4DZXl8x|OdH<{wH8DF=Vp;oaKZ)q=UGlkrpqmLiK1hFEiTIF~z}S!87fk+RMB4S_LJaMr zl-YNwN0^LQfIqj`K;H~zCQZjQ%sD}&pjT-XqO?PsJParcODWQoB>ZBRrv5y>&=II# z)mJjy`XYV?|Gb%ztZ| zg${aS zm=X98#4VM(b&}Wekvc903*ChAb#T6{mqve07_T=`YWy}lScIg}Zsmp-4iNk@?ky3` zm|~1-p^fylG~>3Z&1k>qmTE8YJshArYh{Grl9hg9H)e6U%FO?(I@rHbrdHonjV}S*-wO{lRV4t5*!{B6hE*KDP5J#007Y5d)DqwUnj1D? z|IB38<{F$>$yZLjP0o+ezmlHPc|>s90gu;V|1E8@0SpRAwXR?Nj8bpOO)cq4%x zePlb-8|?XT-Y?HIb=Pd&RyFCEpPyTq%<(P7wvm?c5(k>XTmF%LK?w>qvU!A=*vpmM z63idOfKWvr33ZLk?jBBe2_v3g^+C(VWf?b^=v5S^^`$z`-s%ee!RaK&DIA1j|TL>v-aD@~`Oz9fm=+pG2ABE2fY41s2V z78$KB-JXUs1JB!;PB&`{V9VUA%YIqdLZt1By_XdlK-EG_3UvZ}Ec|ZhbItBBE--4?C-D-T60$eaIC);GLR!jBg@vYPhZCUu0nVSK)2ebV>DXXWC z7oUYziYy~msyXZUfw@0Fx=Vv^K~`gNT-|x~cos2CDIY;678i{{vGaWpem-iw$vrf_reWrag8ps9L5um^ zo3b%oFTm#!@PH4`9TVO;-^VY@wz_e7)DQmy-{ld0y##swnK<}U9K=g%%T zt3g(K{e2mJ%bx6otOE&2jhiX4|E8(>IqUqqF2&T$?JgCPmn?=#>t}8p4Eu{Dc1hd3Bh0De@M@N_KV_jBR$SEr zTZ1KZ1|EF(Nz)Kgi13ETCt05_SFhUpr8l*fjST67|C)>Cw$uD7@H~-IzHVtG=|EwT zkcR%fD-btAb!lW7W|1G3kpT@CA+=VdYrQPkOD!}bM zJV(WNyI!$(9}M6>xE!DUBk#U4sBH$#%Mb-dT&#Yp+|^=8HOr^dU9mq3O-TLp^SqYC z3*OC?JSgbyEAYk+Lx73(z;Dy9Ga(nNV6hi8aX&EmE5BJFXyQLu7~Vb;!!ZzvCWQzuVt7#q;lR3$@&4X4V-Lh@I*h8167=AvFz<*@vc!{yZmxy(w~!PA#K z%_A?Mw9=VFkoOl-@&5NJ(`k1^%QBy_K#LLJ0*M*f=gV|178v^;1hH5l70~;v`oJn6 zEPd>5baQbF0(qqGhWp#RmK^C)qo(VQhPhlrYHJSfWnaRWN21Gt}=mXDd|*b;9c z_@xJ@DPThoTK0YgfR%qQFc1GiY=D)(T{H-ggZM-VCs(^_<2GOKx&83uq20npOXY0z zYVk8nQ8UCf{1#($YEx|Bol6CK0Rd{M0?EG1tV+P>Lv8t}OZc5w6Qp3dv- z=m=v}$;xrW^+u9@pXk0*!8m#!)ccC0%wUf=oP=3sAwl%reVu;K z98O1GU@RxeN*azV|HG~Aq=U0}21a*|ePuP+1vUPe&|Qq-v~$6-C2Cx@xJCnUXDs$_ zF{OF~cUieVF{Q$fI4BB2-yL&Uz!XDHMjc)*B{)>mp|cwbamSu#*G^m>Ndp~nE+#tG z_xqQFk9y4;^#{5)I#34`4AE;UE3-QI^eMh1@zXK*yk;FplYtTp-{-3Ytl28DoGNmF zRqMWP)dw% zBh93<1M0q}Cgq*IszH`Raz(VhYHs}%7Q*nkA3h&!^`nKjf1PMXe{eXz`p7cS8^Q}C z0zk&~)-lR;TDjVlxM?o44hdK{V7*>Xt7Ob-eHjv7xm;~CcxLvR2EZd})>WOTN&L8i ztNYiw0#CCdiB5MW5PerEa=P={nJYV=a z87<=}#m$C0R|X-|y`BVVf86DL%rK=H{Q≈y5!xghVvK2Mo$gRsG?vfv|skx|c05 ziXmX?S`~ApcP^t@Qj%0QWyp-_?spcf>=LN}Pibxmup%0KeXZ)s`usYyo_8{Ev@FDD zd}l9}=NL44StB6@G!+XL*x|Wx^-tFkm^h%6214S!^fso%b`(Q2#~OMTr|oRnU^`7QcaeocoO?&eY=gnIKa3OcE7DjZP z)QjAB5!-=J^Sxi5vZ^*3bNRqQDJqU;(4vt1t}T9+tiF1Owt$b#cOKRY1s($BC(rrg zIuQg-uKZUW?sp;Wt?Zq>7%$#8dw77*dwiXyWf3L-Z2QgAyhAXsam&U7kgaO--1qtM z{7!D9)9^Fe+Io=Yu`=v#&04ebURqiSObGrtCg#XFZ!tVYi23d&$)@W zna@qwV*|s&lXeHYfOPHq9<8UK_(LUTL084SiDtB15DHROLV~TxHClXX zZsAV1?cMm6@r2Q2htO`DkqTChJhWDkk?@ z-Z52(jM@yH-ueM#QrdS(ny5|t{9~^Pki~iUoE(svJ*Uf-ltf~rm&}oDq^TXA{)(Tk zSwSwv@8HeYsen+H@eP&=kDCvHV;mG2KUgbvpuTZd<6TY_p6W;SIf*aF$>J?7VE44e zvQ=jGeY!Uuh>ki!5?siFi1Nv&AnW~Bb9JdcE_@&=s$64HSBEIoQSsjH$ZqLPB@jYb zWF#j`7VwF`XLy)payZBg?QOA&(!W(B?EM{=A zb^5%+BD}F-qbR?jq2bDw%yxRYcF@m@5f(pScHL^u2KM6<;t~ znap;o)ziS&d(*JD7ThSJO_xTfC9Ntmcmkn}ipoy>);08Wyne7F!$N)u_$Bb=mGd%& zL?Q++Vo*v-ijGd?5xSeS!hVf5Agi0HMsnxmxA#)Hv=zPkPiCS6&?+Q&b9#}|Ta`vc zGCnXeHF(MXg`W#-e!9H;`2AYh(s<@~3)PZgLiKX{^{ka?e4o$p!cFDo2eoTs1)FC9#8D4= z#Fa#zosa9u_o`h~AMcX$pOL9;maAhN179i^-B!BZy?Y0`0~+`6zz&!Hlxz#+w^9DD zTpK>cHD}TUG9;-AtPgHho(cwEi^o*h^dmdxBPUVq-=!D_E@Ob+KeU*Tgi1sWKG3z~ zlOw3x=@FINpGneu_L_b?PCf2Sj0whHMBlcZ2;)9W>J9K?>_Bm7#O>=-$dEC-EI#UN z(v#oWFH8At>`9%#q!_}EV-NNJQDoz%MYuCZ#Z8~t@mu#Ik>CB!9%@;|$3`)H+l4zD z2Ox+I*NArMw^D!P)^Uq}?MWxEMnDiU@jK3Hq`fjngT?v=)M2hG>F#$*I9?;&<@?rn z_mXn+{c!Og&kcq*)|=z!`{mk7U62WWSOeGL8X8%tNOP}c@7@*e!cpQ1}8;mukqk4={)NfGyqlY_DD{EaAA1GA3FN2o#C@Ynd z0{_T=5!`RGoT+KRmXEUisIe$%)sXPry3u~t#tr2J_8#jFb*~Oy zno%~hBUG?|j{=;6IdfxkdZXa9ceH2Lm&=l4A;_`ffJ}42tne1?&S?c5)uAOf&3%Pf zh&h57gUIwm237tpRn7Wo$w!*^Qh>M_5Lug{09Pc##ni5)7zz*}FtE|&8&I!j*C+x9 zP_NyNvXs$zk|~~E%t=#eC5efjkqL2ois0GV)hj!qp47`$EZAQ6HT>cq6Tok&6JBBYozgXZ#w#3 ztsaTBdC%_iP#28O*6sW8QSrO|tHu-*0eY*aOn4@6SGYoT`;j?lsO_cOt2C z?qT?}GPoL4=Uc>!4!>x6;Bqpn(VeuoGS{lE$-X8mRWM_kUC)XKDI9;rQ`T`>EEz10V%rq)g)gGmEi$gRRr^p9oh{>^ zoU)hh#wYdg%W8M6Kd($-@{iSjT*gyLHI|m~gTYY*^~}o0yoc9Tn#!RW<;R=idWt1K zua8Io@c}&><3gvJhfZo21ClxRvonr)-~cix9aj@hLY&YGrzGg_Btj2ry-y)od7 zsVx@!Kdi_ltTwncwk`M;rstu5QCs$(zKf504E08D^%m*A&l_Iwvx#cux)|p`aXIyp zC(O9{`Mpd#A!JAn@*b_xlZsRjA|<=wMMO+kcn5Z)K}*#(rVy zD{$@k{5^DlLBEs^Rzm|+-*tWvs|v`bz=Bt=K#NXDe40l;{D9^EzoBbw*nOqspGb}y zVw8CFWJH7T@+o{tpSWli9-Fp0Xt~p8sN!61s5(m#s429T3(Iq&CG9eASNXQi;BkVU z1^y|f(|+b?btQOM!&|za_?Wh@0T@=Hh64DJKQ>V>F+AQmlKU=6puR>J@^|c@H680l zFV_Yd16~*ty;ko+=i|L`=M@cr(!kI{NkTm3KV~*`_+YFqZ9=%LgGsHN;*e%||`bl%WUhsR@Pds6oldey@Y$nuEu ztqC4#Y3>6O0e;DjY-C!O+7WW5q)%=H(4$khJT5ke9CQ_!y&OSJ>I!JLUyn~wRk6-N z2RwO*<51((%{2Y`dam;mN<%|7 z60doOzs@?Y0xDxEVmchebltsnCen0P`~&SoD_Y}a8~1+g-5Mq@PSqAd5V|F(xXn*$ z3>X0 zHFl4StGc!;lVn+f(GnH*X0)37*PLF0q_>MyE*+k8+d!3ex!llE;vzXC9vH_tmgVvlqqxeRIm0uBWw7q{+nhhPdnYsroe&KL zAcI+Yfjy~?;QMj0pOvOI>nBS78J%oaU|eRA)Vp~U?B!;0g{u3vbZ_3Xl6{jwc-oj; zP0bL;Ho{-HkwsVaGp-O*7Q@rfFw(4T=*!3l-96=SmV- z2Rtq#+;EU##VE^$grg>jC~X0__|1NhX(z zFV8&y-Al@I5wg0v#yZI1Q9c;?b;lH!oJ<>41?#9F?^_S%ux3yCydaz@X%YkcLKUGO z4%jj+o0fP>sS5snLg(U3z$4o=AN&m1NBI>o&?hq1MO<#6-M)EfaS$a{;bNR)v{~)f zH-YG--Bc2)Nu(zx`=LJqS^jtiywq=|C%q)|fPtPbv{k=RESPDi9g$o9^XeXV3^=?` zZZ($a=H>chO1KS*OtDK&ixr39hYK`wU56L(yF@bZxnR7qzJDRa&sTtSMBtdytPfn7c4&L1@m`$ji zc#k0s=8ZX>mTMRGaF{u;H!h8rm+`L|5uwhruMa<B(KHwvuIDaxlNw&78VbTb*8Ch}Y9L5v_8$`(C=!n#b+x?V8)!^X>Y2rEU*p zrhB!+(cI~P13Rb$#uZemoG>1)K+6%Jd*}UkaNnA|_TUj=@!}%%RQAGFnv>6SQ^EgK zN9|_T@^5ze6RE;BCGsw|jKA7!-`G~K`~af=@8~L78m)0_o(Xmj1-+McLD#++|0^;@ z51fEa=XkY6KBDUM;ZY#fX#_HQgbBn3#AZP;&^NdLQZd3;3~yy0`}r#S7h{Bd zu2egO6~XI$@(8qlE}-DS$vYikvehb*vra_L1E~n;WA*u+BNe<)PyfW)8+9+34|uQo zE089BIx~f+XbaNGwx;}!c=nTadwOm@&q=mAAAM}j3Z!2T)HJ8kDmQxW94H*c9#qVh ztugx8{nM#UPa^7rQwDRzdKqDeC_9h_+-DEH^R++r=KKmQo~gl-21OM7TFR&Mi^A*n zw6V~1tU8VWoq9mIMUcPx3AOd=EBM9Pz@k%KA+|&;%Xygk&W%c|fOfH{bORd0yrx$x zy3=mU2)?bVn&qJ6WY8Hth&~1kX_P+-lx>xYS#Vf6wwcAN|NRskTGDF~6sjj`Cl)-Q z!fqYZn-?ir*Q;;;r_Q=%;r-*{N&XV*=`Dk9>w{?H`}>&!O$(fUA65u?x>fb)7>2cf z)7+Y8VhwvVD`&p8?UzGxLbC2Jl0=Iec^Nq{c#)K<rXCF|zWOY+d~lZhC$ z9P3bgmsonu&0TM&@&wH} zf8%Kf9W)>`qy66O+#MrfWK?P7y8JKz@=wD>1Y9^z6-O@iHiat5NW252ey=$^2ye0w z_;gis>EA+D;x(m_!MoYW9UziyTOFDbv0vUn|EZ4pjQr!Had-AW1mg>F4edwN>bZ^^ zCHv7;vUp!#|0y3*Uz$IAUY{gxazTAxkQgN&vwpFlu)6PFO$ggYbbx%6YQQb-ct4|B zZ}b^1qWv)B(EuAUMj&~-X@0F7XLb_H`+R2rg~x8Qk-2j{gw z7c`(b{jB^}RONg>1O<~T!noYaNUFK>T^K%ur$8=ObeIi$3RrsWNlM~4w4@?}#7;6` zQytZGznTjx)6dsIF?aFd(6PPQAQcmm*VOF>^9O(S;M3+`2XHp3fGb2(H_fpflidym z;>k4t3Ehh4JkketCLUL}o$b6%3J{xH(VeSYCgcUK#Vt=gQ2=^XF6&#a14^sAR^iDg zZmVF~j!Eyfg}X8P&1S|K8tJRkzV2FJ(*iGH1UY9PEu)7=ei334!NJQOFCh}ZZacZI z4*qr-D#*=GlQwTs;to~@rgGi@TOKR*2nxwD{2>T$V_%P1y)JVuqZANF&#=sJxzbnX zG3T;&CG~33skQ99HMZ1))0iO5w}4!6D)a@yrpjB|ZQ0Q9v=oz>sVyZX6=|Ai8}b{9 z$BY@5#{L0wRnb=K;7GS<>Y$~Wnx=;u&N=5HTdT1hClkM7gO^xIS-E}@n6c>&@64L; zVB3}z_}H!Gr0&|uYJ2b?yaJTzxOx8Ah-lYZ&4`k^sh6BJX59CPd>%EcoQRV$(2cEy zv+=8l>TF}L>pTQ1qg1%CynW_DDnOp9Rn_cS_!;zoBfa_2V}u_YzvB1^s;XVh%7pjS zu}Q5**n@!gQ{X4c?JY9!dGx}O`PaTx?1AXUkI_wCYHs~&`LEs|;%v$tvlixB`+iL@ zyrcNJd+?!VoQ7kLtdZpw{~Win?V;q08xfIMkE)qqD%*hK)>jpZq8eN^t?{?F{hbtP zb#?UXE<2KcMn|T#oaP)gQLGOBv}razI9y&{($LZ##aryA^HG!V_OJ7LO;YXCAo;`* zv0LgT8NWPW&D*y^2sQ);9U9Z(+^gp9e+YPTw_z zdLHQK4+xh{TbEX{Mb$x?-9)51Dmd**8@IQ=1ZaUM4B)_EFtAzit#}jY@A=2KGHKBNT|e$$ z>%G)J>}Ri5$}2pL zv`|r%i{X{O>sxY=lA<+yXcZ(=cuu#`VGfU1dl_VK4IU?wX*M;VjIMp0w8D0l2%3hHOjU~ljh;LrN1Pz_kGY;Xbh0Do(N$SOjN< zXA(g^Mpw7~q<|t8mKRUZ(9RAW40QLl5rnhV*^1MwXdde&u6mm?{XHO!i;LZ~QEoC& zpF{y`?@Vkl-s>KxX=S4@>DT5V02$*xC63^rZ)?ni9x_Q&xcsqr+`|3v;y4Re_N5UapHJ#Xf0Z#kLHk zB6SnMx>aO_H;ys#qjgARV4Vi&R&Y#xK$yzlp=KFF+Bw~*IZAYhMWe_tuvcho( zK1amF&|V8;A&q`p!~3MxL6Si`MK+ph+=(QQVnhe(x}C^G0i2)LlMoYoL;Vx*ylF1QdKaUEM^t?!GU&-s&XOO^UAeDJsMQ z2sdhd5Mu;q`TO>NY!aO}Golo6q`9&*R5-C{^0UHpF4~(g_FKZ>qpRY{9mNoqax0ER zsPDB|M+Ulziu7q}Qn+vO+L0VVr4Av@fq~(5#+FqXXp<)2z5E+K`;-}Ds5-dv3ed6u zt%h@jAnP?qpF=W`_7ZnL`2OBQ+gVyehpTO7?tQQXQ81FpJAmkqN)j^j0W5{rMj`;5 z*G|5Dv(yxqof$YTs2~Ch0ftOJN1-)s(>deB@$P@)qouytDdM1WSrn@d83c$d+sfPM zGQdES19YlVQ{k-41N2fyM3uqsKWvlXF$w5Z)Buz6_)rB5x@V(h001G9g8r$tVtZ}~zKE{en8YBWdk1)*e3Ypg%kXV< zHdj+L%ms8mYmz}rM^EAe9cTUl^3 zT_6e1Z}?jK_i@Nysv!Ax*#aP)p;i35V<4q3a9_r6)rFAdaYk#Y0BKGLue*bWM6GyDKErGgf zR@E%zgudQ79H;ePYNodkJ)~wC_bjwQ%jTDkI!y2>DzV%K_R900@&ix9Y z?{J(fOa6}z<-FFDvo#x|ep9f6XPEzQ4GW=+`2VZm|3?9i3wfWsG+XCF@viTGkH*uc zw3?snd71V{&;{t11F(hw(*5@bqU$Fg2a}O6>nECpK zDxO*MDv@=Z!8(zon?~>wkUm7MZKR0>H*^OIij8OKi3|i5GE%(*G}(URS9pq3+~0rt z^wA$SAQkJ&+XMl=kqG;@VI3aG%5}r~1%x9jf@4RH1w0h*n`#DR(uzNo@ z-cqhOSzetA_?}$qjx=T4`bnh|Ihk%pXz)s5zP02j^9FBLIVb3y`(r2i)-g8p8q~{_ zQpe^N-hNDGPF&8y84-nAR>|00m4r^$W>Qj8PG=^H^fTRbZ?FmBENQ*Kttz2@_Lkledj?UxPoVwEgg>x5o%W^@b^;*apjwNrq*6i+ z`tPL~){t{X#|xnGL+G04uBE?1>EQa~iBrqh1OB}XhH`Un$^x17WK~k=bA)t0vg4fz zRim2wha>pj;@CjPlOcwhL70B&@cXNo&HR-f|2p>6P09WYUYxxn?96ENv&djVa&8xn zj^b!MOmM*@_;vLXyq4p_$@%ZMU<^u^Mt-~;#+Yut{U48Cvj{`tvcD^tD+%?%+__Zd z2U({}Z<4F$jU-dlDw*F3-XEiX~MT|a#Lio1+sQiX$MCS{8C9$cIMWYu5qY+i3C z;;Ofw^rIlQc`WD{dZV0miT83nH?{hwU{{AH{GlKgtGq(j~#c!NKq}-9}sM@-PxbksU1W+}C-^*}x17=>VWJ z(&IYsHND8PIns%idXi{}hubMB1;y*(WY2^D{`k?{LogC=CT51x*<4}ei6j5OO*S*N z`emI{ucPqq;N2kSheQ-SgpT#bd+%>zZ#TXzI>EzDC@TgWIuG;@>EK`-B72dQoB~hP zoFZ62Wfat>(3h*pdL+#{fTQ6Ng%A90Z({*YBh}PUHQf z+Zh~NR@IbWjy8#Ik6$*8({-$N(ZScOvfO;G9jPT&0PEH%|yb12j#g}mR6Q; zo8xNX4~Se#f*Eg+v1zHa{UWo@-0)cE@qjV0bVVIT^h-!m1HY@ns6PL3!b7HVCFmRQ?gMJ<}-xLrwyQ`md$@>U< z?2dmN$#h|Zq)2>b>II;u=CCk927akX5!X zzgIztiJ=I8(7ti6+O=YQIr>)g9_y8wIrahEDE+n%t)%oaNSEp0z-#A9u6!s!=sbE(a$CtdUa+SzUB0Cs-z1r7C=P@_kz zbps_%@vr!=6OJ8xZMeMu^do<-ymsrw4{%Q8L_0T!c{bYq>FzH8wiYJ`M`voR7@dGc zQ@NE!YI#2jp*QF;$MoLOcB}os4@4tYfk;+G{)zcN8zgZE<8bwc*yX=t0c1`4KECo`Yhe`M7?x{B zL5kn|+C1d;%HweHv6zY*+)>469~5zgx$a&`?1@|wWOkmnBV?G_iDvDOIB2vsjo!gp zwW47iI;P8pE7;D*>o8?qX=&Fpbw9d}zm4?eQ<}4g^AA*z|2%tP$F?Rn}Tj1MvVO#T^XYvFO%oxz+)KU9>?i>&o^`~oT|o0 zd4>5!E@|=(~kJsLx+T(H#3}#N^YTvIG(+*FQ zlB2T_n*Piql;xM5AMUG8>e9ec9#-Gx9}iE3MqJ+Zj%P5L0|H&2smJPbuWiru_4G(* z#QlNr5)P`KyQjPdeLgvtm5Yekf*5PIGl`i~xnByfv_1Eu3TRB{Mn&s<>JT2DY9}0b zumP6V3Zu2w4uHTAcd6kBT7QV3M5T_2?Zp-L2U3?6u<;*qxzAG?2+SnuM2@V7C{?W~ zXj`Gt&6&;8UVUhzH5J$Z-IHsa--)5mj>XF74(keL(GHGRY*F-fRO#ueq`FWk2ZzWG zJnOsY#btB7s5o(8Q&F;N zV?#Kd7JY2+0jH;aKtja55Z15oEQpLBvOfTP$n^C3U6eD&CKzXQMJ2b28@5C^X{v+t zJSG{FQ^MSPI`@0$vHZD_?Xs>CU-i4*X?d}5w|q0M3Wn}1++K6m|DIdGz)z-r#>#s! zhL!!Gb%ag^kxEb6@kRM=q;nkaW_L}CL~*S8I<-Khq-v@(lkLaEShQ% zWraosDj+vEvBG(;Yf-j{vn8bmFvPrJcSKrvoVb8M`C&913bSZZI)qkZIm_6y(U}C1-d0hD80L>X|A{%8k3p z5Bk(YoU>!#!UFmrqY9;VUQH#(p|r)rE~IMCLmi;U&1AP@&zCe;6#&^>ARn9dN5J_h%n#fRGU3Td^VQn@ULenuV}U74ZNN>e zoduWFLs8@FhmRmRdxs5$O<7bj7-!6EAYz1_K0t|=$D1?NKG(3l>wnvje>@QXiDx%w zEZW;im>;dL%Z|3GjY_}0&3#!G73=dx{48+mK_e>@H7Pzh74PY-E&KhPjGSS}P37&U1L^XQC6LRlyp7rEiuTE3%u7 zi-xEl8?^D{xNoWPIjI<|hRrkQ93`U=!&4}-VS9pzVj@Nr(iHBeb_IUc5lwB)YK08nU?YN z{UPEcIy8ZN+{OAh@`z>m^Ly<59ySy3tmJ+VItHjk%bix$45qPgL#!u-W*(184uh^Q zez=UQjW7!%ITdIqM+#APy&pIagp|{y#JK(_kGmQkkVTuq4lp6jN8XxfkLEK@>US0f zXL)c+XUS2Q&&KM}4l}ZyZ|my`I7^RTtXWj!B5k)}Mu}_G>xEHs*jU}zPkDPB9+LCWB9$CWDl#4&7NwqL)jzmOivq_b0VE-7W6;wz!|Mt%c zd-u;N&q>r#KUGQPskRl8oEVvmgxfXMoTPO%RvtXjN4Ja(6SPE7(Vk=rHtkEB03N&Q z%0696T}aJO8gV+}Fe@R>RW>@PZv(!~yvAIf!nZ8Z*PycSYqjTFet!z<#X!+0m(6V7 z6g6@^Y&mMvRykidl#&6ke@|_FP9>ldPUHbB*g&U5-IUA7Nd*zr>>EHu#x3=I=b>^bNn?F z&r9<5Z%BLH=L;28VW8r|$xVW``sLMCNm0>(?1@|i%DHSM)10El3?e}!H&dFx=EqHl z(LQVQAwU^vLq#H0J{PG1d!wsUud%SA#Z*yFnwiPlnEr>Lzx4W6Im2FjJ7EG%dVBdQ z_5XN_KdFV!Go_sYtor4&J;^cO+EK+WNu@wx&iJyabczFy{9T3UvNhB0%1+NUMqwn_P|Ei(O+n|!}sqlU#3 z$JABJhGp072xD}lK7nPa(WOtY9z)>gc1GOm=9~B>Awd`TK<+T{3i@LmwUD7d(~fe# zb^bc6Aj?wC*9Et4p96w?+8ccn9MuR3>h>S_AzZ5@JHWr&xxL$6oxLEfQwT47t-5fk zNqw+UiAgo&PoIIL*l{@VhhoOGVN{6AmmBG=O8OTB?BFKDcko+QfTnivw0%9P;vM>+^qC{FD2yhIE$;P-gpq#^a%-Mo#7Mn%r>w zfk&OXhZgSKV@0*rP47Isuh5uc{4}#kSHd+hgIM&fHC|&W@%}HRZsZ|WFG_#+UXyAs zMkJrZC8QuOiFxz@0?oS1N92r`Wt>^>n)@H_&}R7q^7u<^+E z-}abAC(`(IyEB6MyhT4?Wv@n>Tj55xdJ%JAxdR#6VEBOZ&FzIAy#q%4*ZD?Hu3vJ{ zfXW~WRMK~C>~;fiefv@uy4x7s_O5_dE>|V{B=N4`=HoW%mg;L#Koia3@BP2uV9&a$ zDV~eMY6Ts7vQH5dZ}f#cvUXDml0j0Lu>Uu*>xzf^lnLRGfg;tRUTI@Kp(9rGTlMmq zDg3_1@;$MJ_8t;BC!+Zk6OkApU@J{CHAb)pZ6E@1&9?PZdfx#a;bXzMj`o^5a+X@6 z*M3WF&ckk|9A%YFv74T;3^u#BVB1Tak-D5KXPo@*dc~mF3(de^n;rN4u!VzdIG2%k zt2Sd!)X5QRczj>D9xNRyGks!Ji|t~7SpNOtSYOqhFt|wH2Zd!8(XB+MiFq(UW~g}- zhRM-BO;&g;6UeRiY0vp7T*YH|qy9Fw+BE4mYE6EaBX?#>ZAY!)y;kx*jqzvwmAGvX z)bDI>FM&>-DFOy?yPRz#rI1s| z#P}NbCrqtY51bvmCLp^hMu3j{_#|Ot`p=v0MJE#`r?5vfGT#&)?&TruvuzLXHo-WO z0)r{K^k6$h7*wn5=ZH7$jdoT2##Nh-8BKRnY=(8J)XLE)b0Sg*2!;<3uOhKD4FvSH z-S@&5X+-MM`}$YY&-?W^HEi;CzZq?ke`ka8mKpRbWbPtN7k)WDG_(`Q8XM=MMoPJP zQm^Qx$^(4jA%_I)kfcFA)l$%7!VS|fQIMP&%r~O$7a0gc`DP*Gr3RU`m!CTXgbqZH z{J~zypN_RkcpcAm`X{x=XBy8xg#nUCoCbu1!(^KqICBPg$$z8|t*jqSr1F+!uhJ|D z)kv|aGkVI_y2LgWDAs83=XJkx;v@dTL*W<{_3D-E`i;}#REWW?=e1m{0>)Z&gFh@4 zGs9ki4B(w-?PY75@IDu@-ON}yul$uw^Bs2CK>l8LKe8mv%q2Qe*as>Z7x0)t*~f)s zrH7^FdprI15ot#xM4UH>>(Z1+{Ds{zO}OUp49`wjXTD;tuH-Bj`MH>>z+w-5`=sRO z!ir1Bcm160?mtpPf3vSR=mF-<*A_##P~U7Ha?VPVzFHkdj!Yw^_wN$ok184$xHr*u zTzOU~MVIJrkw)FW9GQ8d0gi`@v~P`$)82<~tMAvy^U3_eg^S%aQ0@;S03tQr1F*Pw zRCvmUfZ%IN$R53eB8-E7OddNd8NWANL3gJU5J4~t-g(=6yWVd#54sUqE@SLYf{O^!m+YKW&-FXx8r8u$wm7hcY?2^!x@kN;RRI9nm}vr##C`07co~}?%(@8}`z}Xw z8-QnAkWd5FsY8RRpRswV%pN<|6elJHRnN|B>Ogv~i;t1Dt3@eD7J-7IWu!zdsol0T zoDz-h;n&B*`ya@BFXTO!v+JL(Gr^NiVJPvtdm{pZ@Y^%djx7Y< z&(#^qh^c%hWr;E4q&kOJR=u<;g8l#i(g>5uI}H^~0C5^uZV@e8eT$5`5F&QJEF6Ud z8Gz{@n${3YruzuJal!zLJsVyJ{h8c~A+#NVg1xoSR|moRvYy;=^|y9DxAkut|& z(BRwgG~-gf>w2GHXdS=MyREL})x>0^WPdGRVmvV<`LOp;yHzrVp{I%!q!$XO8fGN& zjeu$<*Q`KTI6|Du5D_sR>tr~eydQFxl~1(49-BrDYaC7h0b^IdUU^j!u+#bx@G!cg zgO^6LM#OHTw@(SkxP7t8T`f-UeW3yCJyl8|%{Qs|N$Rg>hv(J#Y%n5vHR60O-v2~h zQ6KkT>ik!<7E;P?0^EPXwP-qN)Jm{w6UDr!*o5$iX`9gm#vopk5m8~Vh3z1n&ufNnpOXrzQw49VDiGfVmI5$MzBx#S57pa*2=TpG_k#$Jnx0y?w$hf zYS2qFTyFx|dAk6gLZ*Qo4L!_}xit#`tErWAYMYIIDjCVOtSt^^%OV*yE~}WQ$($1N z1JIwq_tZyoW(*Fv^-1Y5jwC$ez{i?Qlj8u$I2qAtWeA^k4f+`)pPu90pnnL5MH%nZ zF@EMbS{yiweg_K+KGz$o5&Nqr9qjv`h!B*cvv)oB$md3MV34aIkew#>N?aR7B3@d1 zzFx_{8?U=BA)cjG&zsVWSz~72VO!i{+u&5|!ApiYl}I~z?BjW*qEjWShe#E3s~%vY zdqMVIn#`DE9g45|0g{E)Qy^r2eyyp)eQZmnqPjis&6Nf@XiIb|+vG_Ju=;`)tUv=x z99>DbOci2+JADB`p4@f;OP-5qjqLiPF&||jFl*Lip3V!m+j}InE)Vo`tfDhwkb?wV z9x+%ojac?;3BU*tP@QX0mi@ir$P-0?(&i0@Q`R|tUar&MC%!cE5(=@I+=RjQyo;k+ zPYWmd7mSh1olVrZCt0?#TxS02by=JmiTrX^-RG1vp4ReHmQ1|qk1VQS?x%?i9$i1@ zP5UAXd&sV3OeCvW>CzN`CN-s~z;zo@-XWu>DEq=#Sig460r1{@76}O77V?88|4^w18d@DnbySA_`<&EjCMhr) zHF?_~1{bDE>1g6;z6SC-LSBD^+B>^fmzU7APJva$YL!ds$m^nzd25O6@bX%lHJV9` zSE^5j-8==YXNm|4{}P_|!9VZ)@Wzxq?A5X)Q{EQ86r zAos=l`{$hh!seS4Nb5`>q3ohVx$${o~0pNt;`A&lEdocs__+Hw!y+;@djTza;@y`q=KYF zy)8Pf5jh4PIffa@Tq(7znu2>86mjr^q9)$%N%W@+7gEU2UQ8wyZLtuen15hcwPcKD zsVrNHZCR*Bk!|ro`V_qq72JkqVAlE?_wzP8j8#poT@X^~DdL)rT9zj-G1r=09%V6r}wsqcZGLEn4vO~>MeCy z1@TUuW3*oe2PV?}6{)7xP$qrW(^+klJIGcnyTrPW~uliF7WDu+W2v>|pa5U+! z&F@(`QbC4q$q~71#LJA~#(qp=((1T5eoaMfLx8?*`J834e8^=tU1RmdSL-qpje)xZ z+Es9VXwbw;SXRNU)N z&5u82*B%6gq2O`rg@FIy?@0kEDc)9sAd!!cF9Xbr?{zSAP|h-r_z@$V-j>wOBN=qP z7r*|xY<{4saqhYSBF_}o-RrMo%-{KiM+})eeYQj!vVPx`Apk&C>^CDJQ{xrM;iL?C zf7uJSJmKq0J>Jbb%_g_kO>xGuW3CB=B6o^F*icF|@GG;z5s$aF6Jn$|nICvJo0hTO1r>uIjUF3^0LtkBQKi5SzROzkX7Fn5zbKjA#(csc$56MNR z)&VbKNm!L4GMEz<^HHJB$tc@c9&duam2YkxSY#Gh(lbGK{s{u1L=tWvZI5MT$+d8Q z%^@~fS>g8aS(SCX99&jM-eD(~lN6m9RX)XIUcoaozN&w5yOq|on}5#_szBsRg;kMg zD3e*WXf#UGvLni5?n+`l1LayMMkIy9s^Y*#097+_Y?wny6+9UNVh32}UbxBTna5{Y z#+O3KURT@LPgC$){txvE-5E=I32!J>nf}{zf;YnzNIrXGu z76YNUfS*zkkCKM(=s2mxjxO(;KGgKo7BPBiyT%tP#2PUqfBu}kv8o~KadCZGArIW) zoF@JZ@f;lyv#a6a;%XXTq5@d&e&BD)}noC5W%4OQf8w&-A z-0tqMH>0#Y%S^Nr%G*&Koey*iB z8cj8RIyzwNXj7Wt=XafkmrxREHj4zElx*xVxZHOHlQ{#vvvz24x*JV%l6fgMA~x{Mt`M_pI}9GmQO2lAfYYeVgKjn-IMXJ z$eGFK>vgOHl@?n(vN|8tT8}|ew=Pfse!Uk#r+^`G)@leNMiO--UyIq0iO6U=yUX?Q zt7p==${%L3?frH;pCKBKa*JwgsgIcQz9y#cHZU-8E;_BXJnIURD#dQ;QaTf{G8UX9 z%@ERRJx^*vear7z-&`nhba|@lr%$^_R_$wct#DeKx9dk0uM^Eq^~ZOX1AAuc55<3< zPZzx|JJOtH(w5TGs*h49<}KH>gHu`wh$y{cFQq1ac$HEzT4d-qU3s;_qr_AJh{0hS zfykxp&dq@*2shih9J1DB-(#6k#xhDc+RR_LkH%p{r6xN(_bY0MBsi;dE4|)Bh$>=t z;_0Dr(7El(2ZDQFUA#&Nzx@CQ#E+b{Oe@zkv`XcbYmxXqbzOS;1~R(Z<7+!QFEgW_ zyO_W5lI+QyIWyOFBDiZGv{<~z-#%Easv!X8V$$(qf!N+wv>puuEgq@YLbkA-$34SD z6yYH{k*7ujZ7f!Pn~!z3<-@E1QO=s@SF{9v7T4us9)Ne{*->uqF@$1}*{%YkK;~5k z6SNd_gOloReoY&jl>Vv$wpRP--Qb1ksmZz>U)Y9HfTP|=Jwo+p0HT%EzdJ+027DV8 zlkmLgAniP6uXx&A3!*l=a#Z6ot3F@QXBDt7LPvMpVMm#&0{ryk00);rqUoB^;@<-> zDA!)BMSf$5Qa|ddKWS$_&0DkuZ~ugBF|IJIR6>0U_@f+FzCzG{cF!l4IIrNs&xL+z zmiXl5xjH+$3<1<9ZmFv>O1SS_SHD97MMMj3YwM4;37My~wHo!+r+1{8ZwFd^Tv$m3 zk{uRZT1rSUD_n7Q9&i3K)c6#!d9)ws@=?JR?{J!Cv) zHv}A$afXTntI5Xh#P-fXbQOPkemIaztHSfj6;BE(CZJ2{D|%DkE?7SEqO9;KWF*WN zr`3@vtCJC}Xp;+CmH>Ohy5;0c6DzpArBg;p1;$L|BX=ELmVWNZrkg01i>H(kWPVIOuA zElkbD@W;|F6KH2AxQ8$o#5D-v0y7=M<{kkpf6D~X#!fjBpox~u$#AEfir>Zg=r?P? zjf7uy40HkgW%BcjQu?5so^0}a084-qk`G%t!_Jevj=HCCi(7$C^*086g5~oRTskQN zxbiT3O!?3uv;a6%y6x4jr#XgRRV7t}-{PQk&l*S$IhYy~QwH<8B)X^?NqC}+JVoPv z3?)==jX9TCL!>i=*n6%y1P4x z>iLCKODLD@HF%0!V}S?w?Oj`YOPzK*{hs}7oeEBk)J>dI8*Gg{Drn%k!=P~3M_)Id=jp5h2`M{0H92~ z00?5V4r_Cp$3C(cc@* zQ~)a~kpo#MJmp@eVDPSbA?~&bPB(F#;pMjD4h#sLdXbDw${+j0n$vbc5q?Z8<{xkn z1>Hqy9+rr|)oz7?b)8zv#jGdE@3bBzmP$x8kU72(L)mRL7&gh*IvTAT6!jh1#%W2n zOmFItJeK0FX=HUpkxV44$y6qc+D$}HTzF9M3KIpE&ba>Rww1^BCO`0p-+9bbN$=LWz4+tPW973lhpZz27{IocVgv4EWt8}s6 z@D_D`^5`|Wl7nS%-Z%P+4?Ww64)@HG!`fP1@ozSH4bgksz2_fvp1*dHj)Li1TD}VB z)KI98yB~18%%hUlR{_VhDqNt`ai$Or$F#Cx4ou;XW99n@f&NQaoHluO(&g zDEQZUThQfvMl=5mfuS3_`I0gA%RF#>`FwL(Mn>Q!0i~VO4s7X2c>>9b+#i&=WQ-$AGw> zClbQ93B&|F4(h$~PU-=wLnzO&_d6GNf~&rb*BM3;_GO4TffUP&%!+%ejG;Nc&nT* z7B8#ukv6vjb4VeZYS?i+j+hnEW4*T5xSF!+x=x^wTOCB*8k3i39lByTVa=GHj{BA9cAG#XE0zBnziA6h0-mNw*vy_!9F0%w`qlkK#agK zrgJ^lR5HlX8=UWV$N>~Xtau&(zk-0VS*2;3@;}c+;A%>WtL2kv%80wVNe2r-+k=-N zyW9Kw^aEFfDXofe>MGFu=eUOmH{-uSYGyf$6e;xlrTb$KZUIS?vOD-%Z^}DMiU~vvR?|z|QXtb{ z(GBkQM);pu+XH4!&}{pLQWLxGDppxg_3m3)3lTW+%~)+fNS>V;P}yw^cFNy-CWl0m zK`iwF7JLm_IvM?;S#@E^eG{cFQ4zLr{Sr}5-&4J49?>`aZye9j;(3lOZ9QSRc)!FM zjgc%!D^=)_1SgdL#gb%V2mCTOw{NvvE68200}IGasd|2ihESF3s3vgz3&LF|DpDA( zE``uw#fIA7JS<_{=vj|pS$dL$K+-qa+u7x`{<{n>LNs8AYWzmys{j}L8IAf28XJg8 zb6CN0gO8jZJ+8n1hi}&g$6Bi`N}+K>xNU0k8x~!r1Tv(bBb@%xz4N#zHe{#P4qc!TKrx6cV%|ddDqfTi!}Z_ zso5cx%?|lk8=1+K{aSfGRNJEb)FyEROx|06MU@9-Jm!^mZNZTO z`Xeg-fHKaP7|a~@DO#&6!yi+#cW!ZUqEA?GD_CRVCxGKh81GeNH^FUxM)7G+>*G8D zoPWZ}Z5N*|>dL}26`R{TyWIuj+n*G+=b+>k+A6fPPH$2P-Vp&U8siV>HgLZLt|HGQ z%M^r$uOk1OG3hLkEjQLHt{lu^1@5ZtQ7Hc&RAK z78q{!En4j}x`}Wdf7Ub2%x?2F$*6Je;$HXp`gsxUlPU2X)FfiX>#NHp5+0;dG_FoO z8~t3QJO-zMQ4WbY->rDS4u*3t{k!5#LG7_bmkMyhqkRslL`rEKh=6Bfn$wiyImVy6 z2yTK^QCGi&*McMFppwh#`ob-??F>bDK&&s)K$M`o$6~hBqmKmjmbM**BCT-FUCzx= z&*W5=o+4YXl`=bQDE^6UmkW8%M6+@8&{41hw}`15bIK&K$+$8e3XntvbL5an)_eU! zf6juKu1Sv_BTc)fJl`(2Ws~tj4^y2L^qLW)2Q57S$!Zk5dzrY6Rsk z4^yhF+Qmg3vJoGCl%aqBA2dB|Fmfay5?qMHH8IO%ls| z+sT3#K@Gfd0`@s-9);h^e0jeaQB!FtCn8FxAou5hBljP z2BaLm{tL>w?>Tgl2`(AfA7W5kE|F+a(!iX&y+PG`Noh8dLey=8|MTKKG_zZ|s3H4X z7bZD>%#!}2YRNU_D1b(~6pza)nDkm*(~}G|8up8IDB;~yx>T%u*#MY`u~C6vllfWtXaaFO|F{8W zaIosxBHe1nKydhFWP%DBFh5xE*i6uLKH)4#08mhJXLT>$F8g-owl_4w$8+yR#174& zMylRi{hHJj@XYm1uVSrYz3mit+U%chZ6Ty2KUS&G^%%wZrJ3eRgY!_?;B=8!8fKPI zy9m|jcpgx?eK{w;J~umdjn9L2Kd|ZxFCkPjz-!eE<4wB_7rdvV6fhSW=kU=G<6N2L z+p^!Ei{3n(mm$rqBl@%--Aob89^ph9^}Isu9vi7)WS<-~H6N2i z8sVFlihn$ey8fR4qyt<069AxKZD18cfE&MuxkdCiDdC5>S|J)U^-bC1qS;hlFu;j80jL zzpbjv7Te8Xv5A1JqsIg_7S|t5s&84Iah1SiZIOW38_jTWmA1-|T&0YwT{L&F{#W8E zb%7m_GLAH>rXhd3aK5;GK|%;2` zBg3k8x5#+>7xo+EYCiaFL;G2>ZbMzYV5vL<=q;CO;gw&t^UV&5bx)PfVpq8N_d&5^ zDvZ+2&&OVQws{4S1ORF+l@${82salP+w7!fFSgVG6=|j4q_)ncI_e4{gb+ghka}UF ztNBD)7w`S-*jb$H#HHM`T`FDvX-UQz`K15f-u;6%5yf!;|DJcf*R#E|iC&Rj{t%Bw zDTV4Fa#KqYH8@lxWDp&S=@N0!MY~8k$T`(XJJmreNCmMK_qftJVOylRv;)smqFSZTim+Ov)R{FK6+!f&&v^g=ir#CS^2pc z8$gu;9?7o)wETRgA`f}P=bZnxw9DU*VeI+*%LTsgvUbD}Bm&|kzC-o$LA5x4D+|_xE7?2%AZ4Z=65q*qx8Vd@**pEq zi_NrLOBbeNAI_Lv7ZVx)nl3!Ow7gIRu(o(F^YOMiGC{A0bMMDf_la+4wEJ4z30wO# z=Ok?OS?sNJQ#&=)69xcO5=-X!!p0&O@SgVG0lBRxKAyHUV^`3iZ&WKqTZ1R${e_B) zl>S*B%rFeYFxwXA_xl?TCWB9cp`I=D2eYm0-DA#Pz7>klskadNHIuAWe%X~fF6_G+ ztxff(mpmdVRWs>7>P!gl(uEdU%O&kPFVi%FlXbBTwajlHB%G|EWUWtt@Ge~-uuI9> z%EmN8PzATjuhyL{06@~k9q+0u6d=N$PTLvAtD=Hx{_mHl8HQmPW_$Yv&x&5$%6+Ea24dGH6J{9G=lnn z8VdvU+X+mVgZlH(O;hgegR0S&+o%(C8z~j32M=oFajwlDqt3Bix23Y zV*h(4EXe=AJm=-%`%jL4`R~t-L1Lljj1L}Yb}L9rX?vUOL2)`rtUB+G=FeueCtJMP z-b|yo8J!?>_Q4J!O7+#2julhDBymoODjiTCq9KS6ilR;QSzgiL zQ2=OWKKb@FtmNXvXXaX9EK|H5;8)o>TX6>JHaW@E=d0gnLS*^`oIuD0oSsMgJLHLS zpA69cI|#pKTN5Pk+S=M;l@#U-XAAQQU2PTgs-doGMwdz0zJJ>gpkry#u$-;GoLo3j zoE09XwLZ{kzZ%7|%v6erFL|rT?Z2j?<5oR+qfpqvdO7@YvPIK*@;YCbM5>-J|Ey$z zus}9)(p_tuef_-(f)$!8{kxnY*jik$&_vr|p-a8&54(=tukWCc7g}SuVYn2}#ZJfH zEgKOe?Bx5UL`293*ae!f+NPEj{rnbD7__g0db7)-OP|s_{jyBL0@_53Hr>dGh_$qt z&7xrIQeVZGD0%WN69!t^L{swIv?rMiB*|nX3H;-oiqg{b-3{VgB>YPD%si~Lc6tAK zzVH3>wKXiXr6=DYSP2Lct|yN>w8z;?3;xFi**U`+LUe&T&dm`RNrJi}z54@35c>zpr14G9IVu zJbl!q`>R30)&zf#1oS7FGSbq8eNJsY-zYLyuY-((AHyW+ual{=5!6gCsR9)HMLfR< z%^JN|6U%3xK((EggmEZ;KBx`O=Ip`P$?C-RN?1 zM1*#5uyq2lh-39R;2O-}{FrjV@k{fZi9_p3dS?g~WfGAu%0e*6?4k$aDhcn}Ux*3( zu~P(HX~zFq03ktwE6QIId5OO=K4S=SAFB`aJn8ZoCxx_Rx@5yB8o~)(X*Ida5x=9~ zbW0qpC|%h+j?pGHmpET&RY_u{hXj6uUyl|_0bb}xUkv-_I)&SFHgS4{=#QPNP1tk| zHE?W(nh_6d9wY^AYnC@%Sa)6M3QE+&0D#^4{CTymCV}if!~^hIAL~p)C7=*~RdXeU z7t}vHw|j33rYK$boEcRy8RcO%gbwtd_d)wyJ?#_%7^aH_PLBEg)$z(`EV^ikm+x)j ze1rW}Eg}_~>^#cna}Js}skZtD7EiM&q9cg&L0Od$ajfLx%bVk~eVOIGl2h9b8}YVN zsdYh#{5EKO53sZyenk*h&t{;WB((vtEn6wL2A^Wf5LsA?hpQNGpIFCx0 zxtVntuSy7YDTRBEur9y*{ObsqU43)bTd}&_rD#YnVve{1dD;<;&i{zAR?EC;qmZk0 zj`IRnN=|!2({J}bLbD*vHz!MN^_-g$ey3?aUe_IgM&tM9g}tD5?Pd$xotCET5fOzc zD4QmKC8J^wYOwWSWb%S6i9>}{ySbX&u<4bCE9bMB=^t)0eM-MuFcoaEQ(|9tTX^-w z$RhdEWL+~KER^967UUV9d!g1Ynt(`1SL0s)lLiu*|bSe9xDH0~{3YP`;i$weIB& zB!hq0UUxnCT;`9d2dvoxshmyi-*QAP1rrB{Ii$wU&iJNMOyctPB;`qQuKI(jd^+n4Byl5erE-`{pt2UAKQ16a7*o4ZBlr< zom?6X6?65GXD9dw79&WokUpStFBnNC4BQ;(fLJf2oICF=5S z^k`ueBWm%SIB7ZUkqpx^d^ru06Qlyd-wFyiX4yR2tbkY(l#<+c6CbW8{90>s-()sB zRw}K1c2O*olYN`80_wU9G}!F#6g^n#FREDy?*glCFZY+g&hqcQHUz0(%08RC@Tr$h8=Xq6?amcpL~01hMAM|~FI|2x8gj@Y*aRoWiL#xM zt0G`57BsPmx!bYj@yhp$*WxW7Kz~ft9*Y;35z5On*EYl~$T{5(7eG%lJ~89Io0klA zo9r1ChXL!e&&a|+@M0H0M>ut0DG<70^oKr_$}MptpxflWqauL2(r3QOx6+9brtK1f zlr*M+kk!+86J#4?Aydw0P06ZtcV5=QO)y47~U25bS zmxsGd-E6=`B#!$KgMl=1iPMQF+PXQp1+EO}o=Pi4aAH+;9eFL6ES$G9nF6`66Ni2I z+moZGFz#JLibs$zn8sXo)llH`n@4?ktB!LQfy>(KpKUvKx2ibPi*p+c*IU}#@PIL5@vaS#y%^I5zLO)vzzIZ79 zNFKtYG6bfboQfh@$6eb=ASr6n6xM(QGV?kKH?F_^t{lfJ<;qXPrF-P4uAC{`v{eox zmr-KPjP>gMC|(7qC9%5ON(yYNHEw?-5;z(Q0_p@-7^p)U3nK(NUw>1rpUSMp-=l0m zLOgq7+iU&q01&s!()Xn}(S5AVhz7BJ6h|8}dLryi8&W$G&*HYR{Xttct}kbaVC ze(i2O8}~-&>iBG>+7q{=sm4aN;k7H;t`yYMeU@$^!k{uk)C(Y_<5#iBCPnk7{q#Br z3E4ZuR@vF+y;~`_Y1s~9GJ;DW=P=GbW{iy^<{Tg$%&E0h9t9cJxsu&B0hS<(b0tpB z0ka`FV^>p04ZAMX(6S8c5`C?A{5#Vnb`p07#?cbEfm4etvOUjfKOj53P2<2lzr4U3 zaGd=!YJORE(Lk{2xH%-W-}YiO)@}H#IdPK3Hnr`YS;GL8Um@!oTDc&j4}|gxwi79N znbPL1ZW>RdX!$wQZ9aP75IIdW8GOEYA?*5Lyxq(B@z`WpRp+?@sTg1CwMY}Rf8Ehw zl%-PmBr(pOZH>J?W+?@LXp!r0M28v?V{TI2T=(6OQ}oi7q%1WF<7V|`+$b^vjpZjC zT|0#Z(9Gjv`v-*tiZkRs?{3Bf-USuylj~ED-ug%bxtbs3c<80={Tbt%4X$c6sIT%+ zO6ReZ9qHa8_q(hPb^zp1`fski3yCDf^E$!$d}9`KX)5e!DtPlH2`N~G84OvbbH>gw z?%-`X?5J+BTKmZxza$iO7T}A}0zir4w~5?g4zn%_&mdPrmpy|8`&bwV*sRlLUQWBS ziI>UY-b6Rn>@OND@q-n+o_4rk%Ng0PONMbuv6ZWz4;s~b z=A97_bz3YM4>wwb|VXxmjMtgnrijl?^}|Es%~l`uny|}9c!Sr0 z@nnkwAPgy5DbBNxH%{yziw>MRJ0W&*W{N6sdO4BC8?-LkS32Ygl6vQYBT27=M>oE%;f^-xklj98Pg1&Z;G9j88&OnQ7w$b7T^Zx zPwYC=qmQ8Xuy_0YF5UMQ;v5Yf8}7c4%Xsi&t%^t)HO_JwB94#)Ehn)eN4thlAzzTt z=4M)jtMI|3*ptknD*cbzBRzbr{q!ckgd^bsKfU%WhoI^24V8emom_(FmWpW122(Zf z8=b(XzDE{TKR#i{Vt-X6fj3)NhCVHF$Cm=UDTP%Q+Saxjy%Q(pD%g2bnfkG&Ki}Vf z(eIjQxrE~vZmfe|)b|*SW<6OKTdZtsEU%Y>B|u4Z?}?8Yd$sIU=G<{1R>1TFY9^%R zohN(Dyrk5(v*le_cL7W-(fw&tuB|HP$;!;8h)35&ZU4G5)8odMd;>mYo#8_pbO`B86Uaq<*#0dwxzHmo~CUKu>3wB)fRo99#Iwh;T;5%_8#CGvTomtQ;TptB}Uw!4SbV zN8}h_HFY}p(fI*n?fT6lwu#Gj568{aX%VzFdOPnPCfXN`#9{}{YJX&xo>=uoU^6OM zUiAiV@^M|7dh@g|wu|Ge9732eTIb#~Wwmt;yn57(Fh?mvZVT4;X3@_lomq8~-fv8Aljl@fjOuv+(cW&1%q|gO$UB zu;%4k?(NA{sQ+S)Tv}gerz%_2qRbfnlt%Pud{;`fO`BX~p&SSLm}v5{700&i&Wvoh z#a<1_yakB{@S@bX3AS;YMmBkSomBbjM*|srRX1rW0YZ!C}Ig%3UP0zWt{p+>K%HqMdN}SkQ`Q%Z$cc>uJ}}T^JfE%X5$9 z7v7gE_}5$-lzHm6;$@mTn9_w}_AHyN#DV(WjY>BCxP@{C=Nh%HThaeMM!TDJ(1x&A1gG#r_-!M^o*H|omw zo4>4Xe{g2pjs=Q4e5H`n*YGS4vzq0siY^Vk%Q7y6Mvco+Fg_aNui_h%waaP4&%Cr5 z*3LP|J=uFEDS~4_?JXo~-it3`a3{2%3n8>i&9hX7T1h7K$7eT7O<)kI+twyq09RMM zpR@vjCIM)|rPZA?W|0$x(xnW_FGz=6pNDuIH*2#_JAD865FoVQvI=q8DJ^L;A5Q0a zOfn`=AsTRfVRm`EE)&@N@?u0|*KxF?C>H9cH%q8}@QdW4HpYW_;)kJk_ZA<5si_Av zS{7D=e@=oBHElX}(se?w7^~GwqiT)&+A5?Pm$eF?5O;$yPH5VCQF!7q^V&|EUEt+z z;}s@4=~WmukK$e*T=f13#ev>w^6cJyJ~$3!r=1?lAuTGDnY3P006{P66!_|Mu$AN6 zj~^l`YWrJ%J56VLENf$oVYQ92mPm!~ul6_is<0=N+cv$<>#rBQs>>WBuC#9LqxIaY zN*7~;F94~;HvOmk7}K(B$c8{^cWbY_z9e16rv8`)jdv`yDnFaLTe?WS@|VNi+V2mz zvqkTu|9yQmKu^y?zH-NW5gva&B70=F!zqVMQ?eLAdcoU@#@bSUUb>iso;S`;{>KGb zdNg@_&vrA9V_z51GzQ1trlu=|ad zHU}kph~HqT<-R+EDKq7&7l+jN??)N-RKN>>=J(-)EF=-QW}o95`CGwPyU`%o1o^}A zL>G4dT;yA$(YLKeE~946TyY1(fg=ss2FhL(^t8L=7XzwiFXL_!sde`Q`tP1Tx^uq$ z4l1@8%UL#PJp%dJ_1>Akx@)J^>`=)PSbrJiGtqaDdgc>Ad^N04kQH$B!IJT55bYRN z4oP8<0$W`L444EFPv4Z$RGKfkx*9jx&yZQjCau_w=iv%e@Jb`vlsi*FTYMX3eUiOA z_ibNcw3?D4H$(C$pX0``-f42dh^Za6OAHaj z4~53{dUD7Ki5yz8VhD5f{j-C8NG?rd&?lCmCp>1~A0W)=e%Z%Dr0w)CZ@aD~^}dhX zX*#?jTQ?z`ZTz_o6I~GJzq#cDb>v0kqysl^##(s5hrsSv@>aP(1PhJTN|dm$$S;HNy;@@$;LjzloahWcHP(dcmOZ4 z!kno3cNv+7B&)v9mu7DCv^8$xzxjw2#FE%C>RSR|u_z1bkAAx}pmjow|oN=?A zzux_xG9S^oi(j%m-I}Nsp6qk4r=Pa@GxDytw3s=7dX`q;4u5TjXSB!&QPu)07z>D2 zKvWdMII*$NtoL!mvVFXfyNmq+1-1@BKf?o+E5-!ujQY|JF5Jws&Ix%{Pa!d1=wOWi zQU4BUnr|C^p8gQE%0M-0hR7%%Mq)Y`DC#N>=s~IQ!A&h6%d_f@K7uLX`1jfHgYMZv z-;wM0mm|kul_$w;U;0TD>MbVEIizrdNO~4C6V&<9qv-o3V92*=d2~n5M}UoE?xrMt zhDFWK?`#%7W_;QQHD_x~W#t=H+Q_--9kUcwcQ(9Yu3KsEd%m1{8jV5so;^2v-T$E* zxt@lQYYacoN_ ze0HA=yZn$FjSR;F*x~Ja87G*Yz}$IHiM|T9=>ikiRGA$WDCWqF2sBghq&cA7eLf4Y z%S1e=&mb3SgriiWk^3>Mhh6V>$(gzxSetT)Ezc32K}&kMqu7AXwnIoc8S^nBoTA6I z@v&U$$7l-qDUOTVS5kLXd%cZCFXazEkC!%DTx#QfWq#RO3n^cTGB|nr*(kp7>sU&gg(Qz1KI1uK#$x9l7ROh(Ge_t**1A5tUK8vgWE?mG6bKrcA!P`E2=b@rGF?;k> z6KX6%Ql;C?*)8&2wgdC=1)kp7ds=d!I!aF!QXeCHpgRx{4 zernRUlcQNTd@%J(*}xoH+tRML4URJhS4vR&`@}c(+{K8<2f4lY{M~Nkc`Z((;eaQ= z5kW_dpxEKo;AJR7nq&yPsK9%H>vwtPS$W}UG&IrieO1P+tBKS=i3jSW2PSsMCk!Wi z*U)4<_`D(MQ1aJ}e2?o;oAo)oXK^+67kS(D!0NsPxD+bTlblpnPEQizR66JHq*cSN zNxdUsJ36i09&aVtiDXG5Ym`XN*hD;1q?C#h|1+LO5<>5_fVQ}4YP8<3kvxwu%w;s& z@RtAiUTOViX3L>k6HoH`a0-2>Uu}4P93{f^9Hdp_H-WGI^u)&>Jg;IYqODB|>raUj zYshNH2TDdQ)>rgMk?$-107XsmRCqxv<3rs-%yu*6T7V7fw&zlUl<=8AGXGLt4@QjW zZ9oW;1z}_2c*S8KvctXhLo1WnV6&Y;ouhC;v3;uiUcW6CN01738X||IofEz-_lC3S zJuf9H`_u7aq#-2R9PK+Zp*ifbN1St6hBNkYZ9|L7k7!xz>z5RIoS`1pfJlBqD+#3r zkNxyP7J8|HtW{7i~-+LBgrJ8J- zq*Ud-oBiX4LX3V538boZ zT~h!u(@erNc^yOiNWk>p7+cnE^&D4&IAW1%U!hLiDvhM6K&W0C{FhgG(G8ZJF(e5U zh}aCl7rdow`5;^TYFP2>1)}I(JH{T^kwmQR6l&H3hlik~rKeq@G+hXsg}S`1vnInp z){DKwW{6kYeuFXh-sxg3VzbMy$pdT+eGR{(8rHjh-+~GPJ<&lJt6u(k{l)hHZ8nf1 zh(?}!5<%Wdtk8ERpQmzrX&DQ9g;o5`l0RYaoQ3t*)f(h8caiDDgw4xkLg1R}0cv66 zviBj>Jv6Zz{@m1vlm~qi{dU4ZP4yyHE7xV{``K4;>I{J9TTy0_^LCpZdW!r47j`>b zb$6e zzw*s=L}DHTo~X`d9Y`Er!QY;fl2`SPK35S|qV3fr)Uic(q5K21)6kxZjtJ{(Fh_8s zjV}w@q`j=)i|smCU%DF5ZSm=N331pIhz-ozLfCyl-iJl3piE-(-qa13kastr`I|3g z!l1y8q61){s5Uexu=}i;BeZ;t@6q%jga+69s-->4J<>ph`9^!Rp}5G;F8Z6W4p4q9 z=|$KEpuDJP`Jjrkq>L3&t4*7<|3TBVS8FX6F7_Y;(5SL zFQ1*8gMYmyPAnMm4HX#fJJ*ACzc@19kV)vZ8X{|vsHEhcWpgFwB+It@wI4ct(8_}c zF7H&LKg$r3Btr!*IBR8AcJjBY+tz#i`k4szb3Ob_UXL+Uv6~g&@}JBXyd@_u_dFrf5>N1baBeAB?cFm))pz^}AB3sFfaz14+~jZh z^0_cI7Wik&x9X0`5kv|6(GKESe$2uh5X)-iZ;6_C;-Xdy1!kriV^wpstlL4-0jPUMPDB7eRrX@KvG7I7|>Ki58}rQ(>}g1_@?-BHjayO-9VjXXBbqoR<> z#ZFuu$0g}IkyqC6&ur^eSRvGL%*~%;3lJJ7;rSp66y{X?87a@PVnwf`+A^TS+uTY_ z{3sqT`GSB2L%8UEs&uGTEQAVQ9r;C=zi>L{wl>Q+N}Io8Z}zx>C>J|Pgp8TWzV2a8 zMIu83V{Q=z@XG-SCt1(wC+`xhx(2%RvJugr5UeMlcvwr0GXy02e=Fy|7Imynhsx zq_x6icc?@ax%L*xk9ij3?81o`l&&)t4JQb@)SjnHr^5u#FbF1jVDF|kUGn$aO1&Jq zv07WXdPp@VfNZ2mTwUfn*+WioY#>9B2VgSox|n_{Cvd=<7k%g63EzE*%^8>0gf54h zuoLGcr-|%l!&m0DJBJ$shjY^Gm?Bu?E@#&DoL(SrCz6##AEPfcQDS5bT&l}uVMJ$) z%`M2Ukk^5bc;NGp!-wI!l*4}3LpBPhxU~ z`{t6DoetO0`AcgOumHvQ3JdUGGcI_RE03W&gATm}1^7M5)|=1Nzx6r$FZFkPh!Odw zR6L|ejaWcMtAPxW`OMH>rIA7^JZb;uLeI7M!DA_mW=4(H#uqGDSJc^d&f$B6F{b=G z%!n800c-Y#f)(h#G;<#w4C#*<@c`0s4)gVFdQOI*r`0wb_SbPB*r?6VLy3JMp`5Lz z8_Q@*E1bo%vzAPMcpbiBlV8dC{$sSQl~mtfVGpuNF^n*0 zU4U~riLuzDmlCrRO)5*f&9Tx)u7-^FA@$N%!~=}qiZnRUrftisLur{Zev(FVk2jK3 zT4@nyJ87xSlM`#vs!H2WphEab*{$!8HlsQ3D4on+NLLP;ZvTDBu~_GRc9ytjID zg7ypMs;J&*2NddimZ|%w3RpR=pu`wtj z;m=EG&bp9Whd{iMV>h!!1O=6;pVjwpQ5ItZD)ewbYLH7fc{%nZX6f$4?67E04sX2%yS`{JhRE=mf( z2NLD-L%y4xrhfECJ2LWJBy}0gzu_nsa95!Qb%^UZkTj(y#TmcOZ$&qG-#s10NE*FI zn658wq|TMz)`;E~pjxudctRN!U>L`rFH;5@?sl9UuE_s=4icqyu*I3Mx~*M*`)2g@ zWp%Fj^U*>6C)RyKpw@G0o#8f#(OK8|p4SWyib)*(5+2-oI>z%1-Lx$mIYcUi}rySg4?6)qA%cupzQ!jLj0{}|-4lKm=uv=qryOC+Ip8Bct{b0WdL%JS<-SFK{ z+EFud&d)`^1Y$!I9z>UWDN_#*oI&~+Sf$>mj=CECh%vkTIGQ_T;I$JhSVzt_)ZDFD z57)#A7GXa2S>IC2QJ*kt3yv zD;dQOVRM}IYUcApQ4t@9vQv=a{R*}0EH5Kl!PTAPP14m{7ggg;dzE%=!|{rh`Fn(i z)*}oev-8-H$GnuQp-rW#omf_?{vNWDr)+bY9PIh51$Zi{(3vMB*w7uF>U>yATLGKylk<=J&=&4T2X>8kH1R3E>#gs%8CNJF!s;`ZE~Geb#{J!^wWsF;``DoXqx@C*$#nEyMlQ60#?M0)jc_J3)KZ~j#t zs`~!_&uBZ>pfALs`B`+og)SQfjS&ziG&ALR|0r@EhvXDSgHL&tLun zl-;NPKXanLh}!?n6aRXf47p0KggBX~r{e_+IEsV~(xQ~c33&P1=Xh)RHA)S_q0y#Fbzn?!L6NNAi zmZn3j*LnZClzgRzYWuJbENxvmSarTydc>{DDbi_CznBfqWwm1_VJ?ovDoJBpjE281MMk!kseC=9GGXCD6o$@A|kw|7u&l@2R*&w^{$54Q6i` zE)JFN)>jvRFRGVG$UkH>3c~Au=7g~U*I%=57v{C57<*YD^4?`t{!nY&o1<#~ zq@{9pupqHD1;{!~`qv6PQ2iyxN~{MpW~YcVb%6a&#qF0~mcK1MVdra}zQIovREdjX zIz@!GzmJ8x)#1*SzpME$g1O9epQ%*G(CbBtkh`e=Tkf4iWbk_VBK9mNL^Ho5Rm$GH>pxq3KJz z?72IfTLroV1v`UV0;43foHOlE^E@8EaKpJ^P+g8w_$#~azRb%NQ|QHTKznQLSd_Ko z<-&rCs@BVD)6I-+7N)*tA$axB*^t*YJEEEL#_--j>Ap`-T6}Bq z)^{INNcqnPKfnF10>hb-0f0(sB(b8D+v5i3`jqnW7#ODy+XafKl!}i7V>ahb_CBun zcHeFXyjXqcx;v{M z`0*O&k0mTlrOB&b5ZP*##3|l2$eZw%#kT4})GOFc`0IOx6bluf@*hVGsI`ChX|I%| zjG^c#G2Fb@N~~z+tTKICfYOYZ9w<%`>ZRY`gthZ4fk9W;eq`g#JS^9FcEIf-u3)QG&&V%c^8BO0~kBWryZZQ@5-#+05I> z)Ze^;J)5JRuM8>w?>r^)n97MFB+x`Y+f$y&s{^IZY|mJkwON9TV`B)+PC&N;w`b;{ zrlU?NzfTTP_r_MbMAY+UNF&7471*L11Rjr&xc;8%Th{L9%Dt(lIGB;}!kIw-hz?!* zoG1#X`}Ro6dWy~YmLuDKr|Gi1w=_lr(Y4keP!4_R+$&s9{>bYcjnW&{H&7$V-0t78 zH?rNwBqL4V1MX*|!S=<~*lxv6U;ZFHJO>6FqpOhL^96g=P^hH1mXXc>sFScX3xBCl z{Zr!%B_3rN89T^02;;AH%XJ^hc2TW+3-{=32fSPL9qB9vMhR~Sjofsh`pPtM&!NJJ zUrrbZul*CC6u(T1zO49`<{aNzodcEom{4)4?udWyEt1MF*0BH38TN&o-N#C$g&*7- z-#yhriP1ICA>^0_ns4*xvNN_bev--d@#VN?Liv+mhn)pk%qStE53>3iJ3@TVZK8rm zgCPcJUas{l&sBgfJ4R_J>he6~76rg@)O7FmNVe6Eq4^t@*pw*4A#1m0 zt5NF9;+n`o$Bhky7hF6=O_jQ7EXLt|a8t}cW3N#aeu@f%tjOzfr- zdVOJO;?Trrm*Ry_tmO%FCfv6xZ1nuqD*x{)fgoFFLB`FD&FLEyWmA;v->l}h@cR7q z2eXr4>)~7pPBO3ayrphuvKQ{Qv;B{&`4wd;;YDgOUPDzaOX*ANt!a<7~4z^hNuI}WlhARi&tlEqO2B8G9ghrwrQLysG4lk2W-9@AQi1a4mzA?dRV(v(5dyJ} zluf$Ge%Xn{DC<=yw^@9-p(E}`(CMHgbgqh0xK9Jq?&1> zko6vwqa=UWZQ28%C5674V#zlk-nB9&ofwqH^yO>`p}+FsLPH!Pq}rhRd|=y@iyB$u zYo4tH@!-2wX)$TNeSelm6*I z#Ida@|5erhnpU+~ziqUHzC!L12P|0l>dhjTz-j+r(sB5PLTtr1 z4e7hW1A_4G&=D9BJ?(!rZfQ*QS-j2b>8AA}x1r0Z=NuE*3K?J~Kfbrv(cNNyA`&i8 zHPoAWIf9#wN!b=p!R1}Gjl)jJMEn{R{P$0JJeuKFl1@I*C#*ReeG;`{0`_r%R1CBl zxt;7T$!Sqx&&~y(P@nH*L16tmen8wy2AP5*;}oE&n{v~a}x=c?mw^;2(e z>ybB$9sD@I4l>6GZX&JdW8FYjXhm)oQNEk}{<@ecLh}&X;?$3ua)F#GM&18@HyOCYfnjr-=$lLL9hx3DaG#=)1bcV((f$L*TzgCV|(#I+3$nF z8~l#XZO+*;ega;})DNC*%>5$Rn6u4}v9!$eaVK5hjDem0Wc8vt6&`7O$`vok-ozu4fQ2_> z!mliwnfg>QH8JFS!8kw&Cbi7Z6$5ZF7AgGrqu7Zl-;GSLWh-z63ju2C6`2t%GQE!Z zo|2c`rs~)`16rD?ha9&D-e3xHrc9Hxb7?xpNMlDP{gM5N`KW_rGh2A$ad+o;O40#A z6iK%4ePd+a?{D2TeP&^niJ_Ixc{lhD0QOQ7eht483%Dcm0&!jfJwsT}mKGeURdg(} z{rpd5D!8hobqpq+N5JT0T94jdG1?L&%1En|XtB9GL zx@Q||G}XlDP&+Ut`O1vEB{V;X*ezYIA%}jHTh3Z8`E0DVPx%C#4Ib_L3@AOE#F$9i zoV+6DZ?2=*uqKS2c|d}Nrq=GDVEJaiAI$;n=Q}2jZ}K!=R~t73*@^AHZ-3c=P?I!_ zdzh9R(WpEGx#wx)xbdylP;ADQXa@XrqCc>0rcYR+ID>RADbq=d$!{J^-RAKky$SwO z2Iy`8w)S&OJ1gx~`Qi%CET5S+JX9V9p2nWOfDNP91qPJcvB4#xUY>B%h4Z)J`q>`O zh@zm(HHq#U8uI5A)duyWu~Gz$_gq4fh~^F6RX#;pL8vn!Wp>t`Cm79ZC^C+AmTIES z#E7CCZUw&R%_rICn;n(JFTN)`P)Mq`mfG7;QZk9rjP9?wf7G2PKa(}5Rldh%!W$E0 z8NQaR#5t$Blb#vBTp0)^Xy$Mq)5cqM(&yzzLx2$bWk5keH zQGDq33mrVMaIE1~MZu$$bR%=NJ&*6V8C2%iX^UZ}A*KwGHkGE0(P^{U6k~pVK3(qm zfA%$t&X{dE34%CqW#-@Y{~QUaq;}Ga!X&^2)W%?@f8FPL_=Uq#`6C%_`aIRp4di_< zu!bG)teLx6jaw!1?m77n1lUAhFQ0=0=USXZwPJ)*^`&x% zAI?iTTSI!14?Z6wQ3&id(B$f=7oSpGo>f?pBBlIQyRl4e)#F5rziM$fzR@$(RZ->K zs+ZsET=+A}+K|(aSW4ibBY%2$Cv(jbY{#GSbzVCKvh5&cd!|=bjNdv4lxbkeR7qGZ6cD+_?73o= zjfI8A+U_jltd=`cFeiN8Gij#M^GQzD*p=mm{^#<9->x)onti8I`IPT|6X!Bw6)$}5 z6xtA0OkvA0Zs_dst$-c0D8%Yy>@tYJYQw(k0k}f#m_D6Y=rfpN$RD8=&hiz$l_y46 z24^wlcMtbd-3ny$QcqhtV%7ZkdV7-U0zET;QhAWB0yKuu6_vDY}}gsY8(Rc zx~a(8Ty1YK?75w1gljQ`A5`b04{EStOlQtvcw>L(KT+THN&Y>WL`Bcs*(YH;KnFl( z3(9P=$jrPfp`0At3wJX<_hd|~NOw@GK~A-F?Hkm@1v<4@2dIzngZJA0c*f59q1Hz2 z9(FMLN@B6JIN2Y}^D;b64jS!=%)BEfX*WkJskbTfl6FD1B(!BlJh`&6`tfHyh=MW4 z1=M7t-f4EmifX73HJf@~YA*J96$5SMEsOV}MK_2yQoSuHBHx?jEM*H&n%y*2uz#?l zg7he@By($h2@%!$8RKh_ZHeNWYcQr(cAgt*oR95&9>lJ5K>UIf%0cZS*X zXp^q+om8K?CfL16T8iv1L+zp~0U9qfMZh_a`fHlechFF?TCLcKHx*j#PQmxf`ym{e zY0C1ZcZUNFI%%vMVv17S3Y?sq3L4(Mt?C~298Mkr37 zk)iJ+bE?^3kKKhsFSprY__PIT!yu$1y10Aie4x!p%}-dPDhq>NSY@^d7$wScjM1eTIG<^exZ{a-o&2lBVZ{W zO2;XrVS8WkS4RsdQ#<#}k}b=JN{uh@$u#=jDOv51$Uc%Tr_)hIU(2SB&6p6^?#iE^ z`AELGU*BfZAubsp&n4(Q)ab{051L9|+IgCe&;z7by#~z8YChE)^X?12RE6M znp5*jzF|#S_f0(6LhTiu8i=KRMvp}=$iD!1oQoZ&4-igB?G@vw<3Q6r-=q7^i0O&K zL9%wU-aLJDzO&RnqO*6U+1@qr@e8a2Q0N3%v#bfEj$X1Y7wy6qwN3fE=B@?km4 z`NDBN-9DLY_<=7-J#F{u3;K8mb0ktyF{>X|PW)*TZOqU?NUMxMw2=3z5T`{17dMuUw2=rd1M4-Bc#7XA)y=DmaCA#%SOxSa(L)qT43*pjWB%P z=h;iS30gs^b01PQ2QlX=L6D={C=nMqRh7Qzy&J9$#N*HYiifdv{|Ut*ZG$=0fEd3y zau822rj1uyD!)nA=5P1fq=cl0{aood-he^oX26v<0)UrJ9Rw3slMURsUGMOm+-b(? z5%n*l#N+*i1cDU;mx{ha1NByYTWcUry=Sq{Cz>q&OkfBp5kO6OW@p-FA)auxzAA?> z#PIcjYGx;-lT7GRiIM`&t5wqW8qPOxqv~WkbD-l|rztB&YWqo3$GwmN6}w2#n=or# zT>NyxU98ISkp3(t^_C^ca=`!URk8UqS8;t=$=i1vdYroh-WO-?*VMop9{sQP+(&OSde*BOQHfg3EVL z8O>U;!92l?LYpEkHwDH4)9tn^?Mi9NW|Ir~G7Z@2So!xzJ-Vy+;MZ6@;LW9ObPHz* zbH4J#R?F3(C#W)_iDV>4BP@TumDtTGgS43w1-%B$;4;BprDb-N>R!8;Dcor3hS=Y9 zz85V+9x5}M-S&CF@HV3wV!~89o|hB4Z`0APza!`pno?6On;q`W7F;jM@wIo%Q--qb zKvBw@Bh)H+s3^+qay^Y{CTUIZx3kARG>UzY8c;<@Z0cpVShkQvgU`2+cr7zc*Vg~DwFD=li=)8(NeY{j5r?SNLw z&ZHG+OFkZ=-A?HLi5T0kGVmyFv<+@S?eSoVQc|@+K{PGCiSZ*(_)afRgY1}yhz~$%$Uh$>B^pRcCSVGz2afD=%(kMWybS8wy&t6>dOv{%ko}#pA0eBRRt2 zi_vTtDc!K8F_?3enzA`Q>+S|KHO%2XKB{gS<)qx6sOvI`sPmU1KQTcc(d~~^$#YKW zzpr6W#2cXWGTI@6xtR{RYb2vK1iYFnkg;{8Yu|79;wP+J#e;&Xac{k;CSeD16nFD2 zoI&mlhV<$Uv*alj;xkNhR^V_|19jJ-$z5v4_=kNtatwO8!~FE`?NFmpF=|8jL8?B+ z1G^VpLjuBC-sRzdxTJ33{z zU6dqr7Gra8|Md(WB_!NRrCVINoH^GI-5*}8TUKGGR@*O(b)lfD>jwXb-ja>Ttue%Zqmw1fIS0+%7Za1RtH*3QN#bHhyy zTSZnV@%*<^&NLpX{_o=oF%c@&6&g!Lk}XS(Fcje;*;;LrK_g?CnHpoyxRQO(SSCYC zDnpX7FXfVDFp07a!Z4Vz%QCk6jQ@lG>wdlNXZLw<9-JrV!8zx9e!tJ>{rM>Vas=MA za?;yxe{Kj96(fw*&(9Dy!qnH}kClFUuCs3eU?Hnq9I+Nef#qb5tL|)~rMF~ZJ$rU( z<&IKWlt7TW&(o~%OMQ7Nm8x4kL0C3}$8P^%{`@prv3X;Y*}mH5A0$^6`S6@-sxvq= z-4jWTj*m$li}hI*av%2h{!|n=SXH9T ztU(C=gBiokre78vP6I^nYe?@6E@KCG*|yDB0cNhIv6zYVIWy@aClnH@PH&x&LuGTi z?-R6vmYO>KeB-~>Ik6VghJf2xYxSMD|F%)TGw~CJAJJ4@SCkeXD;z~C>kufO1Avuchrgnurca% z+yTOBL}-LI!aLVa*yEcsOJ4D{RdU?cgLh zs((BK?5oHKZKf*|*3=;|Uky)zD-cd%FX-2r5w2QfE!HSWxZx5PeBnsZqq|`Y=sHej zAn3sEtj3qfMRB z-r!=#p`h#xsiV|wxC^+Mr8MCqv!RHv+!w7dXmHpS?EtcR7b8VJ&CV-AJ(lqsFwt{i z$>F^|5y!d!&Qh&p$M>CkeX?1){b4U)cd;BSWkO$!(QIb>7xM*gBHv}h3TT>hY{R)+ z6H86f$-AWI+8{n~TCqN4xP!TmAyA_m$-WW<5DI4y?g<`4t-VpWpDM31mxmCEF`x2Y--+t}Q(KlKR2&@mkRP zU%sT!kk&^e_?tlC%stSBt^XKJNAp10L^l zZN_@;lL>Y6ZslI+Pp$oDpO-rn_;p~(k=lUtII+rtXQ}Ki;!@z0F#3}un}vq$uPXhw z4s)byCcvf8E51osmNWveiV=t)Hvh1Wn|d{@Q`TGfkEkgdZJFt}cFMS5r~i41~hy$$zNdM7+=zztRch@t8na=ktNu64`^1;G^tHBxLH%&Y?3pk_hlK9)(+mPO@$uQnLL+C z#ve3{KYO%O?{}>Bhg>)@;J4GDQe^)QePGE3daxtoOhf6@l;7QAD~E*#FDhwY?_8RD zN!j|PGneU@*|=a(2Fv{2kGB;|9KiaA`&@Px0%Jz^ndh__Tx~=LkE0(M#-kKlaw+4n zb$^-aSb~Sod}QbPWCnJ64!7Ig0`P)1*>%R*66nIK7s*%o-n@;kEG^Mr#4`!ii$bbJ zSX#>zaC>5B!S<@hK!c|WUqnridsZrbiS+ZE6N6*?S^1-szm4;yc(}(iS>81aoWx&> znvO!`*q_fHwZ@P-T~$yjU7j<}m{iWC#4T~nx8hHp7UK{ZS@Ma0cp1|%8h_$_{z}>o zSFk$O6&d_Q;WQ!Ynin{VAN)hN z0%UNfuH=nq&udt`zbk*~Vy3&a*g$ zz;_OkhJRetGJLPacl|W1kh*TtJUc$gt;7Hf&D~bwM8>?&a6H-EIk5*S@3*-X=!|7e zUbXf`w|ErBqCTJXp1I3)?2AIQf-TT=_H+Hb*4)XUpHqa?=p3y(B~C|p2sbiMhP3sJ zyUARZH|fDcl*T&JrQpzBt@{px&60tXdDXWMl)&C>Ufthb&RuR32*GyMgK<-pO|oHz zuNYjPh3Pt@ZmUUiI=DWc?ER=c2-T3;-$nv9&#<2ow`{6 z7w$;>rJ_#4gKFdmrL}LBAT&4;(C3eS$<}R+Q&5LfE5IR^I+x`=&yXQZ3$+`s6h{`L zBTe0mt6zR{`Gq3iw*4o|!KKRZJiqE|6bs+q-@7ZWntmvuwuh zKhpamrM5ke<^CaAqz~HtbT03v+r>{oQb&7VINW;;2hGkIT%G~{7h$GGHR;LvbndjD!76hZ8NuZO6Q!LFn)Ks8oUarQh|K0!5P!B zf?}jlbz7~Ew4Lh8wDRDt?LL3o*uY7kT1vQ+OjVlU-Q0`{ftuB^K-s*hGtrY0wg+Pf ze`?h7kIe@)+qIA6WZs&oybGXkF{VSm!>)=bimI9^fY-~8tHngxDFr0TsI3TaIA?jz zz~p(B&3EY9(~O)UCPhd@3SB1jLojwjWX*ejmqVQI1bVooaVXv3Wk{4)HD5dGNoL1F zUO)v;a@cf`sls>Bi(!cRae1w|7>`No+Vc|WcO-h(fT{yJ-&q&TNSEs4E zn&bjrP1e_4QLIvylT!{ih$GsC!iGVOBEEmz^HkMA!|pe)j3}1}w9r(XruScgGAVb( zTjhOU-+ah9>s~FMBLDo!m~rEfPC~oa07c~1GeMaLO=Ziu(yrNBLA2E-&E@3x&bK6j zp_p3HnaaR%^)SNmuK(O0fDcU%*)AfJ9$NvYl>#6XAxFN^RJw;48X4LAFAfaYl5vm! zALW|!pxb@)@dwX65>Rg9_Dfh>V zrIL4k$>9P(D;mE(M{m$Xe7D*$1W1neDgUh(ymd?09=K%m8vKrvVoG^*(DvAWVcbRJ k9!hrj|Aa=Pj`8hEn~IaMI`-#r+=@&yV@so=t1$fk03s#4CIA2c literal 35522 zcmd431yEeiw=N0<2_aap;Dq3sAi*I7_aF&wfx+Da%nXoV!992qEJ$!0T!Op12OT7X z!wk$D`2GK<>fE~Ty<6wpx^;II^z7~}YqzZReXCb@_*-=a{6|!e(9qEEl@w*Q(9kgY z(9qETKEy`l==?k;LnY|$S_*H_N{4B7Q74$z(rVIZXcaMd2y-mdIj)PMzB?KkLFe5c zdXMu@OH`)0t&X0Dwv(-k8o+;sw*2%-2QPj|n(T7p=1sCH- z)PEq?{h829{{QK@fXJ(VUGdNLcjv~ym`{O6XlUVkO0v>AJ|+iCxL-*(As5K?3?UvO zBCNV{Tvzk(j-U0<GU9$QY$sbwU?o8ZJ=c3=$ItF>CpfGO0-K4nUlC zBIJ+1BW2jhMZJ~SwIRXxQoNR~{6CnI)>sXt6>6ur3;CVzU-A}sr2(~{fw;Bohlc&c zLCnFYL(VuoWwJ#DcVY&MdJ|vzHy@W?W-3~_XX(@7i@=4(EMg?cX}uR+VWVl9Ec&vj zgDO~B!85{2O+rfa_Hx5MQ}cZ+7bEJ3lK+kY!0NmEIsTKB@$J8})g2%FJDY8amk`AZ8{a)OkfB;!lj@bE>HhPY?@`j_M(>Zh!FS@6tYss}2V+Vvub5$PiHU95 zt}GMDm?FX^pJDYgGIlY~yw*pxgCec=H!emkBRAZC3Lo4T<~96ND4}^@_%P9W8Lmyi z7D{?||MUAx0Ds3M)^(Ha`ca|vqeMB`FWEts#Btc)UZX^)zst5|xX(_x&(6Ke7QW9m zBWFV%CyT8=W7Hy9*mwO7wX+y221oETU9Vjl+nS}%9pSd7(-ZdXU-E+zB-IB~hQ3QR zs$Hn@Ww>qe{%PkZ$YmFZ3jA^E8Ew;Pus9V=n)2(vm_+5qEZKN1Z@@U&bMHI(JNIia7syDI>o>dpT@yTV zJ$zHT&C7}Ra|jX*pmCS2+o`}AjtM1|>SyTbb5xSNURzTgqHi`nVQrYCPzF_&;Qy|}qFzTGnQFE_*cE#JZ7YN2k>_BKfJa+wUeUj2EsVlBQO*Bwzn} zS+@HSV_Uq6D~rSJtm!e1G*j6P)k@yLj64!nRXA2E0bc9&yt(xZ7i_D|P(s%9s#!n{ zkaJrZbzSA^`Bj^v00ZY10v;9MFj%#h#jvm|HW1z=Q}n^_CJkUBh1ju&&Gzrl&Q(whH-IAyBv9_z-`fx&{f}?>yCrHvpgmm@-%s^c5|3hj_#`69rutbX)InP_DJJu>ln3S=F5F zxVT;$?znNbOR=oGnXiDHz4>$6;$(1sGZ=9cQ}8qLYECNI8ZO@YftrxU!+o7FydjqX zg3I3ZI<>7zEyD3fE7#3zGyQC{Ppc(M#w<68nNe*BCmXnXZGr9Kdcy>-v8QZ}4{>R0 zq0J#1iE`h3xWS8*_L#wEZCsnM%B#!<`htawi(b17*oUnB$yWCQDwBMTaWz_J4ST+! zJS{xgXw52wKQZ5+>bVe6(r8GtsttDhu;4RPz9LosO{*L{rB)blkxH2}0dH?%UBf{? zAyI|*Y!6xYGyo;-PanV%&t#o-Vnw3YC0yNv*tz zUVu0{DDPK(;4xN9-z^+!Vm#YC6Qs`JHbrW9{5I*^W>w~{r<$G|Chq!!;ExG2&5I?L zf65T@@Ur*x_Rnc&@#Nu?-+|xwJpP#b^^_I$0}SOer+cQ*4Zk@(G{SAe6}N{fkOjU# zq@NaX)|9^n?K6Mk#2RbLav2IgtWlFu!ph^s99aV``T#iWkNnKK2TH*QfF4MT`CLl2 zP}_k!&??b$9>srR*jN(Y1+jd_!kb3Wb$*-;0|z=YzA?X^C)07 zfM4Q7NYMCVksFkhO=0S{a%Kv)h*Ej{nU)z(Ni9#mP(I$jHu!bI>r4kh070TRkq>!L zlF_9!$TN?eyq8e4$nGi!tK-$s7jNX@H7h=kJJ57|D5%y{yP#EXQ@HG!f$Ra7AN2W5 z8R4V&bT*7lN%+wdTJT~8EOy-@HKog5D>Vi8WZC`3gqF{=a$C?peLU+!Hw|6AS%d%i66YSuMq_F3_>D!&)LG!<16s={ zo2(}t>zo_SCAR=8dQt*PpIr%CDqqd}ExM1zuC$QTUKdj=ieoOk=M;veCOOeuR;~(mR<5bcnC3sD zmPzfpoI85|C_|1)>~$y^W%{x%@2&YF{#W>VMK7Fj; z-w}FlIrMmQUY4ZBv8mL_x9|(Y5OU@Bk5=H;HGtLt0%GxcaQL@xv()+Wy9l^Tl;SDN z4bku^IC-G9+#yIA<9DpFl3mRb()A|o18s8ZIm(FCN3Dv#aT$mLQ>d32+4uRK4-uYo ze-h``Bku|Egg^Xwg$`Tyqb@2*H=|TI%p?C;G+~jg!-9kr6is)y-L4_pKNgHWjO}|$ zLK=G36wFbF1|UrA8%k>w@U=59%8O9VBi~tkd4^2ap?28*OKXrCzxk$Up8#koh;&us1oMuelu#G z%AQ7mhxoDt2z#cUwl3st);bxDoF_d{3+hrmULsc}df1^)U(+Cjzr;$X?U!iuSsGNU zg@?Bef$@glysq2b?~&Z@c&m5hpmy|9!zW|+;bI?)ir3`wlaeRZA%V1WCQdAzaFeA) zci3DAchVE|hv|Bpn8T?VVi4ET2CaxS8LhMZ4QFuEcrDC#@C@u#cF--GETck(*|G+? zN%5AVY@OeW*DQSUtr+|c@=+{WY}+onN4j~hjMf>ePb)E`JN1M5v6p+4r$73$-ElT) zd*JF5X4BKwk4`oHT*tC#{kRDv+Yw-h_|or@CR+-~Hxa|&JfYnyV2jf1Hz#{?f_-@_-OEgiGH@+GT|bNV27b534t_ScydKxyFIEt%#9)E^~C+V%YPmwIafp zk>N>wk=Nf{OxBP|>E}PsB-W=>7JYweWL4UziN8D0@54G9S*ErV!gNjA4t>@z-C6jUq-|l#I=Jc70lbB`Nev)9KFU zm`JC#Mg+IcF8Z7shQ1|d%?l=SVf8_o^gajrGD<5)N$TNZ2mYRZl)BNf&is7*B%WHe zvzjYgRZ?(mTE_&a8OtSSJs2>lCgz?DTyJ6PjHdR!9Djy4{#JTtQD}x4`>&VM?BO3? z(-VjvuOV^3lQ0%wp;bC z3J0N78}6zD%}wqgi_{<`{WS6OY)5lQiIfq&bV1E`hoSNco@GNVhIG{hGbrvwsJYUF zdqzE#&Bn(}_Ao&DoR=Za#Qdw!9{PQS`u$v%ZN4E>wny=KJEIvShx)N1jWTFa+J4}k zGbpubr4qWo4{Iw@j!RI%OzoQrd1}diL{>aXf>;;O`b{jEw{xxb zhA9W!mR>Uy%Wd{hE+#SWF%GPDH`It9CPvh6Dac&T0++Qp)>gjyEbV(6A@^k#3esyZ z;l#@?6qopLv6S_m9;Lsk983xnsHt6&JO0j~|K$;@TZ>Mw008gBfl62cN|HFQ@e7hmA)qm&O|k0fWqHerX9yG*60-Skm?e=B%@gkF$jwaZXyXL6!!bMCWFB zbfjg~{qT&TQs&F>!+g_zdK>Gnp5q0QsVsDO;qDaMFEAESqe>pJhF|AceWq$P zQyX>hxV5`cDF&eJCja(k{vD9xK;cPRfhA>R-OZLcM~2v3cZkgjaBDDi43{-yGdGN|StQsek3nhiI2x(G*+6qfbO8&IiJoM?i zWLe6v29Qkq$9_+G#DnhkariJXKe9tWheYiR09)^3hJPga9EZ!yu!S51O&Y*|oBH3h zIteoqRvW6{ILwk7JaZZTmI=U+!H}JvYgt#|+YW5*k=VxQQ)MO;gzbwJ`mt6f89c2$ zm~Axi1Q>|F4R+k{fn}|k$Ex*FE;#l?+u~*<7_5D_t#`jI7r4p!ysJb|zTe5(G|M1F zSLd`ekJXP*^FCY@X*i#^Um^s@eVEu!e*}XD*-w|~56@Az^xleFSNM%b)F2hcypS!% z#@dWZH4>h|jjNEp9=oTI-zst9g0CT~(KCDVFLGHX_H1mjr@$jAQYm5Vc4g2TtEIVH z%uB5;Jm1ruv9T@+Q<{Sch4aW_CyYYsMa-QIJU|bvHh_IqC3GZ|H(mAk3S5E@hmTbA zz~L;jXU>1iSr%VMki4g$xCOhE?tuRIT%@H-mkg;Ne$Fomn&w8NU(~0kiH$;tfA5`D z-o(7CyYXb7K<3=grvRa!z%gHOS1U5w)1=9~RVJi-L{w4#$Y#`GWm#KB^J z?LiUDYP#cBb!>cn{vzWZ4`Yn}VACFM{lSaEaIqJw;hD!$?eLu?I4rlO-a(Nm|GGfl zbJe9=__SL3mtgt7SbY5%lRS_=PrQQ?*58c!FL};Dc;i1HBOmHqttqW4!@Dp`t^{D6 z_0%AkjL zsT5XOkD}58ANJa=2aD<9FSsC5TU}E(U#KMI)~5da(9h)F;d?%3z2R*Lxb7-@{C=q( zm|bVg(B!%?jYFWL`-sE}8NrsNh7RuB%W?i+b zJvc)RgE5Y2=_e14J`6K05Kg?U9T+pWy7!w5U%Q3C$A(wRRyO;GEtqVn*1=k7 z(YZc9+do87a3Rd8cYPp$dDayrff)8l+b{?4!RNzkS$LF*^wbeDKR zm4glYhKrYvZ+zd|HeHr1A-USa6=fD`<+?eaPnk=C7F&_GaGrD{)i7p+R+*L@LWV1@ zP-*B5!&R@S^1DyiePvwgQ){Qw<{Ib)t;gPRw<9UDf2 zo=Md+7cjWbmrPD%Q|+xiaCpv4kNCN&4n7b3mUWR>eAy0?DIc)Cb}OY8y!uhWo2o$f z@i!nL5B4KBWTc^~Nu2Dh4kjyOS5dI-?1O#!{lUS}gBV^0KwWsRR^F z&fgd5r>h?nOM0^73atxAeu6=HxjV&#wx~{|Q-i&e0B8^f6SLh{F3SA#>X$b9>^*U1cx?o~=x0X9 z?C{tMq~vY9#g|&S_ECDfE**O_*FAV3dp)EjfoO~?%`PsN!-Lw5S7J$vwu3Kw73`Ar zS@dCP$;L$f!RSv}Up3^CPztBQ@&=V+ta?s2jp~HEJ!ssa9TvlWNSp}Cgz?|o$&**4 zG%AIw9ONs{F`GTk>-La;EuMl$y7UazHokD<3L*Wz7Ehb6bJEDW4fYe1Y&1U;8+x&o zqoI@s+lGZww|-9KX)1CUsOHhO#bRcPB&_gn{hV}joI+7La^BT2WiJ)clb9d>D1OFS z5i1Zy?T5~Ih2ij0jRcKJ#)(K$=BM9vQ%c<0%WDeus;s}WR-mQ6&UozP`ODyQ?0ydV|-PI#w@UvJBD)(PUC9q`|(s?vXc@y zeX?PcYR_&z$}qR*rwfd|f^|yz)rSgh%I-ek){Hd=EDm`~?b;)AO1-~b?T9w5Jqt{rG#&PIWsg+I8{hHIkM8-o?5TX1$DSR{J@bsheFSnQ3tt)vyr9b`oVN@6X`tTUPc#)(K*^D#F^O6R48^7ll5^slPCy00?VVS zzT%Jvzy~lFMr0P^iE^vd2VAQ5`9tzr+#L;X9KTyorDy5!h)XKLjg?Ufgyp&F+kw#G zoNxT!r@asdh3DQMX9K?f?ifdMMFgad<8o&Ez-lgxv$^=@{^Y7q501D!M(0C+6)1@A z*1}Bg+1{^02io_XA)J$BIxuzA+%U)voJH|&@&k!Oh_Z2LaaQ!58^bj5rlB_c`cS_r zLB}FzutI>$UdUg6vuV_85V3RJv*Niif&?kdl!b?nlz1F85?(pFd8y}qC!%L&{>{~> z`e866&OCoIu&pM)0&T!Tgo%vX@PHMUa@#r76XXS{u>G56ne|!jb-zV+0tNuXGOJ!e zBsjZU2(kCwYu388a-Smd=1IdrR{t-(7xX9I;k?;@L*?)_USjq3o?8S-S)wcjmAx+| zTl$ASBQ+#cVQjo6eG%#oPwsx+%JrP%Ru9ps3RR6(VNWDl_!|MJ-d3Y*V9wUL;je* zTkBV!3eidnP;S#23dNK**e0jH+UJ|Xm=Xl3{_Pog`9aKqo(l@xNXj$5NQeMCT=$e%=IlX9C_Yb#0#O}9$`ED)a875=bXe+y*9z((v;9V-?Z9J zcKzeo>Otp;>$Ax2J*vXIT3dZ9?G9w-3Ji>Uo80Nj4gDJ^G4A8oI@Ag&R&8+*?0Rh7 zq*SCd{Mq&rZ0&nJ*Do&Y{TJypVJ*t5ug1U4n4Wy1KMql#nvM%SFlJU{qTEhl(>ri- zjN@iu+w@y5cX;xMJd}txcq275AUT)Pm1GXk>Hk|g(blp<&DTLH)AYGoQ2a?X*n(k} zZUH;r`l=R4L$Y3>HN7g$*E_4FJBaUw=vc!RC*ZE6+245gUDbOLFeDDaxN|csSZB$ z`_AM!H3ApTQv754*-n@%T?W6GVs1=uBfs2Mo?6TR8?H>po@E*~x_s^5jzr*D->uW@PbQC|U~A{Vy0f zELAHz^LUvbXmUIU33q?Ejg!Ak(*_snp^eky^ZHP>G(G_;UmLKQDo9OdNeVGX&!uN0 z$@$x?%1MYBxk$QgZD#*z@WslBSIv+?bU7x&+(s_Ut1GiU+_3`2G=+dEJuJlyQL_9z z;hM!FU$r?#tgG+eeae-6_9EIsYftD<5YFQN))QUOetHnttJQQV!}BK_tp+G4{VJH3 zp@pGi{&maS?#Da(-3c%EKuafwc%L7Ss>xiqn#Qh)TYjmZi!rcL7JMCoO(BKIFP0Ig zJ#-N^ZEF^-j^z1T%hmjtPhtTKUCFtlF%pk!BXLaisc(Gto(K)rKC{g}1}vCRcl|{w z=6@m)VO2+#Ix4YGA}!RAgb|vaU^s7c>od_)UEbeETKiz$UEy+ZCqzyuWrjli)d*4w zf4j~Wab?!ImM!)0CvF({X1{2sW7ja9xn>vlE2<;5;a9n%7PncK0xuAU;)W!GpmBUk0Wf?6f`6S~fv&7d`Jg&Fx)vL%XcU*MmFvkyY z1RAC4NUb|F2UkJ4dornzGFi8}4;P3vDih^d9*<2{7&LmH=po~ zt3oXu8ji^7{vO*DeUwKD8Yyr={37z(yfxv2^(^e<_G%-JT%A7WG5Ig1D0!=W-GBe$ zg&@UlS440o$!@pXqk_ICLF;~(X*r1fOi~xs`1(wOGdt(hqCw!TRvW$@h`U_C1m(l{ z$s~y015i?aO5S96_MP8<*G1-W$_rbCxuA_)Ghvcsl`G74;nWY6uet0uk={BV8V8L+ z021Z}V*7ZZZ5ODiGf$0z+~p`X`7h+Com{@_FJY!{loYyQ`A!p=>=JKKPZYQQ10{@!e&~BxF)81mASBn; zk%iju@OlX82E=f!97wbnCCzZ2@2&ianjJRDlhk|^!xHn8lc14FU?x$3Ti=Quh?!E3LBB%O1o#5MTGFYOf0O-8Y zX||deuxqPdurvf3I~Ces&nxxU0ae*Q;wa47niaC&(;z9RQdfR(kbVLt_p0`v0QDR! zA{$rYF^3?5?twSiZrX?HL#>-3+YtfD$GFpS3%g#?tKzYimw((YKBc)oTCkm{lE{!M zRjNmSEBhq|HOllYy=>2dN*>pAPO`f9C8d3UKlz~Nd5Mv``M6TbGWcr`9eIa~)P@Xu z$kHF{iDRtcrce!^3a!3S(&<}xer13L_u_R<*V|93{LYD5-+CkqRi*MMpV4`aR14s< z<^>iDSekW4uYPq$yLfhaDYYryMyLyFI|lc6N?p?bVplG=xwwodLka<-8C=xul7dd! z(1m#1wu3VbP_sWHUM|ZI7xYr{JDnRUD=g?c3rLa~B~)|6HwYn5=~x)&t^_9p-*FI< ztU1T0{dvJTh?~MHtf?_L!FsSI5wyH9f`}@9d7jN8m)@KBZnPm7d_t!tq*C{D1beLy94?*02Kjxkgwk8u}KtXdhCh}oid*y37`=if*# zvRo6Px>Y|iip%qQ3sww@c&g2kL3cmP-6k#6*!I=7?++2fMC9UJfez3C5*9W|xBX#0 zufP$mmCv9rtK9u_;<{dRV_8BB;uQzMCA19g^imN~8cFxk6xhGKSqe|H{rC{K{nX+j z+cb|-gg9=`g=dW;DM@`4N4LSpITIh}BvuYvw{u^bX>JRBVr+4gc^F9zl*bQ{v{_5a#4YhT&A`oVtq+#!4qI z@HGgk|6oX;{s|?Acy3n`48Oar<U*@%qs9JGNfbG4%aWQ@$a$-d3XpO09$z(q z6|Z}TZK+H%AM0^CG2ShD%otI8gLi(7+2X-f#viC{OSIJ=o^N$_ zIntMe!X6l4+=_tf+nR?xX(fZK!5_=d+_B1Z3K!p?p3OuEvPx`=i!4i`)5F12m4OV) z7?&L_z00m2e+j0mthxNV5mg#<=UXVTI-4Ic$`0iw76^67cGJf}0Z~utY^8Bu<#1H| z4>56^0fS904bwhC)%7RKNdRAH?iFIt+3{T+0pCbdK_UibzmjKPp89>TnIe8%U`@}~ zb`k2r!Q-Hm1QlVosfwlO(nZDu|LJy+Uilzjr(2{0lpX6)yc|kSyPa|O7_YMi5Z;r; zRRu3WZ8bNwt@b;%1E5m1*TX&m6j2bw73M$gaIWZ>9^xx9#Gx&_f!$GIXefZ~o8S+v zcLl!;6(@2U_n;vLbv9I&>+Jsu6{50-lCRYg5g9C%!VEnb{+=1uz4kmI`pu_yX~t}r zJhDR9PbZ%>UohSo&xe1)->kF%J(Cll?2cj!n^t3S}!SCT4>y z`)G$c#@@Sm3Ql+3jRZHmy8u7-r+h=z@tPdyZY=+NSgsjc*H^x^(@W!Bt$$+Huw-mi zpQY#8qdfX|UoMN$;HvRRS?KXp)SIPx)-Da9LnVtJ)EBurJKYj-ERkT4XV*%2n4;_3 ze{O&B|C&O{wca)qw>XjR5xCk?-8o8s#Qri2n?%jP+y$!1%6>_!x&6W8H&d)zb{UqJ zn3BS(Ucdvv``;Ct_+O1}6oBWyK^WXsg|d#mzJ9e2Z2i)hG$|!Tq1pHB%ZgGU9cNY-donKkMY)}IYJ zBO<~=hjEgKrOW(F3ppm;`}V42+cZ0l)-RJUmbwxLrF6hwYG*~Sge%@RckUz3@NXKi zvulH<3U#+vfRw;LHTZtVXBQhHS}9B3PrVG2Y`>O?&TUm}@GYB?5ZUZ(rN9 zvaDw6PZp!reOnP#tD1boo8WlSv+%Mv|J{k>4|mq#@Rd9xa~pxiC_(yZA}DK@9xsv#2(g)6wNIp{laTVaic{D&**oFHYtH zo9i2k<#e>((LAXFQdy##C)}ox{mtjP*@;;(C4ky%Z4AqNh^M8L5Fv1SbEMO4JE<&k z`Esb&W(r6lJMbR-B-5ocdr^2R)$iu7&G90$lYU5>!y)uYPGiZZD1A!-*dX8Ors`+3G2FROaFJpiG@igk#Pcne;D6(+6;tk0Z2U zM8ry}4mjuEvI(_Wv<+?C)!$0{a$qT9^*ggFhrrP=uZNIr;W;XTD8k2qFPa%{(-Xg% zbYSKawjpS-c6_=$AmE=2`liY-vJwD%e_`tD?{U=B50_gVcBOkeJ*U?B(#QPDfFd9w z@yUHPeQDe3BC}tzzlK;^;)Mr{26YfW@N0OT^zGv7jaZ{OCdj$8G)<0aRLrGpX$cBd zKceX-8|?-zM}g_f$ta6- zf`fS;gBGi1KMe-e7e4Txw@J0ZkM|b8tWH(iwfr&+;r3p=H6HH~C&7RbPCFI}tZcH< z?r&K%d-!`#zW&J*9;Nje zs#YFgu0N||wxyh_CBs}--Qcae*nuzBgB@lwOuXm3y*+^&^dn55a17d1|CL#7c)fX| ze(cg2|N0y%poYPli#^H=`H{ZT@%FZb)_5fr--@o&da4GPerc>6%J8-T5fm^hC27R| z^RWI4DfN9baU}JrU}act_0lB&*t2tW9SQ!lnD?=@ip$mUZ88y09Z^qQq*J|-s8s9- z1@j}s!wP`r`kF=KufZTLc+0j%sg6Y^u9Qpf`IFW0G9I|mL(BA=jW=~$x7l45a>}Tv z7F0N_{5Qn_SjR8x-!flJpVn)}P+3s}F*8mm$|6_Du=5^$U7He|A!Vj)aiX2C58$6r zb2s*~Ke*lm!)MR%YerIY`L<0VgTIunUCjaH2#IRvh4Cqg?Vxd-+vpNZM#~;3MCd(g zCgiELM92)Mq+(L_(^e)-%xj2KisDP{J4=8iw^WQ3n}|j9Hd;8pz|R?h7Q4?P{bPwi zo)Z0R29iv|^z18B`tAx^@2jcY(sV9KxS2fd!T{E}_42u%uhf;fnGk-wTK@0P2KLk= zzK&w?E?og;iw0lJ=0hn;T!fxb88nvDGjOHwg(WYr)@jA@ikUc6{pzd@6!qw|51DIu z!QC@^ksu8yZR&K+{A59L>oZ@kze%Bm;!+V|iqftLBl^`$6SZcC%!CU^BzZ#yd;fR9}g<;bnebJJHO@-zq06cZ~iPo};c(Eq_O7gL`U zsG?h-a4H%|q%6gao+=$cLOuQPdxt!=9UWC$ZKud>x73 z%^xoI-(W$%f_M)p(QCwgn7o@kwMW4os^_cE{CWXE;zBS002o{EGEA4|;^mF;J=-H| zP4H(=xQ|5t&t@5`eaM=lhA6K4&Hqa5y$-Z|fKE|r@{MdR`@MDNd6-W^97lTBm9>6R zI7vKjaMWqNH1-nz7^6T8jq7C8>c6k$nhv)JLnOj&5@m22&3r=5>mWUvpKSL9f!*n> zrr;Iso-Im27|ciYQKx>X6#kJ+$tPFUiH#;DCrEeg$*g^TBa8#}g=zQ5Xgrp`AKQ(mg7N@fP=`@Jt>PGyTMSZf5>R}M8Ryo-> zch;1NH{0oY{LIh84tkAqSmWn07mm|7lZpVTfAp}K@f!0ixbQqm-OfOVLjq=md=;H9 z{z%U9Q8Zr#LP;KKWHmB10Cm7ZQhFxETMM%8rV9-jfpBl7G6mV({QLSbiJoh%!n3?< za%GNqWyUuH?|-?Yzhowwj$^*{AJB!7vXlG3Ujbn?(AMe?zo3LoRt9;S{^d^Ed7BM!Wezag z4xcf`^WHsTy{Z0#W1fL&LoQC_{&+($o)6skEH>Q=A%mBL`#jpKz2ZCIQU8mlgq6em zrQ*-#>#vG`PUw3#u4!*`du|-R-2Kr$7G~iqpP~lp=l}7 zS+9y>Zp!*Zear?3I-OLc9){dj%&2<94OFvJ6rbILRf-+9**I077mo>D*9t@HZ@&kR zRZeBgmMy!!KSinJdUM98s5{P57`GsQR!qvk3^4Ar%{~2l`4?p|zo?5<`iV2S#n2p$ z)+YJI|4_8Zy90hj48^LWe*HuI#;YnqcIz9kSyE)B#LYeMf~Tx@s=$qEk6f2?Pxjscqp9XHh!0nupg-5k{ovE!}8@n-nF4E#G!3SoNU`Tq)B?n#OR6<$n z(RsM-*H^a2Q?R;Vz~_Yyp9O+xGP<0-+Q3~Ay4uInNrjl7E&2qw`1?4W!B6jC11%9h zcg%~rp05kr)TId{B1WtemCo;r+U?^$+)11prq5s*s0d`-Ihb!zJ005R%z?}hmOb=& zuY0!0FdUg(30Nn8Mj3R9}rojazr|YQD;!7CAlz9GI=a(y8?)~*>NoAD z8!s${alI4>cQXkv=Ry+TUQvgcDUX6uLpCJNCp#x7Cng079R*vnwGWdWdxC98D9cR+ zF3v6%;d`^SC|#)GJIB>Y_|{NxW%?lEfIj=v4ehrE$JL(p^x_%0JEZArs@Kx|3bPDz z0kbzH)5k@;x(Glva1XI~Qh&LxYv9y7VlOCQr_p0dB9D}FzuxuzI9W{LXO;CeYbm&+ z`r+~|h=8)q^MwX9$%K@3v=cbo%L6FGl5Ai&D*#wonmSW^N)!K%`Dx8T!E=&ysB2#} zcS|l1mSVc}>hH!k;6n1dpbzxY7j5<^{0_j2jT>kI7_g$dUOs2rMZNIp-3!^ZKr9J^ z=AP}U>WMVU7)$q`1Tve z7jTL7;kjKv@WXxx?h9(eZMoL;6cYj=IjsU!ct2yF;+@qe#Y|Pgcx`9QU(?;L_F<7r zf%brw-!zKFSfCfc@Cy(!spex!)+89CM1db2Lc2VK^{E72*{1>FDgr;4lOS7o!%5Jr zu(F;1aq}Q%G0I;uXqQqqYc*(9-FoRDKV8(>R{T}4h0CF_J0Et7176_sg*HU>pt%%{ zTin2_K}ztKg%psk#Gh_cK3h<=`AG_D`OmC#kW(ub{)#jzb`Yy^3XreQs=omo$=;v7 z>XGAIOd>+&%f@Mq{|opK$8p$Lr_xi}RsO0^N=lN8pm27)E=L8e>`fKxBGixbP`w3JzmmpbiW7CxxoIhKRgDs= z^x4c^=K9O;nSmdffgNa-8YfS%b|Ue%mt)Jna3 zk*mHOPrLSq^3L*wAKFe?lrc&K*q!m{Cj60Cde}=SV^Vhdxi*x7%X=W}^!NH{!wxGz zKtEXupBY2akREDAWikPF?J}5|d!fA~I#-M0;{C#siH^ooj(%aDFAq?v9JN}mr8zY^ zM@mXw&3{oXrJ5G!;3jitXbSqHwdF)pT=pM$lO~Ljcjq3skw=SgEIL}frMdq9W6 z3kUqB;SIIU8_BReT5CD`X&@c`MUW$k#uo3~c^6`gfbr?ko|R4*QZg<=D5h%D-_--L zb)uac86v?>FF9HTwxD3FqmI;!RJFYrN>(D(N`hpI0csRyKNXz=2fYZCXJ0fL?~x^oUd+qB#PZO zs@i{Dqw$_!a}xjB;)hbY%^LYUHwhnE>Mcz0s5A~2xOoWm)|aV+3=BJbmS)enTbX%GiV2E1Ln9R5-E~D&^|N7AXp(H#N7{MjVW-k)5i`NL z*cQq~$Ual!-9Bzdt;#bgdRPRz0g5%WP`;fOxi(wMzchXn=*Yvy`4r_k(e*N;)z`;R z;xeq^xi%@tT(Y-lx0XDf^8$%KMnT2NoDcLJ^h_wxDqb&I_xS#9%i?igv>trG(|BP0 zU5-iU9^;xb&|Sx4;^&=sQ`Z5lw4420W>NvNOx|}7`~A#M`3gf2V#&|VZwGkVLXlk1ef70R z=%VJrs1;>IjaNQzQg9W^_+PD5j*T=|%%9=sVT05hSrVUq?iC&}&46@&^+aA2X{>v* zLl#HLOF35@SxHp&vCevKUluy~owSRh^wVsT$K{+Q9DRbDr-vx6=x(?PxMF@bimz)M z4O*Dyu5|}i4p@qF$8NAxm;0l+n}T_PpQr{HpR2LU={30Y98jnz(Td&YNIw-}s9H|^{g zn5OR}xxvEU4ZhrEq38{MNMs6v$_S|)ja@)QSNwRWNMn}vP@F=Jb@4B&5Uo(PrormW zO#Bs%myZyIFy9a$A=?c)u*o7}=PFk1NaiUDJ@lw@n3S)Imf|s3OYW)HU0zOOw_1v{ zHhii<%L^^$anGzSO>+?I3EKc4{uVg|dM>0#s5kDfO5$w+C@rD3yB$OV2^FPE2Q`Y? zWB;kD2I6W*c7^JFMZFv9e1vHfIL(4TqD z|8d3pCb=9VSKTaXLHWAw-6HWTzdvybI!>B+kK!X_pE5x$?tJ#P!W?x(cR&8ytMmV> z9`OI_egAmQ_r|J5B&l1KMfQH?tn0Ghh2$bQHhZ7PMBdkoqOo@D;_G2a`2J1{{4in# zAmp(#x)Y~B7mk`%K-KPj@hgW}qJ#R4XjtQZ|G+>FD&iW|jZjB!X(0?4$YBE>^38&ZBm#RQe* z>UzWaA?}xlQ}T!J?p29TP_rv{!u)^p(*M2X@!#~TP*JjEP3aPTUI+>n)J6cMb3$b6 zGd0uuO+6dBjQG&>6@qBfsmJI;Gn_|XR>CKjH#B%7Lb6U8cPe`5BBI3(>wRo)Mj`rN z_#R-7;2&dwoO;IRf7TSQnQ+8r!D zvl$(e_>p?QH9*$=HS)V%gM}Q;M8xb?cbb5zZ8fKXGY7RP!S8!TPvp&?&DYQP5jXw4 zP63a$_a>QC4ARa{Uad_jCzoY4H*xUe^^i@kNb9evt+l(l)eK`<^#COsIV_&a33&Xu z(Oh|ctsr!>7wuyMx|_MNH7lKpDBQk(1%p`iqGX!L)u2uL$w>|;SW=WOjsBjtnT={L zk)os~jiqNZg`Grfe23h*IklKjn;~$#MbVI_c!?B}NF9$&-s1r_&O2hl_$f&fmHhk_ z$Va)k_|Jw9a`Jf;jEuo@-w?gI{5f)XZiM&yERa6a^(C%DeI#Rz_1)E+U{@t^0si|p zfAK=qU#`oz(20al*?eT>KTy?{4?(r*K>6=oByuk)H&p}wUFOD-Vxoh8|728mPOuC- z=5;Q--mybH536>Fj-sLT6?yY@-A+d_ee_Bac5UiS*5Ae}SnOc5)P~UR#&7>Qn(I!( zM{cSKf2xL*?8I78BSsu!lL^%xUq&@M55tyCn|VMp^+Uk(q04vgXg=5oV6l=HwOfIY zBIr1^^(aehs!y_9RZQNz?rJ!2EWQ{%?SquPhbg)38T^Ry`=$G+EeE<~I2yg@@ldPe zE@D=c*eQ{pnm2UcMNy72gWg@|BYakDP~ok=j~*R;8fl4KzUtXhUZOx=XWO)Tap#C> z9A=#fM<^bU0%9Fn*LP=hjBgss?2{#aM$_gPMNc3i2-P(VDN;j?>O>OehfN>-G|VGN zp?cp+cOeCORihQ4=*Za#Lv7hmJlV*{eX>7)Lg8dIb7Y#LM`#cAxg47rpD>8xFLR$G z?|iWZFn;BDw+MT+a&l#Zo}{wxz1>U8RS+z;XiL1RL~DqzY;K$BwwfkkuQnTYTggvL zUl{p~;6X!;=M9s>evLLlxyXH>>EZ`!C5~>Py_gl~6l$#tfo+3Zb5JO9O>kb-%^2Ch z%L4bFeFjP@(G5+8aoQ>#m0tgzqT1-@43U)*X?7OKVHBo$;s2rfwra@f@;`5RU}3N& za)pCa@9O6@FVe8LrO)$K1-0a~TGz-$wc7N;3pTn~i&d+RF@g?kgxKnn>mAJ+(s`EI z+qF6!EP_z628?u-Nl6B$Vok-+P`!)TDli4G)-_^*r8a7&z|_YyDV=T(l+SEGRDBnE zw3Gb*^!C;t&cXxM(f=V|-E3M=JLkS2-4&5-MLr6=< z5Z@ku@B5y!)_2zV{yFQ+AFvkrJbU)D@4fGRU)Nq7j6|2;i@gTG^L3RNV*UI9!h0z< z!=RE262GdCmH@c3ei;vSQDPGCT0XKExfn14q6d4@EZ3#o{Wt7)J*AxrV-5u*+ppXl z%F}pkAo6tbL?v{|dP%}i!5y!;L5sme=YtjIC-||qc6MnZWMjph1NqmAuJW23g=ese zFilmtl(0SlE5cOto!d_TTS7Z$@F1dS zkup^={yK*?_$tSIrKGBaP_s%(t@T=(bvIqQY-^CSiI~MemjC6oBdUYuLD~4%ftYte z+XpP}|C=1)r}CYakJ!F53+S@2!UE*+cSW@sVTRiRhi+n;VnW=_LrO!ugVa|q#0t!z z0Qq}+=x{AwMfOvHD?4aieM+@`qRNBxqNpO+;(P0HQ9(}GW$>*lp!!J3&Ym?~;1e^l zCxlm;<5gUJPla($E?01jH8irKIr*u@T0qtYl!gT;wl~hiyev0@BK=+ZiRZt$XYQR5 z2VO$X?^V$ucC;;gO7AWIy*k}l3RfHe(aUA1rF!9bXeZ-x=;=4rZfp3|4RUijfB8J* zNjRZ=a$l(-3bJMO@~5n^;@za}@3D*on8^>}FWGu6^wQRVJf+}{hxF1ckW5g#n3|0J zoo;r++Pta2RXCuKtP$00?p(l_K83D1ZHCzx>SW$OdhWSgBXs#YV!x@3K5ZYmW#l*G zQtp(N%|OSgIJ2_7t5ex^Ot=Nj+d@6AtrS5pgT5qku^iYWgT~oLj8Xz=#cNFiYSsq_ z46b$zijF=ODLnjZru%e9^k$mGfX{oV7~#0++2M~FkK0X4O*h(5i^~nkwin!6r1g5W z&}Md?J~YqUvlcq#wy1P9Y^KARXwi!5O;OnL{oTHR)q4q*M7sbChjb5IYBtAs=0tcc zQhFEM<|uw-oOgdBBVU&zAvQS$Rr$N!V(axvt0oXLbZTT;TA45w!sJzMN*ttR@ff`|1hpZ@jvc{6c2iLjn!Nn*pT1=v`)hHDn!=PE5PU!=oO3{EKmX- z7m@E`4!;qq-45qcPaytC9QUEXFjE?Pa=Sa=G9=nMR^Zf1GqMW*5M=1 zgS0mX-PUO*B?1Ol^p%F?E0v?U$LN7`;Aav+ zHNkBrc%?me1$)S?)j&tcgRM=Uj?kk&7F7V7=>)q@cqS8`bH2thm{rk(^FV)8j zJtlZ|{fU3NK)APic-NVx9IDhl%)`r_1^OxU1qPC}-8ZHuv0xuaQuOCcYTTgYTA~*RTp#kmR$KMV^*Mg1xNr-dsJ`PLY<1X~UNFyL0CXVisi40Y?r( zoR==9LT^>lPP4ZZJM8N8?4}mad^YdJ%)g>b$qKROLmmu>&;%~=Ny-y6-OhLwG4TrF zv(V*Y#<%C-|B=JyT6vN4dzGO9N3Uz-?v(f*6!%g@a@nh->G#e``p%Si>Zb79go4Wc zJ8%;pb9U~n9DkdOU>b@Bn_lc`9?wJvy{Gx>UY@+0%j21H%f>gQE1}dTD*cy~J(J&F8!(O0)9bZXlTh^b zW0**Ow<#cpaG#TEpdfDlhJ?gwELE#uMK^)QLoTZ`8`Zi$iJ&H%s{fl z!5c1U)d)@b{ypfN!fRnoBIVBM)=C0Vrc+7unwS&v@y1fXDO0x=&g>4W_29%c{uti( zo#?sF;+4>q*FmV#QArUtJr(LqvTuBqew$P7X$8hUDFxWoz2?e%S=z2M#coPi}I?BN)g=@B;CPyqEw7IbP-Cc4--m3 z!6(m;?woHIc3FwEt(P`mONYVx_Kfv0fuhj;caFCexa-f~^W152d5WNTxgJw;vzovC zVZO3X`n!haaE!rd;?;ux`riKcvQo{b?0M2M;r5ZX3E#WV;|?QpCi*qek^-Li5Q3)s zgDBJZaZK7z_Xfx07nKvq3;N2p!PBLCrX^MOet7Sa0awjS*of46w2`0`uYb^MxtT>t z6)rs|r;p&U(_|Wm^>_Sr_Y={e7eM|s3tX6AV+U4TPfY$yb$e8H&n2cNBNviQliBb# zE~A7-j}O8^!OU}>yEbrl=2Kj$b(;J%3xS3otim7ChcUx^?ugsQG-E&6E&n;u?F$he zDiyc)(ccfiE%0d3{@#oc#(I7tuOzd7QcAEAS}IXb+jGF|^wply&>m&_r5Z>Zz7m`g=>p4E}x17X1aXIKj3!9Hm z-ysxWx>7gr+x>6~nr>vSq3@^;H|U}ah?L+SwAP_VMo4sTKZ;I1T20opou?spJoJ@J zA;)JmFF9sy`B0Cfa$;-O!NLy@6(yWon1~3#z&L8`+j%4`NM=-%TRduIC1s|j|FI+3Y68i$$G(dP7FE=%JV)CJ#4%NpXga= z4&6*|86jpCdR)q!M2X@Dny$#ogI2gyYBKLy<>XCGp~~W2c29LEC^HPz=z2?G$<|P< zS`rZ8_YrQB*^k1@TAH+iXz)HPt&ZDPWK31VRavs9F?wuIlX^Za2(sKfG(a+es+Dv_ zNo5QvDRvk9%GY&l;lv(2cdd*ld@6nj#e;Iz4*cPN5Zk;@I8}5^7g}pyK+af?{1Fda zC6X=P^B&VG zH=R&JK*61Rp-}ynUk#zKc2DormxH{G1Fz!UX~BD-RJGb3?G*> z0#=F`CtR;{Q;8G`m_+I^Ks4x|9E|3rHpwdFy(zfokE89E(=fi^QWA^& zC8ob-hVmYG+LUCiEtpD(I^Ed>)5%)8b)r=k|M)7g6!?*OUI`8%A9n)8LV&%ZuV6fs zL~xkoL#%N{(3FPE(WXub&*qk8EAqmMp|Q3TSKIgx@;;@<56qb5E27LioPHl{1=uYK zEltnv320@nh#m#9L#^f|)L#5F`Hihh_gKj-nN6*K?T4Ll@ILEK*-9v$rA1w;5n94b1q-*qlXv_!ufOL z6`%J90VzlR&=<_SB-P68sq#%^VZreu-9Wka=Es=ZMGWJE7BLRK<-5fGM(XhIj`l@Z zolMt%!}VC>FUboB;h#g&H7+zeGTQyd+3+77jmo*1J!(`J^m~V$v*S=q7sxK74=IyHy{&kd@SN~f^v|j+9 z8OQtiVpWzja`M^qklCK^L|G)Oi~|Bp(JruccQPGj&P_dcYNupQ=e>+B%WY_m8A?d- z6u2MPF5TBun`|Iz+=bY(T`%K#{7O0;`H?Xpr>97Jt*(P#Kr{DZH`Rv!ZnT8lNzlAo zXf4g$b{jbaO7_9j!Fz$g7Yb1QQ2ilBG2@+jv!2n3)w7J-mIGjU&uC-sJ&K6Ti}{-?`26Pn;?AASA0T$ zs(;D-AvkWC-){rS+K|8T{9fYQLWl~-z}HWGNxQh32Sxe8z$}_Bz*OWMw;mic^n6Zhacz5vE4$Nd9 z=zgYlh|4_MqR%AiRnuMz+1KQuwPe2^Qo0#dQR;E*SQ_aOh=yr&h;d(1X=3}|)^^S; z8*g99*r~*ewJ`Zp?IhnO!R86&I{`8dcDV5jXVI{vjO#PEwf;Xq2H~0oB_E}Xd%HW= z;5LEB3_<>fdi@R;XrBn6LVrG7{RhmN@OO~dip((8T=HdCGrD-^R(a2@W+p>(jAr`Bc)%3XiSH5gn_n z2hlV_gUu)L1$iwB`CmrtHN4Z;A`D00#eb2Gkf~b?^sDKnPtGVFYiO`p`o@0R78kd) z`M5VN-SX>}g16&ct#dik_vpGd1ONTbU9laGlS96OdtzUbQaEkZ@)UhKBxLnd4=*w6 zFee}}I3b)ulP-s@YD9{xX@#%WxwNw#0XF|D$ffPsrvm!9(f}YS7!47VI_XhIC0#aC z$*=2T^^QJnzKPr&3CE|Iv*Wd&u$YyJrQcEMBG(5bkZIeej8@g@MgH3#npIpure4M> z+s9I*ei(hZ^h64Ck3I7IE4j;KCTI6zB8^tK@lt3|=Mcdeo6W>YFW&i&oF4#Nl^$Lp zC_6IVryRW67mCY$&JO`w-%8n_el}_&P(%H_Kc<5GINz)=RSAH z7%6U}@9Bd;*F@FD%E7_GQNfOyv5*cwGc1JE&)_#a@5^a*(%(}hhXe3@t29 zXeEFZ@?OOm&ojk}C3ust2D2_PzF6}pY1k-l7&&{^-M#ngjaC=o$FBFcLSnwtxywtg zZFkd4y=K3fCdCn`UDEyxbh0)iK*+jygX3&a5o>4A8@0s^- zor!yr>{>kNF14i=ja$>5Mb<;+srcN^hEfH@NJ_kzrWbb?{|&F;KKv(ct)AWvG=d z`vcsWkfzy6^6t@2O4W6`4{z^yaA1k?V*41s*V#I$9DnWFbB}CJ!{vqs*72C;@elcK z4vB-ziSL$}sXf7>dV{{eAF#-7(bb9@Ou~-#Gcc7Mug^vf5AHV3u`3s*1qE(lf0lAq z_$!x^%9!k8V$<=BP{IR(BvRGZZ9b_!Gq4a#KSHZGrc&Zz!RKf&h)wbw(a{K&*fa*i zF?-vMwPJVW5lhvj)d4OSkj<`>G>yk&tO=rlJ*aisR^&Zlq|c_lLuKjTOP$3{QyO75 zRQLDB@+zBAse^;on=uQjcE>%Jp$20}x38hccJ}`Gqk>*S%Bw*PTYwF*Ary7)ur=n3 zEbHSlxV~r<3pIx1&UE{>JAAQ=YAYq<;Y~*icCD{FL0xFZ9xdh7GWZkIkEuaMdfvNh zq^x1zT8I;;H;F~-)B|oj3zBzD94YeJci{)A88*7?rFTxY{v==o%03EV*zL}lsl4r2 zWqZD}^Np4-fmu!@J387nfsax9E|o>R>8q4Fk<5NW{~h4-^)&ax(Zn$=!MQtQ3vGSa zq79s(&jPim+PJq^M5Qa0hV6T>dAy&y!AZ#FU3NO zyR8OI@1N>!4!*ZjahJc{iYmUeq?l`lxqB4&JyRfFcRDGFvu=GZW{K8(bg|G4b;(G% z;;$qM7z-o0>|R(tQWt!bnc|`0#RjvGN=WJTXqPEcD2N63Ix(gm&TA5tucfIQmw5XC z$SQR;%Qd)P>%e$u&+^b%3=zj+QNW_5&-KG~P46w*Qb}+%fjjccN>e7_bdLRECO&I! zAZWhAZy}n=X4JFaU+e1>kO?cS!(A)OQ7vv! z{o@)vE!5{={Y?hd+NP!LJy05~(31~1s>~3qFwfMQUN*ZI!M)C1d~{Tw&^)9CNsq=^ zTB=R!*+tOU*lvTHo7bVdaGBHS*NJk;T)l~ma+%|eKNntN%>s#XKl^<-6HT@tf?qkG z4YR`A1^ISn@r_{p&%rHhzT+n0nD^q5x|4hy)qxWWW~XqJvO)*~WrA&R z>>b2(=KspH5Fzftg(*X|`Xnz!Y(i}&O;#D^GG%k^kvRd&J2F00s-N$KR5|qr50*bn1MEM9`DTcoxaK-N4(-`sr%BWyx=Kt(9=9y-}3OOWd83Tn@n#C6T_=E za!U5j>2w|TE?S-sak_oFEy_R#_KxN%mAro(1zp#^>OJ6Wr!zqF%JK(~R$G|8}tb9@NdVl&74E^dU zCWuvrqQ>!jy*kFf)ufPE<9#To5$fFr>W=6xi3?9LR@a&Foz~+$bOus)Bi|bC|2MgI zB({j#rK6`M!H4m?vB*wMK+VC8XdhOQ`D5e5mZR&tsh^&b$Av}RWwTf5TQ)$zl+lTl z1)A_MJZx-OZ`}JWlZ*vgulIfq@XF)3<4TWIl9&L8r1tr-OyfaHPv^;~@+65CGF!iN z%`NhGELk~i$<@uCHp_#FH*(h8F>bX3R_l%nZn26Wk>}+uRYMoVQFjX`txjTrw)yXZ zRdS0Nb<=EiM*QA6B=|D}Ql4v`2s4KA(D(@0Dn~MgVmu%g9S?W{hxdSp`7^_Aglw6v zuosGQFrE)g2wO^2BiW2lrPg1YJVf22XxypM zjQHuo2x*7yPB%6vIw#$nrd$6$X44X3?eP?grXzITmOz|+;Al3x@CR=X2P}03r~C6S z9Qj8l8=bBC^r||3^6Rs#S@LTuU6S_GGxAZTAwdV<saZwkQX zDWOuc>(3tC+6;WTilE38WW4&7kyfENl{1r_c7mPKU#*Q#$0fDv>0!N-q?U;`8+qdx zD}|w>AF4>{BLUm?5S_+H#b7rvV@}AAxe}c02fX~>|fZ^*jt~}RgVWM+>p24~wlwjI`NiOAefH&8Z~4vCbFKW?2i>V0x!V~zS>?FOB64d} zl90Pw*535yKE1_;!p*LmIi%ERBLbZ9J>8+(Z$8e5L}rK?lvIgy@;cOJIwjvY$s*Xp zlGnuWTP8>oRl-B21_HZ}+dk2fs%{usAiQiE%4nvl16FAsBtn_gXoZ)DJ)IqNzY@ip z`&}+t>Az$u!L1&`Y>^++SqD#ZP3S5g1C^a~a_p<9@vQtwN^Ek2lmm*JckIH*5M@fg z-lZoYk8ti^?pIA2EDCMb^s!jpiQV442yEsXi^CzTt}HF`8d7oeQ$own9e#MtPJVAq z6Ywh8;*%hSR@a|Ek@}0yd<(1V_{AhY!j7j{pAvjPr46~TG%0&RfR%ciNn6HS|9+YL zyWPK#-0*RsH5_zpXY}4M01nr-|h^e)iu#2;N|IwJMS3l-YIb-GJm(f796l4u)xX)9yyO{TC2RXF%&!J@@qDkM1edguh5gz=jRk#zJCA@OXdCVCZ5f1!6NRyZyOcGK>0a`MU4b{SO`y z2hYo|QO>#|j(F?!<1F*_>&y8bv(1qPblhy;^J!+{R40R%GSZir90Pijot&!~+W2d` z0;yyi2J{nbryve6wMZ*qI{gxWIVg{?&q|I4oAIwbk9WownzTe@4=)Zr1J7%z!7@`1 z3(m`ghf4lRV0)#|pdrvslZaWV-DXGO3)UaC)*b~CXX4y&7P4_N^&lEg`PrI5t~-ix z@CPq!KeM0KFMYEq|MgX|8|EnbG7MFq;8MEM4s8|uLAL6qf3BZUxGMVs6yne_9$u_> z26~Uzejn>_|BtaukX=KbYKl>>b@w!Vxh$2d3R1brK28{E}Z4z z0c?L5x<$D%X)jXjgF)Q>I|_D=nD4$akLTji9lNZwEPL$%*X ztk>aTVp!^m{?1hFr5QUQA_?69j!f+hL(&#$?!dEwKfu?XpNc3yhB-DUao}5Bg^%Og zimO9$V3>y*hW@U!6ymIV%BF=moA#Zx*u z0UPsZDk~{Y7J_~_FXfQCIaQA!k+*uqT8=fJ&vlmS{KX${x<`s8Y_4$EDRXg9Efn>$ zw(;OuSA@{gIkq*GQ-O8TfQ2qS7qLrn98C)(MWW4p^gPMIY}UC!HWcRt&Xb+H zRn@A`$B%8KdI))a{^iIs7D~(OSgqeO;TcxXzrV`+%t)mvB)%#6WRWrL*K7%!+YZxk z3-Ctk3ts$^DiPe-Qk3YP;Qe!1j14yix5b4reDbH9<35-x2d_?vchRTXk`SDmcN|(x#;z@5d1qGQnTKLQ18}Q5x9{lqa+Ys-|*oWlCm!g%2qKVlnS>~?FTg+1ZeH>6SQq$*wk!>rE+8s47HUiIwn zc8Ls1q5aCY1%w7Z=q%~$R6BD?yIB@y++Z(o@onEboOxq6aDdI*zz!x743oQ0 zg#sv`ERp&ve){K1*lXbUhiVjYTaCZtHYv(d%FDoJl8k}%Q8dGj!ITWUm{NWrw(*tB z%GOJR(y&A(W$Kx+>-w<_HY~x(p<}Y1w#X0#cS|k_7@0mDwo_2VfG2OD#yKGbYL=X+Zp^fPPbosHfootvL`{C$3SC zpqZpi+_%&}`-z`egI{X5c|dbe%N{ET*J+2SsJmA?2 z1jrL3zJmuwb7dy=94!$^Uin0<$_MY)BU}$rg8P{`#iSSCsu>@Pt>)oY; z*FP;U(`Rx3lgee*i@(x2^+E^j? zJj=lAW5g@&7q!6?3Xdc%z4NvfJ%`42*Kk@jLTSVyw0XsuXh*e}ZcH`Q5_g3Yn-WAIVr19|L^h=X47qs=P-$j zq+n(fom!s*P$w&gCe)+xq#lPrCoV?!C8pHw^7hs|k&3fD)Kes#bQYsBRbaQq>L~mo z6^QYh2yS-8ITUKFz;W4VMO{^dh0C#Cxym=!RUJhHXZoI1BISoBLq|Ja<-Y|V((j5Z zF$;+ZDOL@GuK*>6U9voRe1dtI^B+q|Q2q%DYG3CwyYS^M($|1XL1TLH2{j<^;Ugdq zsxA`;JerMk$N`Sy^5&|5Hr>J!pNI29S1h~d$v`Q-&t>_B@HX_G z{?xR-$OiiI=(B!ICJQzcWN; zuTor}`s@U8e>8IFY*7L%ZXmk4R_(`UZaLPcKaPiZWa$PkYyIW{ZOqLf5A#98$tLC; zT0sXsVzQf16dJ?fj~>vtLme`pJCExBO_(LTjTnT}P){)fhV=g}<-YKxgEsKU%c@fx2ReT zOCu@|Ys3?3m-TIHw4=i5($c(Uvjz97z?MX8d62brx$sdm%>&Fv3aiW>vL6ak==@MhXx6*cKfQ?^ zEYgIoIeByxCp%#t8DFc4=yw-T!iIKF3X#=jbp8aG1J{Hpa1Pk=rzu#V<~nV)QF5s} z_kXq0Cn+d{22nq;|2P}Q(4A8SEK|%pOs%@u%{>f}Mw1Ay$doeO^{x!ffx2i%Di?QO zYQrFaF({m^z$OlOFRM0URmS%KUYYDEZ7KaCBV&ew4RMhma8$*`+n`{N3hA zdAL*{Oq6x>%e1Z;vku0Un&V!Ht8w+h7cILugwD}FfCrqH5zeEO0ws&YL~87sj{NOU zpWiug3lX!QKh@{&DWkCWQ#+Xy0vz*(*^3+p9RM)zUKM4uxL?s{%{EFP9Tuyp#B1tA zQ!wi;uZW%=HXMYtbqlrvI-7sL=*}pj|Jo%JXR^(Osah%60pa7i=vaRE&dVQN2JiYV zNuZbRw=oX62CGxwrDqnvKW`psWI0tV=M z(x{kp;cg4Bj?o0A>2N*S6SuYaW#Q`ApDlFKC8jQ7-UaK3G`m8p4-jP@2c~> z{N=f(wR+Anu2=>N3Fz-6?l<%=Wzy13BssEi+63CTA;0Zz@@#|kDeecL+acekFHN4c zlJRGyT9|2F=_8^;;$Os>wRVR)-f|WZze1LxFzV<>%A{%P7G_h5YaFW#E^Rp!=!@Y4 z?*mv!>F-vKJ6oB;X*}$CKvTrxV)*m60YHBFWC+?c;q&`KeQxn>A;)c69@uj+L-Y4L zpI@fV>o)xdK9k08tY}0sfgvX0`&Z7oVjS)gb%GbcaX4|AICh8}C42(y!B8%+T)O)&$$Uq^U<^dQ!Q_RN30%>ky zJZq!_qHUcF7W{U8|JjKUI7#qPf_xrM0z2`NOcfgC0ql^Y){qDg=scNNCm~bUHEw$# zR7(8OK=AqT3M^1dJgLQ`OmHnqva`0l?LeEm%w+r*T7dF1&LY@2o?H<7U|Kd@HLGqs z`VOj3qIxf?2#0^uvx8>N9}}50KKuj|uD9QI@h2PiUPA`;a}_iSg`tW_-6!OVVvQ1R zoTc9PcmB~seK=F~k6ls_yYz78d(@qD;rI_L{Z^9%u3YNuKUbdrk4#{RoD{CVy!mG~ zL3jOEw&f${{~?I(zy2?qMef_Ae|*tLvIJhh7=Rbp1^a*e9Fl;O;PdoVIbm>*l`fjG ziGKt1>i;6cduI}QQKd?|*oXh@P9;3})XX`2xmHKN?Dk%x?Mn2}i5~~aBR{X2>Sghf z88cdz0Y9KTnJLB@MF(hd<>Sg%;B01~{b6-K9ZO3DUv2H8;2N|7~gmE$e9N^(DR z)2srr8$NO@?4(w3a6cm@W~v^HwaF>BF|437ctw)CZCLwhNgdpNKf!5wYPnqC9!B~3 zt>ctZ((Lzh$eSM!%KIFxdgY;mOJ2;*1HzK+19nwew9}}paStO^fL=V`YaEyz_NU8w zSo!FIt*BTn+y{u9@~CiAW!1SQ2Ju@x%v;e+rzTDkPB|f(R!;|3g2;%^=ttIUa!F`6 zo-5F$b5^0Y`*cu`gwF3p>Y2ei8lj*E=s2_qhW68J;|sK2XsUscRNQBmghC(Tk2%B! zYEmY5m_D}d9<}U?qTANyK00v!WU;$M>wB)yplSecSsa1xz8jFBs4Dze7v`JAQJstV zXfXo?(8s?2K_6$z5L3-&h=07*NB#%+^vq_{%ky*i{%Hp*34eymcSeP_SstR$5r>=f zhv!vcF;MvE+fn{|(?7f+lRB^gg{@R`@~WJkZP1_&LqYQ|z-Poy{k+mDxzW-HpqgD3 zY6K_D>kEV@rFpBO3a$}lgz!FTKsJyn;u<5=v+=W%o51-s9Z88Y< zA9@}3yXswmZJK1sIOZJMGQ%57>^11w!IN>B#IZQ6?2Eqs{{f!CJoXJg;A_y`)D#?T zg6{qQ#~IqNb*MSL;yf_0XxZZG*zznQeSm1JKB5`jLzAF)2@`PIFCD?`=QVm(BQDRQ zr6g+EH@3UXxY*yqE7IUp=N*OqQMv2Sz>U{C9H#HAcsd?kBy-cenfPb!liTmA2|pWv zBTMFQdFdNb58~Ek6VD5NGrB~(1M~SG7<-`0dc+&$TL|^#i{jvIA2{CU;S;st;Cu zjp`cJ5tY;GZPk|RmZnQ5s?E2g3|<}h9XcwphpZFU5<%1mdTGy$9TVEI%7MU{mxWjI z?Gp5U1MYQnoUzC0_HYwP`^7)nT}F%NkLfe0hbonj(%Xb%XVa={7NWp{IPHhB|I?1_ z<-Oebi|&N+;c?I8V2lNnn~FF;9~adFEm*2Uq2%?K*W7=Y?VewK{^BTdq3I}9DYRWE z`}MX())>_$a7L6tB{{8tziZ06WklMq$)+oNw%Y+5mP5tw*$Ds0Cpo6na8_RocPyK) zw?`%7NK#8I9(WveImtBIbA8hr1f-}e-7L%%sX6Z@)hV$$;IEa}nznz183c`FFw{%5ZT*)M;ztHU z_x9rRt43Co^l(pXFi?Yij?ieO4c!EjrN*iLZqM1vZ7a0xCXt(Zdx7sVg;-XWp%k%# zvB-?sj`=IL<r}eHB{L`Fj^*5X2BARcYC$%0y|s(05z<##=+ulgUf)sXX;3 zANd8c2s2vb9EJ`AwhW%yNC6`xO4^v}o8xoy`sc7D-nfQizF*txCiAo1durHf=OLAz zSCYtw?}&+RTt@DnrZcG8-vJCXc`@n|*(yxHy&hjwFn7tzg#(^pT3QxLe0onaqiTxXXzL@tjlai4* zPgp5pnaAP`4*l4v@|L?FGJV;}f%Iy4IEMOVm#oO_`gZKxe_o`<#R3-s&IW@@%Dd{s zfT>@1e^qUOnWT|+_7lQq=B_xJh}v^cvHT|(rjv^3f2)=>Yn)}?QRbNu<50jUjecam zkiBmB5G!Jcq11|nx#`HxRGHC?U25Ig#>0SJu&LYXS@vYwef+*ws(jgozl5z94l~XP z*Bi?~JsIT_HhB-Y34?u>{k`s5pwy^8h2?l=Le@c0YI@k(`^d+cR^n z&aQxlWM)Vp$6jFwE+Of9EWbhX=fy@Z@M*cU)jxb%SP15oL9^+`fsWgU86WfVVnlL4 z`VG83{71DF@7qoI5ITyvj=9VDUAfx1=Fk4G<09bl0k7kdKfJx8M{iD+Q}s%;<3ExCuS!_0M+mcEc3hj`F= z&fM8=8h!f>fu0JeO`+py9E&z7Xh33i@+WmY>H(I;Thu#5t*Vc%8I%rO4KW~a*w=W=zwxPaw_Etko^VUQDKHTc7)3kHm+n4dd`f*XZFLf1<^yKIqg$0buovg(wLjYW z*ep)lO*1ImE{?yKlws9q5^hn+13fotU}dd$C-ddo-YHIdA% z)K6H6|ICo9|0<^kAj+L?YxU-i#=kwT9()Lka4@Dbrbh^3SVJ2~ zgG3m!;%gmn?#N7m zbyqye)4%oKi%~A57CUBE(p&BD%s~w994y=LTd{a<9@v*JXV%R8cr83qD|Gf0#5uKv z>~Uu-abMQ&g8z@ksi z1A-P~${8L}TIyoBz6tM$&9HB4LU$(zmb<;<_ek?Y;9Dk@n%{OCoa34@_q;T7GI|Sn zz7fVnQlVteF;)r8EBrEr*vGs3Kk_=HhQkFe=0O|e8sV<$AeioB@!i(aH=~E5VEw6ha`|NAbJmM z)nhu81H5;mC(3i)>pH-~>|H^q*J%8tioOhPGK+@S64w4rFBCEuZh0M(}K0+Vz@ z2G@B+?&wRdEK>G}VQyZ>V(4xg(?mI}gJeUB;k`pd;7Vw2<|OxJ#$%n7oAY>iR^dYZ z@C+h!(A?DRz1N%DTeasgJ2TOtMxhv7Jx_3BtROa#8iJO8<&$-ZYNTWv{Z^ z-VYW>dT>>Cp^YI^O5Z2OHrsc;)U*w`4*^XPoSH9lUrBc3m4uFlZei|P;}TehTMQxomCX*u4*?x-I%pvDm4sFs3aj}m#C?KiKFZxu!0UAABMqEaijHb z1Et2i0!2sBUjjRoP%;7Do}`gC7sP@?|8kmI8jcUq-y?bRPow<5uL<6aOYsUhOcZkc z*01!RRDWFaYpITjvoq{o*58@wF!a0kiWfK!emb6y!FPMzZ9jcE`%Cm7d$0$+Yw;){ zI&=l&H}R->+|`MHuf~*zpnihOhv5FI*rD*D$NscHlm78zMO#KNlXioD-`EIgMKeVJ z$gmXyf7eJE6RJUpQ)*BV%~7qoj!Zji%F>;- zX2)0Gc8BlRi61EZbCvm}JOjC}uXj#o=dmg|Z(wh)=7h5wPumX&zrH3Nblx&vP-Gp5 zUC__+RpN#8pd-KlO*)V!{Xvha-*=mS4$$1S2CLp4aREo=n1qnwqQtkL0$Ecxe{ZD|uq;pBuf7A%sB&&V&|gacyHfQ5 z5{f+bm~OD>+}9;OF4m^dE?nlbLTzhTFThpAgy}gzGpp%@StZ;9L;n@<-+V1{6q^ty z@dZ|;*Fell7psgVf*A>Nz4^EjLYkQRm_gweqyMe7TeEr&g4Y%XThJu|7tG_3Z(!!m zi6WkBw|M^YSMt6&z&%G- z>sXaVlZp?gQ-8)2Qp|Ol+x(sW`(|bA_4-M(ifGdgK3_e^c#%cZ&mzj~)H-8th3X^j zMWvtBcEsebAK>4ewqWk87W} z1B0qYpC^eou|~*wuf(kDOYRIE;x|?ujW{0}0?y~XmeP2Ajm^K1wDu7u+b`U#Z>r(MDNzcY|UY>zg?8pDaU zi6~t+7DRZz2;w6NwIvO0+XR7$dmly4A_PTPmsoA6b)Cxxf+Ec=0DM+HnlED zy`h&dRBigznevZub7O=_yWE%zJ+Q-j-POWq@4h#eqEa>Bfb1!4<#C41ni#1qDZS`# z1ZP}7CJm0j{u(dXF(}p`$gKkDu7l! zWvqOl4*8JXWTpeyEdRtj)>+tF_|FFTgh^Xo>}Sy2MWd58lz%tY z;PQp_=cq>ALe+2Q1xf9WDrU{*?pIN69w_BcSbJ^Wp>J`gsbqa*M(?OvVMliag2A9~3yKS+gp?-x`#~;Sb$BO*E z^>?jdAzoGv2BJq~^UWD45B zYTwkrT^Uo^yzz3mJ9yF2l@+r&DRgDj)9p*;BHfb{$T2##X+8=%I0q|wAIGljQAtvp z*OfG`K_s3@u)fh_NO9z?hP1byZB`xsR|sVKQ;_`0e&#K2@tnKYPLPHX?;8qia=v6A xe#<1Izcc*fg#YHwbpK;(`j2^8O`h!P#;waw&4M`zc?-PcU#q+-e`y^0zW~IV>{tK* diff --git a/docs/images/scenario_execution_structure.png b/docs/images/scenario_execution_structure.png new file mode 100644 index 0000000000000000000000000000000000000000..08832c62c781e923236398c38600521b2e930ecd GIT binary patch literal 556187 zcmeFZby$>L_Xavxpdw)qQYxa-Al)b^($ZbhEiuH97NV5WjdTv9bb}%wokN#2L&wl@ z_JF*;exJW{{yx|BJ=Y~O^UQvBtiASH_qx{_-#wKPyL93D1qcLkN&JbZJOo0F1%Y5Q z;hY0^GT%gJftNFO55*O6z~zc#;0->XfBra|iAU}A(h+U=QW|_8lr=9z>qkE<7AzwX@ zTNrM`_olP6&@h^zD+&!YvyOA}4XE3hLB6>26<`ezNL6C<0oB25MNqb@K)s55iARHf zW<_LhHk$kB>wo>>zLwk{l9B@JD_!ZM9hyqgj55&5H$Q#UqT0kGaENxO?tbY;XYsbF zm^%Kce?5tL>v;vbL%7UXnEfN6T_w5ET;5jijr4IF{CuwZ7IJ|SY7d(Q3V7XrJP4^; ziH4oo+Yyk=*&5vlE~BZBgasY9p?pyP;(OydMBJ%FO_E8hh{t~IwIi0vD zMBfMuqdk9Idqr39on@OeKWJ|jipSnB;yM2I?n0$P!&I3^r%)l~e@XrnXHKL!9Fs`mY_T{%rtR|p};4^X<*%CB-olr5yHA=Tq=376ju z#KlY`6et`|;9OE;4#V|FL@VR;~`P$w>PlyP!SI!1nIkqd9nrg}4N{3f9La4MtK#RcNk_ z(I8?gSg5x*BZqtx`SexOydXCyXIN77bi?)ZRLJ?wB}(<-LXIy?=8v!CjcA6P%Da(nyf8^hx* zSkv4r?XyAisUsi|uOHtnGub*^%uB3p(Kc$d9-j-MJa>63>7At?{+X2>FkDELu+(6| z&GO;Wz_Q!*Pfo^p>0lkGaUZrWu$^mO>5@TA8xdVWTW{SxaJ(KC>!DZ*6-zULQxK9< zS9Hi5e^hX#&{qZ-JUZ#%>FnL@r?m}HYpGF-76RuWpWa)RQU$p$)dnwmd3zjdhTWWQ z$G+U6)`rV=W8;!QAJ=B!;`vvqzlJ#6(mn$TKYgW8D{`1ZM@q%Y7jo<)STu{Cn_KAA{n&0!63NB91-o@U0+dbFt>xY3F2zb77Hr7YhJm$c*RmBSW4zlHjv}h(67nMl9Te#QOi0i%ngz?elz} z*=RM?Wsi5ki9|<&S!LQyWx*U6xY5^x%k@g6QTwI0!~W?$sG*L{y%jMPfZ($)V{;J? zZT@=eSlzbc*TV{8ArJ-@>t2pnH*BGs5WJ&rn)GF*!&(iWO})g}HGlKn)NVtI4Z9N~ zIR#$~voqIL-m7f&Y2ox&s(qg{A6 zs4%VvxS=ZQ$i1$m>R=4g)^K<>^&%u)@8G?zZ6oP9m4 znSCrX2t<{oK&DbaOS}J<(Ww%LJ*@R#YyjfLESQpo1KF7HrBY@!>0}#aIxgCFcZ_%> z5kIOr=|!fyV5n7+cF98ESPe(Jf^`}yPA{32pMs2Hxo{mgbd-NaAM1&yg2Hexyi{lJ zIl}vw%Y;Cpec!c4M`XLQxH}&A$)6EYXfU^KhdFgWHfAN|?;}rUXi95nTp){Zo6$QY zy>`4h$f!Xu^^)}JRyW)64H*Sy8a}p_nlE4xo;Nu;kdl?IEcFThtf3QSUpyO+{jU{t zVFoE7Q*S-)Ak9Do=D7EGju28sFtE8!7P#1P(s#zpYKKLX^I`ziWvpW>4}oyY?c3@H zemrSH2h%7REJ*(pbEsJo9Ar86}IgR33CdHIA?6w+du+0_|I^e~Io>j*=Qb zZy#_NEU!b!VM>8^|4eC~w69`!bvN!`V)J$%j!w#pJ(k&1Efwv!bb&<70jW-+7eDla zs~iu4D=Jh8Jrp5){%cUr@rbRa2yyMM6PfDT2Q*S(XPbciBDtku%p}>+deSQk$>jUJ zou=Yw9kH`1B%lQd^3#h`~S#R!_ zn?LPf$hoB6g;^tRNgz`cW|J`&Ng9*N-CLta@4=rshy7R@+TyYk(P8mXn}-T!9!b?A zs)D_q=bst$vaRg|Ag=x%E;JdNNjfL*vz?>t03*bxe;u!e;=$iTwq>c|AEQ}@v6%$|I9?jUXA&;I#^5>P#$;8B38Q^&emduXL-R2f&%mv+`uK6L z`uo2%M4!y^L{u&7@0T7!Jin5zsQp?XUE=RPkDopH`!wPoDV^N<^{RO1pGE%1HzDu- zu>*g8BW(D;Vg4ty(La^q}NcrA38A@BAH{77Zx(EPfA9sR$(ylVhxXCaeA0~|91W6l0aaedl=u6 zU^L$nPxSsKc}oS=VAv8BZ$B#T7x4Z=FRB7CsK4pU#cqb?S~UII`dUj9c(rTqH&n}Y zmCK(SamSp3_RNgf|{z52Zl{$q|wh&d{*gpQ_kMQzdc`O zw|V%*apb2>uwzeME9XLX9;#e5heplzW9A^4uCFwLH3o7s{!Adj<%bu=W3fBLZ=OGM z>cxlGZ_CzY9%2vZl09E~6w26$Dwot47P^W<5V;T$qcyu*%%r2Mwlh@M0dvTU2o4C_g9lIR8OBW;xm*_sWsTajVrCp7sJmM)ZNk)jXj&F z!0w`$^V6<$XMd-9&gD|v#gnf8@;W*SM!R9r;mXSEW*drR6;u(6(>V}+64*tBlaa~1 z{538gjeCzI5QcrqY+)rc*+qD0|Aj2sSzVmmzN9%K;@Qw3$%(vyEdMJ+YhtN0#;GCK z1$(HH&XBjymXY$P^KuL<7dJX^D4Y_MVxWvliSnoCbhXlQp`sc6%VbV&37`3NhFrMU z_sPc0;#xzNzh04`$5Z&wX|q|%txqI-`y*5)bDhH}luDeAnK|iV*y_7iao=S5gghPKw#Hg~-%U!#X!V#*jgKljlPPB=&U4R3Z zz4_V;Jj=Ajw%8P_c6>Zh!NSgL4_D}WnV4Wx=+(b>dvaHl1t`o7-)GSd*HUUSSQs}d z53&+_5a?aLb>&As!x<*+1J@WcmSzfX(0Iy@+w`Ho8&2{%xR(5XPWvZj+Bk$uHfGv3 zIaAl}dMp>bueB;KgUc~nTXqN)vZp2XSnEB6c<@@EIy-tYoxi_sJv{16Ih-g{a(Z&E z!+9G;ieu83O;lc#{Gip^tgX9WCUYFCy5UkC(d^5JV&%HO_j7VrI2ddkB;j?>WZT#m zQ+0k$>B1OR<+;tmxx-U-Z_P zV7jj;Rf|VHJD>FUw^ssj%&hNm&@w*=TD`oUt59dMy=Ww`-hw5trwxxR*@63?!=*K? zAQ^J`dIodi693lA?|V1i_rk%6+v{Sd$9l0NSS;(aUtiut2w-+1TiwvAL8v& zrd26Kq_y_V=2jZ1aMBZ7nZv5HZzB}mX@^}dk8b&!sr@~m=q+_>EM1(Oz9gFQj(h{n z63!lb6n5);+qk(o-2bfTwbY@M5e5q4ZjQok2UK%RbN|z!csNH)e_vbjj=wv4_f_1s z4e1K&^%%m`FKU7zMzyAz4rR55yX^OoWGNHB2m0H)EpDLLy53}Q3!VC5GRXHsj5~|^ z8u_-enaGcxY0tklXLTdjhtK%3M7fnqfM}m&Ajn*asTl10JDrc9Dpd zoZNmF$$Lv~^6dFY4mvgJK!L}i$E4QZ#>L#Ln#Smt*Sq3J^{}~q9+-i&pOuqsDc$u_ zxc?bZhOp|CB`O_@{yp7$Nn$-+sBU5hQ+?=L(>Zp>OEbxEKbWccIJPytln+uaIh{A> z_9M0PR%c(`?Ck!3AC;s9qi=fOje=SjTDxh3?xQPP7rL0Wvp&R~(jBdg=Au@4WBMhf zX;`x}UGkvdLFPtYZXOe=Ar%hLcB< zSm3jElsPYES;3Oiek_KIZq^Gu*YGXnD}_uNTz_|$!<$)iQVa0=?(sX8nckII*w2hv zujW$6ME~AJ2*6jBKZykFk!gzKzncRy(m*QL+*Glc{ zM>wDUN;mvx-zT40q%iKPI(opgM^=^**{IU`)ac~^iraINDK^M>t4Rov)`1_}r?;hf z^2Fa?MVT-THZUnsLLS|Mw&O5Y3USOIHEz^@Wr0t|J9_n;Vae+^$HL{~LzUY1 zy^3Pc7_rKwrR`2{aw@b9;%|^%y(d(&_VqBJ#alrRmKE&~Wk`yz?Aw{m*Gda+L|1HX zah??kCf46l<>zc}bC%7{?932=d$s&mZuXC1h3zq?0Z)YGs=Qr~XJqNQy!?W-Da3dsoHj81=KBW@0_#hKeHQYjDYAAxfgFf?YHL0UioulTrY*8L_GSe+SNM5XS{%E& z#|wG!bm@SX-L9$kYSyT%)XJpSxD-Wvz8|(ne$f*@-FzvR_f*2*ZdCmrk~sM=+BOKa ziU6myfVcL++zh&r3fFCUw}7(pW&8)wh1n81bASJEV+T2iM3ii}FIX=qNoyc7)M3aW zs?RLHSY^C(nAyL0`lMfZAl))QW@qg^ow&T7dX`LNczm)#E=MYh8fR3^%|lDzfVInE zDgN6-W)gI)Nq(*G!g?lIEQYI>kR+V{fx28P(zoC3bUGWRGzm_(&gJD+GzRzmo_9?# zg@iv;jbi*0h1C?8@CG~7T*ESzlVYX|_+U%Hw)mk-LsYcH$Ckc zs%_e#A3Yz^ndSdN_KUm6+lt*@?I_##QVP0OS$4yM9z!lerhlG@f3nWY!2_J{ z+GWAjjl~1cZsmM);DO=2LkZVPHM#~lbmb(DTR#c*JS{AmVKU#%tdr4Z$*f}19?q`i zEcyaC!JBV~jMP#h5(C%AxQtC!mhPRZYcnu7@1$>BStBW}@#}!6y6^^5=P=Uw3UPeB&^+yLz$xD5Zr~;D3jwUR(o}#K)}Ilq+=J5?eVPC9o<2x zRhjfeh5REkf_{%VjY{B-(q^pC17g9?v4Q%yv^1nPUd`$XNUL6k-;4a?ooBUSVIKym zfK#;IsUQh$U8URqiIz~xUstEN1mK6kRN8IeL^?k^Gh3NAThC}|y(UK=vK`|4)CeQqY> zKOO)1#+wOX-2K_I^B5Q3Aj6*RbG$%ZZcO0m^`W-KJ!Z9T)4oO|s%wY}r!i7L$F*d- z?7W`ZMHb0~I>X+qlot21eJ%gj-ioGU;N@b8> z8J6d!7-H})rsG$2hJ&6!bkgyusMo%PARno(=mm!keJ=c9WqO1fkt{Gq^JKJ98z zTIQ*vLAkG%Wt@VDr~<=6bZC_yJN(pmNBy04>LPz>(>fHwRuoeka~Z9GiMs!Kd3|6@ zF_!}>Dt@7)gJ-nvRyjtQun(y#>w)-+-;gkNS z6Zoh58=P0t%?%Sji`Ia_vPMLA|bjYBsj0_7v1JS03NB`;Wj|35A=gKe{)A# z%ecs<*HYpgly-Pr(ZW~6Dpjlg3ljj1HMQJegP+C;rTGh1?!EY+?sBdRN&M8(B@Wr1 z__9%t%|iKx=y~p2I^dyn8>a0+ne9P58km;EGViqu;uPiX=$+H3S^SLLR)kw~IS2t& zDM%sTZZ#7pzLw<~LCvpaI^Iaz&_2YT*7l3pkKP=kw&0}Yuv)eWo`JeAYtGs6A(2Ze zl^)BQK+V!C5_LEh%E#6T|5@$tHw26+*KVWg8ylfb3z^7ie07Rr+j@iU2t|tCAnB;V zw|FXH;p@*V$z>VSbf(ZsutK#*u%bDS!z*X+Dgr!@iKa&?%jl$hlpefSVU^i^&^kwf zV+IWDM*g~qwL$=}VtExM06PpQiap?F0fm4L%_I>?IplG*M%(On8dE!(xF=Jc@Xcf_ zT}H(GZ(6J5p@z!gsQE;4a^dxNo7@=mDRF-cK$Ogc^{;E$3G1rPTK=zMd-~Zv0Y7}W zjqHUpa>T$KtuxP^%HzW~1UNF1hfX{>LeQ^q!&J&BT7u2(y`9HOom`v{_ZIoUV4@aU zOI@iiBjg&qUv9+kneA_x{CWW!TVXbc{n( zpgw%J#9cE^$i(DlTD6tJ%eo?kA1{QT#<+dd@J8A3P1urbZka5h=?T~msCtSl;+SG% zQrC|E7LFj>NN#DjmHBDY2Sp_@ zXz|~by(pAr=e!B;yck9H zEe8|a6p_5u#ES}irX{gj5==fPZ}iZ2HK-f}Lna0pD*Cx@Uc+I=uc=~L)X6gV*1wmi z|Fe5}KVVAO5CS4V7x2yv=fn0R)ogj1Xut5qGlucS|4VTr{4X1*|0i2Gz!nD39vA0rWu} zlVbEhul&+04A?1IBOe#^Fe*Y(MM3MxT%@Cf5ZsRtZZ0W$YX=o2>coSU!=IhozmMn4 zNh;)^kQjDsUPLvv-@>X&q5~QE-2wcjtLl)LlCHtEU7? zzi8hbG9A1l3Zi>x`#gUPpFrJe^98}Z-oBwWxK6odd}WyyJQnN1;a^y$D%==1tbBVh z?VfKx6cG)!V;pvhfm7FL%mF;Esa18X{M>wJ$j&`NdBGIu{^E>DMj-nwz+~6kmLd|duhMDuOE=@UK~-PwS?PT?N#l~`Z>Q>N^|r#M z>xq`L!3#=NH8@%9V0MXvmD#y0mix#|^8nf|l_}p3b%uq!Ez^Jt#DK7(9Q&cYb-baK zTJ5v<3eW0(IuoEUB9QWQL=dJZYW05kk#w_cmq?gY_hB@*x{#B@TS|9?m;5wK?tlfa zn?wo_k1B}jvi#TH7~CmBhh4mjqPJVc0LZ-Llup!>X~mh`P$(cGIZ@>#*_7vpVcU)KhZcvm+Uv$fV@CK=y0ww5?-z> zc8XvUI4q_Zu7`!unh9M+B$?wRDYw~V4vP%lX9Jn3?Ca+$FOq7L&8kl3)vN8S(9&Fw zn#|>GxT(g%`)JN85@Aj?k^$oHJl=mHM^!7Jd(ykJ7mkHS7mKiF{WWTWL9`R9Z&<#Q;I9Xi3RsY_VhWqSHe7qOYc(q-7qKt>2 z!g?#DUL+f`SADr$W*_DIMg4GpJ5nLs0!ps?#Ex$PV*m>dXK=LcJBlh2d3yBDe={g| zsn%?!pX$XLZ3E8P3<E8XRlLJp$ZW7g-B7%LAZs zc=g1ycPDDin*py1yt-}wTb(Nfje4Dy#=giaVIlPOb2+?tEVn0UT-LuSb)vsdPSQyP z8`1=bR*j;@HdU&j%Y~~2IpfO>Jhj}y zH#O&er!`lMpG4hD$sIW7Q&q`N-vfe~TY~_`!Ir#=0jpn+x)=JTFKLP4da_D(Yi=3{z=>Ym}xX6eo zd8X>-4~gesZ0fJ>j|b9L7d&zAPP>iq)Nqi6`|rz}001y` zSnGA@CbpE;bhIf?O3QJy=FJHh6o}v$F|%?w=Pp1g(ovQLz$Rlj#dhpmu2h78$g4- zLnfe@Xxm(ybvilDNV7mT6A_h|oAPLBlj?Ets`sfFu2(+E|2KVE$y8Q5vn z*(yVi6w!&e6&GdKhVNs?XTKXUj!Db@_vL+qOCZ0xYx|;Pr&P?bQ74c-N_dLKVh?9` zGu{pPp;t&MxI6JKVyBtj1vk#z>sy{`ISef|d0SlpGThsTaNH~~6>|&2MCgcOG2n** z`I=Vhv8)m&bT6Qh3DI~npb_LjC5y!=C+`$1eLx|%=AD4cqN8cKwy~$Mb_G3s@y^WP zZa3}K3%jerqL@=|$ac`idz*WKbN^@7iu&?gA&(KHx~(vPG8tf`Jl_sw3xn%0 zxEsKj;S;Ln58-&?EIT~%i5*Zx0ADQ?A>?L|aF90`+N{-c?VJ0_U1~Ose^yAfq2l@Y~D`Yx>UQtUiMp-_<}) z%9*w~zR0{;;kOP*M{^aCu#LhE_bIP4GNsaI)3yCTO3DV7g<)mV0u=!%QcZj?0w`VB z)LbX~+BCi5NITUAn)+<(m$)TIWB*P`4YDKJ=5Guf0oI~+L2KUSWuUDJQ^(w!C^bfr z<7QT%`6OJ|z4 z%M_15wz`Lg5+le6jW^!M95{8=NHdt;82oP7OvEL0zuJi5;zNj_oESnUL|OnO(=*|Y z!XVuN-PjJ9v8lHT3oK)zsVPzXFsAg_)fZ`l-XDLD288Vecja9s&zsajHJKio_aEW8 zY+aAu-G3mE`$ZeS+)mhf-a=V_`YW+9U|=z>XVELbs$U*dNz{yYtWQQ1M{0#zC{DC; z02qFkiMdCvQZ3p2LTojLg1XMTi|h~plu!3~*w7u2)&Z{Q{U&!v)Qp__dlf(&bYvxV zJc9xc4oKmKj=y<3&mYTsDd!ffXO#epv)l)m=9~eGL9SzvdE-c)V|{+;3tkU%$OZ{0 zKqUwW&OoyL*^DOjkehbIY_cB!=sWv!F6dOlUEqX_QR-AZ)A*=&(0tf4EqJZ*uKn6d zBGkyaz|?S5J4^(Veh}L?Qc`v2UhCT71(U``vySJEb1)4Ut9oIMtgOQ3bfrE?S!p2> zg@cm_SWj@6lM3n7^S_jckYx-gflL(hj%@3kt%?2PED#}gM1M121epYGQWv?AcX{iQ@YBaE0(J zooLR-DndCm>-k=p4Jnl6dHHhY8U1;fnP&2J4bL5ZqlyC|Cg8oAnaEvZV|1b~Z#-MZ z#8dm$ODZ>Bav2`$?jMI7@>&d#lho#B>kEluq=Ewrd4QJ2l(TrX9y|13PEk(FB@P6~ z9LcyYdZuRILp^mswu>n|!n}VEz|5DX{XAaUemqA7@`K|GB;K z6A&iBo^QXN-9!k@1QeeX;*c&nxgm}ValDx@^)RMqr=ne4Rh1+WR&MTLiyoyCr(Y~z zqq2rCbma$FcVd!zm=dAY?XxMwf*xyWA7T2&xv{EstX()?pFU}H$e$_p5NfqbpXJYT z=CE|jFg0(hEMR{U2qGAerGW#^#8mrBaTGy00t8^GvMm@vf6MvxbE7}@;YLn*4!l12 z@^f)I37_OMdjtUKV?0GT5#JWQfHJ6R0eRGVusfW!@gVpGoZn@BnSAutH5{+5ezqGP zH!;4>;L|6sraEMP$VkB}ikuM!RdcvVx2Xz*`}tO9!KKWaD|XOjAM>_+SaZ zrija%w*v2RD#LO~0Z{8DyZGhCryv9rV}p2;cU?jvShh4jj@mR>g>6@^$DdphUV5mF(Sl+lVET4wb_S zxl*zcK%YFtP@rl;9+EaD#%+e_}G%`yz1jpZ=u9gB?iJ`7GK|V^) z?$xOWYwkY^KrxQ;qA7ASZa5x;ysa6@Y2pU-`e7ZTD^7sp4P7wfgi=7dd7Pi607lXn zb^V3z6CsZ;4-5G#70ORPQ0UoV0N8J5gIWVUph5>73A<|sLMBslz!qywht7hEA~O^U z(DU(&!WxK07xT(RE$!s;JKCBch2K+7pJBiBo(^;RHDsCE0j1s9?J`nG|Jcgo z4>!bNb}G5&PTedfuO*hAxLtfHj^`@a)R4(7Opep;eV|foT-wKUZNTDJ_gpw5f;lwE z5V(4NsuHLU$S+Rm>}olM3u0GxXVI5;rfSUr>UnJZo$hXX;^6H7{_N^qb;pgf_Mh@q zI2POhr<=Y2)#_Jg+Zriv7I1X~$w((n2ftSTo(aP9k-=mL0Nf_;I0uK#%e|alHWP8d zehF%p6rkn^2QCMYlJCK8CFMhvbWIm#hn^=0V@7jBS_-r21Q zx~l)};^^rYAKaIl@b<@QE}RwlxSNnBMA8A3wde$-9lDJs=$c3P$hwDSSzY=Pg+kgA ze*vnD zT~sZU)~M@zbEWn_Pm`?!Fp@q;?hBTuZofc1kCQDc41J40&Y(nHVnW%P0`bUssRCvlFta)JsI zWR+iPfSM;v3I@=+Ab`JICR0;FZd*DJ_Q4=m-0k2~$?j>?B7Rycm7H*cu|m=LWIc z2 z5NYgpI#WRsr%o=Rhc<2?-l=ue*^AxDZCv<9Qp=Gg$gn^u8+ML58%b;Ei0V`x^K}r& z$4{VK6O?~Meju~nng{eywK3i`;EQ>|p&{~>X$KCD23DR2`h#gepC_i}Lla~+Jy_4*W76CYQaJX4# zMuRdu+oH2U0N!6MkOCnf1jY;S^+-^pqYg-? z3(6iWp;{mf{XFP{QV6`?{?jYz+aM850-}3Q+5D0mC9oqu`9zGq*WCkdYhRD)^FBi* zx0`RR!8UH3#z;Ft;b1Ep*bENW0yPW_t*O+2d${X+{S>-gH0JF(v|; z*zX-=b`*THE2w^Y;w}f7umX69DZw3h$`_ ztHD9b_2A9ym+K)YB@160GK~Uzd=pvy!r_6QY# z+DtK0g<9bm2c6~e)Q!S5p~pB-@c7vC$eGr4@u;t{Gb@0Csm7PNn;Eg4uF%)EgQGyw%YH**QqF36XuvvW$X z`2=w=@o9rSl~^Vp&Tj%c)ICqekgHmps${K{C)&j^|7%$Uv<_X45%Q;ErxMTXRbz*T*E2NQ1;Rfonn_r*zT3!d$qgxhn75DGTc8uP+nYmej$_L|H ziUna33&J-f;z0R`H^GsoR9X^#y0mE7IhZif>M{L_9V+_lyQZ)}DT|s4!w)XkMUXY1 z*xg0;BMIC}sj@+i5mVIx_)GqIpJ}0{Iolb4adx_^H9!>~t|5pxcls(F=7z5+p(wng z@6Usi19;YKfX#$>ZSrW%lfD<*4{q5DlM^MHDQ0)9;XR-iKd0q`+W%@8}_GAXzOMSzx=fr2gtPANye!_uy2 zmP)0V{IJ+?=DUWuvR~e!3YQPnNnhhC%L~fI zfr55*lA%DbYHjn4+3J~g8B>h0rgd9Ef3_a@>4BR;V0>KZWU2Z+EUvE|>3u2om&tui z&%TRPULNUjdK4JC_`;hBOLntnCd;%BgN=>+ByxCLh%bYZ91s;#CvRZep~8ZYG+@|Y*Ayie^=4YER@t^rvMgo?D33+S+~EDbOYR}Ap!yh79f-^q zTk$u0LQZ!{I z_?1Nmzzcd?^Cp`u!<<@cGeiJMK7$6!Dgit8s8TDLgR4bBV(@2}iR)l5Lma65#^iUF zPwEjX!T|$g9BLd@^4QTs7{5XR{?uS8hLlJwB+1O)Yvs+$z`Vo?Nq|-F8#)w~9~SL( zbTLq<1=598@07~8S-r*N_CM03V{+)~8p!Oro^I67O|!gLIkKI>2H$~QDUgYaP8WAR zpF&*a5$F`40J6H6s>(2ClCr+%z)ETlv}dUla-nJ%{Xos;TY;Xhpjumr<{YI5#y6q5 zf7%Qozl?W=#LaV94C|YlBfAU_q#G~})&TW&sLRrRc45X>Rm8f3qk4FXa^GC?Rl2z= zbP=aI+iji{XT~}+<5I*mIB>w2f^JYiV6SMJ5lzI;<*Ev_za=~{8B_36D4C4j9Y6zH zx<9$FUp>XWZ3^NzdPHOR!w^tl?xLbddVj9k$XBZ4QSO?3%esXKCozwz!sFW}4c=$= zCxYe6K~P)iY#0Dc=;MPMBmBS414%^_%uS%yl*`bH-5c<2+k38VAYy8eWnDCm`xy+* zBqo#s>5ti;92_N+#afz(6>C5_K2-CnC@gvk2qBOg?7csR-Duhh_~=p*LzuZ^W^Dh{ zR8Xv7#ub%us_JG`bl4|zVq#R&szoCrpIg($s?LM+0*{+-0nz~l>hWQ=ZZXO#1-9k) zArKu11|+oRtq8xRwQIB;0~q!*lg`sm?}}@U(m~~B;E0$b*4A!p-%~^s0HIWI@@BnK zfTfe1nwkxrb|mGzLP7`XYXSSD4){T8Gb>Td4+5ayXRa#v&n+#T!O=D02D!zQ$fpjB z;-DJ-n$p?PC3662&pVc7UK@#lC)kfWZdAa2-or%s*Lf3-3oY3I`+@Y6wd@&D5fl5_ z3^q|~!-EX{qbDWuzK5PE9hmXa<@p9g(ipo(+}gqhjS1!sbKg`?PB#}V0bqQ6PpNa# zhSWpB6qHA&99q2jX;*Ct=zJ|sA)Qp|7WOQb4u&OS&Vwa!nw{y;bNf>v0x)L{eZ{g3 zs@Y-Y18rUo@c#;7lA-SaO2XJ7dZLNUR^VX=qShyNcm>MiWjHK9I>Wo)%skN3&- zWAeKCf`n}|#pg4F7R%ol6Q8jfKXZJI9X?b}PI%`Pu@T<;TBZG4E2!0dCsZnVm$~lq z!V8bf@j9^|k5`;up+vWc1cu4HB|QItFxY26HBa$e%05gJDH_nVxmds zr`Ioh-M=!%%1YZbBq^8T_?l`;bW5-0`y%&Kq_1rEwXyO1vp+INmvL_0N*G@m)Cw0B zoggfrr^5=s4`Jrv*NSoVbz0v$)7}(VqAca)_NtDOj_*qALG;_TKt6rZhaXg@@&2kJY8F}^ zTx)5`+WxZZu3zE_bgY>kD^cS|UnY!!e?0%yNmt%cO5(z+=f$_CIV)ySnoFj63fFGuT*2TW)}?!37wO)e-f2BD9M*H z9SVl_>QeFBx}TyHWX7sof`7-(yvX7q$=Yv0{!Lm`)IQ0di_Xv6Tc)vP>>LeMhRZkX zZhR?}|5Ksjgh!b}@93wj9#|D~;yY3XRL_2&XU=JR7P9+>SFnp%-^I&&lF(Gm2l)b< z*ie5oHZ5Syy2CpO{96%%WeNukm-^fJ;2 zYM5{IinyZUCdCWEbA~<3220ISj~<3c3ee#*_P>gA45hDE7GFxPZhFw(yWM-w6=oTE z=VDbr==FsF{KIZ+4XW!e>|iStYw63Ju%8>OHb2~K89;AZc4tS$);eZc%3KJBBST+~ z8MoHFjM^Q~S;q;-9lRqgYG2Y(dS*0r0DCOJ|d=Q_IveueZmhEAhXTsm*%hu#~#+{7VO@`|hrUX-09j zqGPg)bg3B1^>0*^rpJk`r>7BJoAHxHNLP<(oV(GR;O7W2PIL)pCK~FXl3XI`{du7( zV8U|!TNjqx)&XGnb>|o z6DiTRf=M0|duLWOqpII!3JrVh5OH))YFRov&}i=&#yMrjsRg*SEZm8mn~m(BFIp-c zB3T{0ZXuvL4bEjq+50=Lc^jXcth{SpPo(*m_Pzec`YKF>a{cU=y&pfSG;sJHA6>J{ zwwqS!`L@JRks%vJm416Sim}G&AWV~{kIrwA&{rBCx6ZgHIbO`zr!AUw8g{$IVEJ3J>CdfJzy0USI@6=GlCYKO z7v3{hU#m(vIX=F?DZoM=6gbeM*A;xvgP|l@D0JVA0QRP^()fm~KI`1d_eTOBcPB^& z`Lf9vt_w8r84BMn;O9P7J@#s_{OYZLuCQg!jP!VUC8kAMV7I2^zWjh07`$cJD`UxL z!?b@@3boyo502m{yLg|9vOYdnjFf=bdpo!DO)BUp5 zC|A?OyUw#=ZfT|k?-lzT~EXoBpZg)obDs zIfcZ?@f}$tQK95Td=~xTEc>i7W1JlaPsh(H>poT4b&vHnaPZQEI-KkEez+Rk9*zxt z`9nCjG;I7baQ05mJ{T-hN5&KFoTZxQns;|Zp(E7BG0FJw1&#B%DEc}V2FPIAAHM+h52AWXMpQIaSn0e| z4}lI%@!fI#E+0w@xMji5P(*<_>iKj8*t)U&$=#Y&S6`U#0_m+#v7~FolhPzBW9s~c z48;Bp8^m>Y=PrC_b8#rBG8jcLimE$wKG_y|4jOIs$mbj0TWmA38=YdFjHBN#zZA~H ztD>=(w%Qx?STSw8`&h(3rp(@mQacZue)9+ZkU&SH z%I#a_lDo{Fc*~r+2lMtcZxu45vcmUTjM($~YjTw$1X(WdQBu64J$(yEC2W;rmeuhw z9Y!)lc6EZ@q$?wrx2UYCyuW+V0_U8e>qDqB z^1+`OvE)PGQ$N&bb3W+n#Q>e&)8>m*UfTS+bVkCOH1WV{eH}_6utz5r8X~Tg(3+rmh02s^{xIK}11X zKtVw1MxqQ7K^pSci+7;bI#dkpM7TR z-(SrdNzZ)f%-l2kPN22-Cb-h=*37j$Q<fh^UNdH2|2-<6D`FxAJPtbYa zV$1i!p4D%mEZnX2OtQby%Ux5`LBtP1WBMXDOPW;Z)m(i~OMMPk%Qi)JKrfzy5)c2@ zkUfH!%i!W9>RvbqvpJ|ra2~`rdhiE3p*JNFag0~vv7~zVKLy$XS5QXRSZV8SE z8DG((14y~Xb4VMHqUpFgq^az1_v&#ln$4L_R2=|4Nlh8C^|5dNEvk%=yn9oEEQO*r zGscrGl-KTi=(fg&-i%~0JDH7(DA*w0uZV*b+;&MH@1}T<1qQ4y1DiQt`T4dcs{IXk z<8|iJ``>_z%#$AU-%NGi<>x zj~+pd;QpCj>8#Sx&nHMoKjqR?q(w6nm=J~A=gF?J+~wTqRxM)~_)kdzxS0zPWuWS{A1AS!=#6aV6`a~n#7fn+y6c*S}-C<}no^E1z=dJboH zfZLDbd?6}wN)miFpG~kLT9%pFd0)HNo8*;SNs^aV#G7#jD0^OfcZ^T0TX}aigVZiu@LyRfa%$FbV`!>c zq*+DYmVTNzZn5f%pCE8vxOtnj*(x$~Fo5h*eW1#u=@m?6!;b|0xEP zf+xOVG7`qlE->`mz(%4Fxu+#`^6>lK+2gk#QWE&k1OzhN1``_&*7*FYuHHhyy)qt% zwSWo9pvIqyTJ}>`_h_Nz7(#2W@4bP$nTTk#Vjm@FIuRf$jHcm{0$%X!l~yS?u}w2J z5|XHkk4gtq;18CfXP9(J7ZYbLzh;S=52+LOTNB_8rnme$0}La!%qFzF{S@ns4Ae`| z#2>hGzyJIE%ObaZxorTrL~H78dQwia6Dw}8OuuBABx2AC&mnbLsFLMA`dAcUW{jI* z`<>_v^)1|)-nF1-^*z2h#)nH-{J@`_1LXSIIu z&TgQ_;(S2jX5Lg+r7QQ9l*Ffc_%iBt-GK5j8Ij53b>ci z23t;m&oPtgYABc|%y(>H>8Gg@S*^>nY<;V0$@7iVPY;h7Yh0*6LYMmPMqJr_T$@z* zvKICa0vR&XwIG~RD9n6Nh``@8l#Os9E=NEswdgDEj3|&TSg<0K z5iTPy7UGVKv>)0y*_(Lzs&Quan z10K%1#r$;^KZao`)U}~$;E*Zov4?cwqBPs1uNzU$?d|!_pRNSsJ3L{V-wb=r%$RX} z`{+Q~W(#uP@#xiJ>3PDjvTHBoTQcVAZYCuYBh_PI`+Hw}zX7kQtI0_)`!zfWjMTzz zrelWKaN9v|qWAp3S`OAG=5pxh8A@k)q>J4;52dAq#6qgY{|3{c?!Hs7;R&9P;9o63 z74$h}jxol79ZMo=92W_K2hr5%jM!k*R9DBss*DW*1NF(eS!;wEqLmRX1_nWFu}BzM zHR_uID*y=JfkDL^vv!!lz!;>;H!%Y{w}AAbi10aG%voC*x5V@PD1%C_Qto<1i0DLdT?_E1VKBFE&s?uxj(VX@0e7yH2F8R^gDH29M>G-53 zrAM;$T z6=@=>6EvG~A_i`uv#*+E0+o$98Hz-b3;U*cxf5Ph|`*fHatC~ zB)%6cXn^n$#!AckkZ+n55@UZDLTj$RCvE0#b^n3g&hl<%O=4$3mxsmXz>wqr##O1# z?>xZJAeJ?)e-(Yejx2Ham(_bI#{t>dUw-|FCZ$GdRIBFHZPN;f`+!Y>AqvYoYsg0> zf|dpe!E@gH$5Tj~(u2QNcgdDc@*^0lvJI0>ceX9thPWOO_jMAmgT+e#X1yt46qmp5 zz>NcpNFu>5I|*@GWS)hr9Gr#q!TpXw9xn_t#-I<;BbB-fRhZ$lbeB$s9P|>%xZR?` zkI=hc5)Vi#4|{Er(|Eb+-!>sAO9ID?75O0;E1}TdwIb^c^YC!viA&S@s$Zap&bhI0 ztr2zxG|s+i`#+E6`>rYZMVj(~!@wDS z(1S){$DSB>vB0`bC#UqCzEv!{efn9F^@Kc)_ydN%tk9FVsGtc8nylK(Wb4ngV0}}kuz61oxXUg1b`(6R{c_Uu=AnH z(!<6!I>*h$q?(Vnk`4^Me;+bny}7rs*{8(Jq6Lt^NMcji<-kc*_dR zwcB;sqS^4gP2?yCsZADY{Q3Q#+^{8n?vpscw9p? zAMP`@448R>jO|=n%NFfOP(G!4YD`jKL}r@rB_Zxv_{JnBmc2g~0t+3uPg`pq4s#V$ zW?Wa${3z8$D0uW<`5O=uNPmn6bXKFb zd|4Yy$%1ZW$Fb#6Q04Pt3Dbd|;0vAMsToX9sg1=JtRi zrmu~eS?CDjiB|q16Vw@>Ntt7T(QR&0uGfCcufOPjf>b>pQDG&%K@{j-YSMHjj8q!8 zf577QYIWtrik&B4Y59~q zRKRM3wAUl*Xsc74$DerRlM`>&Jm^4J3=DRzJ5FHfS1g#8^TmcnPef@2hj`VM<9)Cg z*+R$N_V)RSlOc4W=XmzwaVXk5LyyS$JYb^h@+E%|n}p1xn(h^{c^jez_tI2pTCreM zsYfS_NjLsYvqB8VNY&c@UhnvcZP0RKgZzEZ5BT|s3*)~$q1Jp|!aiIs#wu@A&auCA z`dS?SDOpVX(*;<*|2)S8rCj4Gjd4a@a_Ca7X{io?g{-UN z+Do^pz|0ojDD+aH*|Kcf1w1|$0tjVD_j-_z75zpRJ{)spZOCRH@N}*`Tm-lcwKC=H zTSOdutt*Hj0BLX$#*GkwOn!A&Kc%SCuTekr2bJkN^I&Wi3Dyeb9V3&EEh*!zb82Y8 z-4MQVLJfXbfY=cL^qQ$#1FBrXyX92+_ZuNf#qvyXx9_7v%^f{X-Zq?E-HT1U>Z3RBIO;vzzb@kj zSiOxvZ^=rq`Tf&|ksavMc=Ql8;jYF0=!>2r>$(WyoBio!P5N3zcLgS1EvIsB1X4M@@z#zWNZg>Pte92b}_2$UumDb}eLLWfV)=*Y5wZZr4 zj*|jDTu%=ca1*0Oi*oKyBQ#GFj+K`q@NlXLlmRlbq}&@ZZd{&O>H_U$ukbwwi|EmcTxK16|#CkxixM@2G!#d<8nyad3>J@Z(VzuDv41CdnF zt<74-#86xm^<%f;1QsU0^_-6*cR91tMPAFc7I30dp@zdcS>Ods5e{cZg*F zn2hJ3rOgbq@K)#>xuR#G26V*Y2mgPuv9E=yMhueXbBC7>7G z4L16it|2CKd^e@lNDOyXXrLky7*m@B%Wwf34f9r(MScEZGGT!tsWlar?DV22!X>^g z%mEc27V+`5hmvPC>x|*k1&iI=Bn66=!2Q1Mi{08?nMe;>T_V1l z@=mUbP48dz6xoM5>0*ktROWSVz5&QE(RG6<-+5-u%tP7R>_vYaX~2QJ$K0x~Y?<KgR;b3tWEAMY(f_41?XN)Ajgb-nr4lrM70J2OP&=mZJEaJ`#=Pp}= z(76ymsdxCEr#RGf77n0(B)9KU`WnRT{ssMS_{SJ56+m#-GjgRkn67kU>8TTyKV;lI zn31><9M~s-6|M^Bjt)TKig-^xW1G^VrDL3JeyGB#!NV>uf=3k4d9#V(L4n1V=mWeO zAajhyNwVZo_Pvv3KvzOm{#-B7&TnkPq7Abx3DeV#wBm}-h95kRv6c9zr0}qew{XkDqgTiNqvgC z?$eK{^}4y<{~^=96(ttERpF`qc60csXbw##(g!qW@(Z9ODSDWB9C+FV657Bu&To?H zH`WhMqga9r#YBUS+q*or(kn*Fp(b7V%{yKBy=SQfvpk5Bz4(*+#hJB^3$fhO+|;Od z4Jn9TbS9`1&iIY{t)sb5FBUl^9%t`j?Sx4c+nJY|g0d5tO6Iwl+sl|;N+p~1b!|Ij zUNx3YaCf!nKa4xraj=``7x7(I42< zb{wsASV378?Q33HQu&9E><3%BNY{1saMc4-pMb}+x+$T5`V@D4HxtwhqlAA-z45G0 zNcdTsk2>$s)GH)Wt{~Fn14yzDPevA61)()BGMS2q#t_yreOl+!elyZL*njAq5NDQV z$4aOMQ>9!s`~$n_c?uVskag&`wSB#6A3*3Vg8UjW z=&JW1Y(Z{brh4|!o%lkb-%+pAy`fZ>4`j^RfM60QdYZXi!V(_E#8JXmC;SRhd*uS~ zPZQL}S#Wv89hM445UO1kqd5Br7axzmM(Bg|KTmt4mt ze0_5En=*gwY=JUqRs_A8PFewQ5||b&$9{%j_a&iKR(3oHEKdOJz3Q81e2*g9tp;jm zUgh~uCw;|=XDa1_&CGw-`^X{!ymZpDDLOJy8wE~2vd7h*gXAJ^R=yKYAFkMsR8B-K zi*YK?crh{*x37(#bSm7CbRH2km-wrRwRD}JzMXq|QT_`tU+vXJV!wrxhkX`EsbC=* z_VYgUv@21sUUzlgC=P|&K~#W1?MpERTgaEW{0XzlrSAjPOGhZai_kn!Mgkr%2o$R^ zo*8`yB^T?fIQCf7RdV3Aq|T>sU}#N7hDtqnlm&mG-tV0F$2es~wA!E#h%Mo?g*522 z_ri9U>0$&0c9qgnkTH_=(pny8DOXj#Oa`@D4gs?Ru^ z_NwqRLOFxyF^6A$9OyOqq`j*RWaI&Tll}02IpWH zX~J0=6n2e(Tf#A?>0FN;*J<0r{~{xuz4}i0=`7DfDw*jp{(sgpX=Aa6{x|^n$-qpU zRxrpY7Hg>iF}%NfEWiGwkHF1Bh2FqDDm4&pza1DymPgztATS9qMBAKv1Q=4B0Uiam z&mq_Yv^f^7Ik97PH#bn|59)$0lw`w~yQ$cY*Zz$;7G-rXZG#2VM=NI6kg_YIDKk{{ z+g%(9Sed-03Onqs1eXzwwu>d%Ym_Urt4H!2LOAqrLdOFMgG5|ae3)8It_mO7ZOka$TVO`~gS zKY0IL@B!1k3%0u7{Y}IYB1vxczej!0zcAbcR{ly)I?8c(H{!wd&XRc#(!)&kQ9eu$ ze9Xe%jBo}|B~tUQqS7k{eV|N%Sszl~ir+X94ydI!E^${+AB_!K*D%wmU)WXQj_OSy zn_913CsHcBx_@m}2!e9-p84B05}JcH1}AP?QGsJEkfSy*@d%1AcIxz&(+sY4^YQGy z*_>=JId;30>eH}$vtdWb$?z8XCgwB`yQfcl1ikn0fSM^Vdp$H$#K7+A}63C0fW*2B0{jD~Nky7t64 zaO&FwRg(1=0Clkl4bvLo-*72hdW80BX_2?gg#pNzp59$P*e;f@PVS8s-BLXm*gH#` zYNy$sPcz%?eUXN0d}?)ZZ+qM=Au!oKDtN69MixnpV-s&2@Vz=pf4ohl{|qErgSonY z@-3O-)kwM6XwR-53Bvw-Bh22Rx-8auWyO->N3%k_G3b@Jm3Rs7#03sPGAww+x*f~V zGL``JNe8cEE1t%9nkoo0bOJW$&y~i{UtjF(K{NSex4y<*`LO}2tQ@-=xorB)!DSTb z!E_xCK6!IJf*s-Q=koIAN0w4zG7&cbM$~N2^ry80ae&5<=O9Bdf0NhiYp(AdFGmJQ zlU%Cm{4W-Ld!1<-{f3>^*HZ78@>vc((>LcmJM*Z<*C0~;MBzRW?2LBzQCuKn(mN9K zmz>Vq6U2NpU0{4x(ycF0AB7g$!}y|U4v*}z2xH51Tz~*KW8NVZ=9*M2mhPPq@3vw) z8p*JVPID_~0Bk-px82qk_FCH^$5bVr^;Hlb(Z4y&cm^ONBNc}@cXj7x%i0!?Y07%{ zaWG0pVfvB)Q=;U&-#~d38lyu0u9fa3;W`&m zM)|HM(qsPT1(ysoC($hjJl1Yol?1GA39ssw>vXR$F}o2E0CD&R6lzAMo4-lUgTF3<0oImNPNH2o!M?IyaZwvA zFbX?dCu{`^4wnqN^VTgG1&v|Wy9kX4Z)m~T`)BjCvdcjx`4ETN8+gtq@{MlOZ z_fd3B1GEKQi1|}pXBUp3SY`$M%6s=kG{BWupV0PO_3ceo6FAsN|{ z#4r-Ql7ddre+d4Ez;b*<`f~7_)0oox&)JXdzPRd)&`iSty&o2$?MAWc`OrVfqokap z=d+*H0}f}eCt>uc^-r3unZ}U2lfAhk#sU}gEVK~Wh&@BFcNYE-<8m!akLVLA-@Mm{ z6zPk~u&=8<9Yb|y__3D06y|-L7Xzh5q zrXIUv&Kci~^0}3x@mLgDpQ~-1} zQ4v)OiP&jMMbYR?FGngck2Fw7CHyv`A##gAl~_uhtt!I$FH;PULL|2nF18AGEE;~) zQ0Ln0SR@KWUtMuYWqZq78ck>nH+53X!!u=K_y^}_9FF!j45fWAdSF6VKq1}q)bQyE zXUN7g+JuYkf!ZFwFy{mih=H@BV`t!a3=^^0Qdl}L1O~hhd?Zo^Pr|FB7LYcHGbk>l zFl^T8Hn;QrDj#ie$#m#dh8hLz{{{S5`a_gbPbf(|ax_l7+(-nX&xdHQf>+#JC5TFC zFKIxLs*<6Q75uUj(C}K;n%Jc?#T*zR-gs>bl2MFL22bQ2LU4t4MDnA_=Kn5Zf#bWG zb3q(X>HG4WN-F{d;+A%Eu&EGOvk|-_dMITuwoku^FaaqcEq^R^{e>inMgs7QG)m-w zYqK{ylKr@zM5l(5*udOzXTK%T#uzhhF`8>XnZ4xEqCFD7h(B>$m92%Z5T?mB?c^vf z=t{C@j&tzPXM({FU?TH78&qJ)+MPv!m5+x*2R%N}LXVwt)dMqMJfA z+cuv0RveOB-YS};%kHCO3XO&F8SI*~DUBbrK;9-R3FT{^^L`YV`V<|PGKojAhSKjJ zMtDD2Gn?vo-f*7`%4f#VeoDOKs#!36PfBB2j`^d4B+KrdMYT~@w&TV)xA-&kz+?J* z#7>|tXz)1bJ3h^6@N!~bN>Sqc9-UJ4*n~;fV&Ct|tFbVLY|=Sav1W9Dsb5D8Oy`#d zN<|^!4>9|%P2|Fjl5jr6vg&pOn_BPHSU6s{C2eEFY!_}X2$V!+6Q4wT#*S7~ck{@G zcoB=rws-v~(@s0h@I}ZJAc!~~G04XHL1)S53vb9@cmMg9JNIzYib==+VcoR5Vo;KR zsW#n$C7>)8&oP2Qq8GJ7BqbWfr`asp1mOauA|;P+_xy*clIV6OQyJH>b{G;a`i9gS zs$83mvg#X8gn1QrbD#7#xW^ejmvz;ag(HUV7cHZ~pL%s$iLwJWR07@33NKay`3}G; zE}7)H8{onijCVeUV<95|)DX;fiI!=sMA{)Z+IAC?K^>B(Bq~VX1^3`j!Vp7#-;KQ;Qs`)#M@82xJVfghE#t{t*ljT=Xcmii6HQkChm@q~_5+})7L=x*iY%r5){_I8c~dk8@~%?7kApxDgsUp_x(G_H%d?BwC+*q3d^j z)PK~I=oo?c(}h^%36I7=&^t6QQO!mq&W` zzOI~jTt9P44HR~x>h}a1%L)v0IzF=`Q zzi_V@=7SR$dCTM6wB3RZv0_iGxm+>_Yct5O-h23w`c*e;6x)xz`Wi!Zw)1$dvDxvq z1e|YYt3v8GgRJtD=LvO_a(pY4-2`Ji??wLKG{kQ%>vaq`JQfg*YL2*0FrXn+D^n7w zqK03B1L`ViTFbXWkD8`biDTBfGx)TW7>`etossthdx}kP`hl-Gi=3^lYmPWW0^sa- zc)%DG5sBp>v@a38xi6+*O5sHA{S!8-Z|M|qqA=|Q!ta$0Xhw%l^3hUeWhkw zp#Cz@qdGEe;BbcdKcnTJxtp;l_*tkJGsi{_0YaM$+Pji1|IYc%*1^SEP%vw4GY3e3 z8brbC0iRu6Cx7H$3Q=0l5x5@R{QUXTYwL2C!td6yc4&3n$){gaD~g=@nx75sPmbMagosuk|KamDy<&;2r^YCl{u;~IvAO_!L)b}_R1C3W&`X8Yg zHLJ1&$9z(m5LvA-P_m?7#!)&AmXApW6&D~*4qm%0X?z?;2c=2M@A1uDSjQu- zURz18L{KixmZcq#i)O1>0EBhtA>h;2@v&aSIB;6vJww)t)Z}(h5`ni!uIA@f5_6x> z^lOqTZ1W1iTt+4oB`3D2{4J@98LeK(O}6Ry$kPh`bX}!(>$HBUqtU^{BLOH^uBO>f zVnCP@WY7M7Dbnt+T}C$Tx|8Yujbq3D?pv4+{gQ?ja>tu5-fdV&4dQ*=ke0<=FW^Yh zOR@xM2ZlMmNe=E^0BEPpnp6B1d7m|4bz_D_B?-j)NBiN8N>3a93~2M8tWq8*E)V(= z4D!WTy@U}GqP2c!`lyc%S%Ow8yS%+YG^`+-Ailc!U%o+nMpIziT7gzYO)z;i+b3^} z7C9%T3vh^seVyaM!EBjO-?bI~bIBcXl?H1c^?1Nk((GPY#40CcyPOTcf4Nqa5=V+e z<`M+jPm5;+`J`8;PF%mtDrvgMA^;{+Ki$RQzV){EgGa|8=*}6}`JQ5QFiqhx9ej!N z)v+kM#-r8Zz_4xkJ>TQaNfGAZ$O!_;$L&p$H zWkgK!EGmLW6-8w-Rrja6ezg1j!+`=jgNNIqK+GLhcKwD39@cYV;JxkgsX8m`1)yk| z%bPm=y7$ZgS!_ScVT*Fm>XRW|+K?T)nwBTSb$4S(Q=ImQ=1ehYMZ}#!aulfP1CWk! z1`?ZVpZ1ooG_eAG8!w=jgh1)x?I4h)0Zv331Q0V0>0kynoWM0rE@mO_VL32(pwd(C z@=SE6*i1;%ce}}+AyM+$0sr58r^&Ire)&|5@cAd8>h+T;ma|V}{R$sDFypm2si;3L ztzR{7bqX?KVLL=_LvkIGy=!iAY=fmjswb)2l=s~fh{Yy0UFvh6?~Wt3!V%=K>uF`Paddi?AJihBJE zm>9NAzp?YM2p`Y886^;>7ajt#+|yz4ZORxft92xx`}-6txr)Bqx{1?wbL9CxCdRd) z>J6=_qbvG#UlBn;UfTN#0O(xq%Eh>2!Q(CAA)E!py7%*cm9W?HqHs1arvD}h?aPHH zu0`ZuQlxwuHN?^({Qrc$>jDoPwtPUdz`+#{{};@a;%n#X{wWZhM|+A%=os73z%vS# znW0k5?s#6kMpdiIe@9D0r+PC`FiL+#PfPyZy#>5mZEXKbm*Rlk4i^OQqBqzMc$lDJ zgiI)h>fW5Dd@<>n5ij{TVH*f8#G5%8$SwC$`srOaWtUWa(WY#)QU48&%+-o5+_-BQ ziW9a3;Ox65ifU+i77IQ`0FrKXWVu}HmrT+H2kx9X9maq{_k3o%omXbk0Bt{pM{^1S zpE-j+f6mM>=*rmNZ6#L8CI)gJPyz4!IH%=?4oZNFK#RTX3_=H}tf(-T143PU?Dp1FLb#G$-&B z?)`0NK}9clT^(Tc3y;<+KxuKNHU;rg0`?U!@kX;qJ(R!g@9vP1it^r`XXX=%A#!g0 z>8T%|K+f>@+EKBK#0E`I#O|Iu?}^kCgDg^;46pape%CtCn%ekhJtk#73*+oz^xOIZ z}X>%{rUIET!^PYNfQ(t0u4Y5#FhG& z$!9{1+l`AyC%!qBrC_+qJc|2p2O0p)$sMU~2oRnlIhqaD-%$#uo_XiS2ANu1SmZNW{o3*QZizs%kqh6KL7UHCeL8BPhJ}`lPv3s)*N*nZyjiTL% z#+atP2ovej;=w>^0>FMC-hGc0ym5w`nGn!0V&RQx+_t-CV@-TxaQL+=kbxEmlWGl? zI^i!T*Jp?oR~GfJKIuPVJ=6mj@xLqW)MBfZbNcoKRsRBHz;SH(4C03D88>rsk>O7^ zDC)96%Szw*D|poG?X}G!tJHa&Fp%q0b9_m|hT&oT%+B**{lq>5szXHgRnYtAu22p` zzO`LG9nuGV4!7Jdk~X>l&n_rq9&EH)(}C`|@u3&mZD;?aJJwV9LC@o}f6tQkx%+?}{VgOPVFldQFliQ)NEjj8N|QBZ=pUa>c_5_g}bQ7 z5Pt4>2yI;@_eRAzO8w{tGI3z7amSi~Da2Sd6)5TS(bghqgBK@cb3MEnMYKMOonqmL zx+wux@oH1QsR%aB$rmGOpr9!(j)c{{3D6^OgTyLbveLs|t!?qupFg(;H*bGb@dpko zS3#Oi3yv4W6cQ{iAZdtpgt0)zXul(A&4W%muU4_!&Xz3r%EkCDJ=PzwGO#roZffMn z5P&JUz!2cSbMNok1iyU&k4fOBcRk3!DlKvg%4G{@JPIJsIgYx$R6$;Wp7WPDt zFTO5qeE*d!2Gpp5Hisl4T5fh^p@%yx#=1n3Heaa*p^2Oa^vdbRcfD?MpaikoCGj+h zRadWR>(m5%zv_kt96GtO>|;o< zr)w&UP?)c!-o=LO@8xzs-QPB;um(pqV#xS+8OQ@)S7aTSDr(~~w^WxaZ}0zojurby+F21-(G0Jq0#!M!NkC@dje}X24ufULZRrP9p}7v{?!Zm^JV{o-`zDI zJ>TD$u{ZB>%$>t|W;b7%l~hn4D@vnm!q?3|bXIbNFYs#5Vo_GO&5n5}?ryx!+@l zfI1y*OeJW1q!sH$%2VqoOXG3^a3Og4%>~KKs|IBM2k01;SkDklcCm8@Zyild$|B6b zTo2(u<(OeSEa*SZB6WZkA(7Q~4UHK17mF0p9(Z|Jc7Pt^Qtrz;Ahg}pgahM}=)1~# z@y?h@tmUrl!>_9S}`I^1ZCr=@~C*cThd zZ+@Nm1e&F(>K_0LQ<9$XI`m`pxrpy5Hv}Ck-&whUzrlUJqf>_j8x#zf-x_2Te2_56 z2HFf^$qTAHOYj<@RJlS`$dG|UT3t7F0!+I(LRc}ejGUbqP*~a#1ilR1o)@&%g0!3Yqn$-%R&wgk zF(M9yG_rZn?GKD`ziXDdRNN+Uk+arN7_z_G^uO^ND$#OK0$meTsTq>?o@rc}4v#z~ zDIzO@qAg&${i(q=z4;p;$tH$dF4hAQ?oK;5MnL_-x-kv%uj5ULiEToo0T-{| z{GJR7S{|^0+o-u67Jpt4<0cF%N=&x=Zu!g#mTm9kZQ&g%OT<1*rT8^Me$|>&EK=nd z4kAEKqqGdA`Jzru^Q&hchS_7Z;@>AvT6S;hUd1_LMzlLX{?|>@@`KmSm#j<2!TB~ zP)GdQz5ivI71;n2U*T?lpYm9)u8-JqFSTh`bik<&;}O8bQ(gI)n>YJ)!4?i?3@rS* zQOjGl{yiELq<*?%hALnifx=}@05--3xM-rHJ>gpb3k+))-A!mlPA+8dNpIw_1dHU+0|AAnxo=Q5uT{ntPnQKaeBi<=Dvc4fC5ALw{S*EJMqj#hZL z>^VQFBpVW!muS)sYmg$Rux;;6=qCwN7lhN;gvh%7s%W0qS!%!ip>vN4L&hZnhlKBy zZlV{a868wpJ`50>*Y}fUuBgv>!%d?`x??=?k2wdq|2`Bk@o0>p(&Bf9vM*}0paX<* zusC?y@cb%2p|h-_C|9CrxN~j_0`P-StL{O%Te3n{!TswJpjK3No0A6pLZ2x-`gB08 zH~jl`P2*!wJ8@>P+jHf*czOUN<5n;k>Wv&Kz)pTMt*=3!aoT53b5)po>3DFZ{o&mg zM+*RDK^467qf~~OVS+K&#$09QVT~aKv;+ejqvj_XqUPlav^3PeXk+YX zZ=OVX-ZlBdzHCQCHDtRy3b4N4uRm+RSvatFBIdmJNd93bx-~i7c>jL`RXy=vRjRhQ z$g&z?-gA34#0`7rY|FL|&zDPsHi%0j=0i+so{R-wcOcN>wr^hf>0ZouGwMk{q4n}M z1{It{kaq$ebRoi&O!#u4ck4>GD?Q!ntab(+BgH z`EL*|f0DS|*X?o`^Y<5)AOK8&{HI+mzvMadmFXw8AD0z8V4f#0}r+E>}~} z=Kj+8*=JHVm+(iV=!z3A-Z{#K*k?s9YNn%#g=1rbCi!-i7BU?wf`xV!X#wz1ojr^f zFG)XbH}2isyggaV!Cv7$t6e&BZ@k>>9dRF6SoK@$cKdnpXJ=B+`NNA-yqV*$e&_j- zPch3o22#xd7o^ViLh{d#MdeQqX6Me;KN;hGUXk}>632DH7xBXV1|7~H-z zl0F=@uRpJ{sw9gwH8t~+i4sgV*tP7G@8k)__!L6TH7>h0Z5kUI zU^|;-azfu_Tgej0|GLm_t+Z3blz<2+ncF8cKnt0uD(*JYESant*uF=d^f3FuhYk~d zmGnV%<>Jx(y}zgGq37f!OrHFp5OiKo*T^$}6sFsq)J@1ifU4&-eAG|yDyaBKfSrzL z35@S%5Wmf`eS(YB^MD%4Sa;T@df1ODXI(`}iO>^@o9O(4f{K6=r!!q7O%O@8VCJv3O=0zh75(=s%jg#lj>fpdl57>TpO{>co z@tZSr-yL_G{OsMzDtjDv&!8H5_Ii57^03XHAx&b&g;3dz<8#V%r&d}P)_3&n$Vj4F zu)WCsY>H&Hb|iw^T%yQd-(~v7@1h?`(w~12gI>?6e@BCJqdPj!#Dp!zxca(}Jstn) z!1Kt=Q%QRS(IHRqk9)>6Z1JdlK}<=tx!-h^z`SA5`yZU-PoczWA=1$F{JJvikbxug zQRSMT{coep7Zv8vsSII0x}lH3Vk5sMjn8ba^IRgjcB$qe@#==h8us$6TYCtZoDS*^ zy+c~+_?X?p)Z+=Uy z>Tlh!GP0FS6IvtP%p$qUscjU?w;#_>F}kzUy(r=|&o^2`2Zxe)J%(*$ReaH@(@5Lx zrtg%?*?4;wYVA-7)#ax_8UiEtPB3=?vFF*NaG@iwcx>PG%*y|rvHAX_Fp={lH(J$Z ziL_Hlr8#_8Tm8C?vydvc+67N&<(X!%&Dz0D=&BAMjabXai2j&5(V_2U50=1z#8+S^ z&}G{=9(GqX1Vo|tV-2X#z~|0HA(Na`f9C`}VJvE7>pL6UR(pT6jv6MEBp!2LTW94m zq`2;8#+=jcL(JUwE8g7Fa875dgwKTEPFKc7O;qpXkTmmG1nsCP^W-Ex`iGX^_uPN& z(oLwr)>!?(;5(EDTSQhoLoD)&)YK+ozvhrdcar?9c_Jo^ z@E&tp#6Cw=DSJ5?)c+m77cUfSl)ODW<8|e0enojN_O#f}*ktRq^V84Ra}3JGmFc~^ zRR7)Elg!y6SjNdsZ34$rEXorROA2)Mv)+m62$t{Oq)0b&6(wtZzhZPIbr~UnrepaV zzMpJ1(037xL<-t$qD9cEtd|Tm=U#$9Xeu0>?fUcanfE3S?4?$?$OMIroZa)X*0S9% zDi1HKiq&aM6r|;|-B7?0kPvjr-#htjpfO#lMO+QWh?>(^8|p!KP0Bm{9uZc*#!8dd zoHJm?g?L&mBZahw>wLk^9D;wXTWN%dh7J4*-T<@4AiV=KjPcMo_TqWX_8@F?DZ{X)kk%tT~k$FuugzBbW1(NX3NCqz6D8>@!AVZSu` z7@ef1o`y_*TH->DNXzt6l#d{xC>d4a?$ESzl(iFPeq1$hL1!s*nZ^c z01E5PaDR-aiyLqBsCCKTt#;?PioTZ1q<_R@E>en^k-Hcw%EL*#=%coCcC(l2#LPlY z(IJrX8BV~oYX2HagAev_7YQVT_+ZkYqU4%=U|Pea#+wR_@%;Eh%*tfx_P^ta-aOoj z-yWP&3LUFJjLFHRyYBhqLM}YTgK$43<}-aF$H(ZH8Ez5ajq0vRNx;M(d<`$i!xft5ZGD{ zkJoZ9EJ?e-@0_nRdE9;_0D)YG!p4bsM)GDQ%2li^I8W{PXPsNj2cm$@EY#6zd+Jub z-3YdqVc>s3#8d8bADdB|zD_c(yXI6z`SHpn;{0aW?XfGRwi; z`XaTTB|rnG=Md6QC5v5oyIUhz|GW816X0Amn~Z$G{W9y?3Le*}sr$^xz4259cHXP0 zUcAQel<@VyLx4bpj^FX_{o0!QpVR8lmL@OJ~1pHRz?=ikix z-ArCtvuAu#G3fm@zVG=LOzaZ`<*C{37O)&%ZfiAoK*hE~imx6r^F*faB*B@DweP!V zGr%_bu_=2D5_~qh`yGv%DLF>3)ZvmooL(W^9Rw!-J-|D4$4BQ`-Cfitd#U!lG!hN4 zrtfWc>buysw^2=OIQ|C0WO4#M$(8{++Oe1h0$h(qymLuYHyas9cq+Ff-wu?_O zW%U#+G~H*_!>NHz-E}MLyqD{-OOnR z4v$A{m({WIRBBfP9ge_TnZ&FUF~%4+ayA(ZdPE9^dl0KH>R|u=j7l<;grsDE6W{H9 z;CL>}zQ?l@i<3Vx@jg91pTFVN-_ts*tY&XjX8`i~b4I|NbZY%=rA9MfQL_0*$Nls~ zXJeII^Q9{>p$4cSmxZ1{WTu-$6kNw`Kq&55$m9MSBvw9vp#s)CFc^bG)_Q5 zs^KAE3HyOz2t%CRu_LiFt9@?BHCnP|@nA@o(t2pGu!?&#&cg^jV%u4tT~5n)4hqaw zTb-FM%pVsl%xO(4TudO4`<1_%gCP)CitP4Ol{FN(5W#H4*{ipys+`+=jd>|KKaDg& znDjr98b$m{9SY7SLAL+~BVj7K3H(NOmvEj`^;7d=Bi5K_X5?p#9ucRTn7^Uc?>D@g zO58Ia_n8&pG?7l2>q=_Q6lH6wh3+j)w&vM!Jwyf2@}Mv1L6FA17bA|3apgu>9iH|h z+uP9@XraXpr#_73C(zJwUHtEOd5Dka$0Uuy>hWDLUI3U`YA~vHp@~)7e)E^a&sp5W zx%n9Cap!8UWBvfOqmgJ^8iYR08Y@R->@GBb!W${pw$Lb!$Mb1=Y|pNIC)FieX&~2Z zN32RFhi<_qv!i-Zk(lNHgOStG%Z^Lz6>epnjkUGm-CTITYb>`R6(6z?QwBLH9;^$5lO8;kb;t)e%M`BPDQHfxF7Xn2zB{>JpX+?khS7tPZleY{e>oP*YIL29YrOj% z30Pckw_C)?X|!I&{x}v3RiDcn;At4oec&K%Bd`d)Gtm^YGRIW?N}DxmC&x_DPR@U@ zFH-0O^-#b56Nsnxg1w9pdQbsnY|=DE1K)LWT|?>)))Q zldf0HHyauEf&!P<5Ft&u4NVeV+-2(H%}pY71fK>=S1ltCBTg=g$xVJ{rbo56f>SJ? zzf#13d-JqMB5({pHY{SwSmIzcrcuKAx?ESR%;Ryg6g4GCq2e*|Q%MfxU~h#?Ekb)bz-jAe>xs%IOc(GE`Xpx8@w;Q*_%;4BLpn`2e*Kgret@87)^ z35yt)ceiqlCAMKR!==9MFB3Vb<+d!o=9!}Hkr~#+ctIfh@cWMtAU^RRh5J9It^%sc zrt4k>0fSHkX)s9XmR7pEQ<3g&E~0?6q%_jq-F=ag?(Xi+`_Fy9*YEqEwbbP@?tNzF zoU_l~duHxjR*f?{gf-Y<=tWivZeA7?*UpkrhrNN6r>uz8PsY-q&NJ6$SS1J28;j>Y z=wQlbP z_wJLvArU{p=L$=rn#BzoY5R9ts`d3c0GT01p`otBc#ffSGYK2@H%=;47Sh~8m18pM z(qAwb2G!0a=Qi6-3ZZ+(W65hjMb=<9ibvilG{H*@f!xB3fVu;x5ge_ove}?|E=VwX5x1*ZxtdJ zZ1TW*3cnF}PTZ1Gv-l^#TW;8o8ws+rZWG_2W3AUdUf~oA<>mQbm^^U?#p#G;`D9xE zN`vbU)7RmXaTb*AT-7m6t`K5(zMP7(o(+QFNl6I=RHwy+7iH5N1XOZ2@bT9CQUi0b z;r)=;emTr#D*{*ly!@sc#L!yW6{4^F<7!v|NPyj>XAtBBOb+F(Ht8rtuD9gP49z@~ zE^(9ablUmBigROFD&zXeXKc@;*o_Mmoi_yI5HcyDYN9y1O)&&fQp&_t>t1_S5gffr z8Z=6NN>gN|X!s$rL<*Fp?a++^NnI@?T5O1yz}VEJ0V~5?TTyyScR=_iNH|-SRaFH2 z=$|(a!{TNrCyfnl90CC^#2oi8oQ0ray3BqW;qB5_zw-)G<8_;3OguZ0xa>`mCMM zhT!wByP7REF1G!zy4oZw>M}?7HX#B6adjmhz|>Rmv&g8Dgr|WxQZiS%AbOKDPA3xR z$tzCDSMmXrs;PfgAV#nm1Pdi~MyA1j5G|3Bwr$8}&jnh?9?hn~1q)q07Pl&x%X^E_ z#T0j4b~t-_?Npgl9)d}E50V1z*4SBNm1q_mKMOEKq-`AzJ4$s-fZ*HfKht5P`8-{h z-S~L32uF=~miwEfFBU;Uaa}HzkG2xxH29oZm^`O>?ziAO1kbE!bAPuY8lShK7*n2o ztzP%QAc+pQ9yRq<0*vJz<4{>1x1OZHcU=8%>TdnnPpJ(^f>Y_x(TN!$ z$N59!kvg-F1$`lX;Tqeb5j z(>ouz`6M8ck9%X9n#o_T}_`t z(Bo?oYmYBHYgalPMC|TC(1bEMp2I{B-*;44x)tSRu6~n#SUtSRcy}d!-Sijb zL2j@x{7!cIeRFhO^Fa?jEPjbdS6S1!x6Db2fCLLN`s17`AZ@W`_YocBdzI(0py@ZL zmE#)fs94I&uXd~~R|Gu7e;&rHj5J9W5{7}&c#1sH(#}$w1Pni&dh2Qok6*$)fm^hM zo%2%s@ma`3x>UKAgWz_+5yX$?Ud}|2jyloB5qRvS_EB8?vx1uOpy7767dfdVv;Qo@ zJhRP_{0{QCifSSJhw^buwBYYc51-tdeNKo|d;T1>e0??M=@?M!oamkWihm;ciHg;I z0kj^Ola1wVn5GV7ZuN9Cb$vW{_J9Ium~UFA;OL5dx#oq;R?5SMh@f>)7L94p`M*g9 zhO)-_H8UF-#2)qzix^PT(euo4bYh4r>Qv#S#Ug0ca}*hgzwrBpv5I6?l`^#VWZKy> zORz|XSz*$D%t8bGIh`-&VpMv}_kr2x&j8v$%Ru05S;@M|PXS_18@L!Zc+rtwn$`pV zGJFuS`l!*0&2OCr{CGSRLm5>?1ZkimOLiVo4sWxhzILGxwVGC%%XXV%7>R76Re=SQ zZtfVVZs+s|R)93Vm!qC4s}Y2#elD*rTp(UZ6;+MWvK~75_@PB|Rl3k@eG>J;YrdHj zP(MZoSIgX7VZx$2O+~D;@%JDCjLRHU5HxwkD+;p?x(GHd%E6v-(`?-GHe7y!b?5^loZ6dE6fl`+mhn1iNj%r9A*O2kYN4(PL?DU&;1 z0dV{4x1=$dvX19kZyQ4p?ess7K(SgyozD6n4Z5QKsqo*u->4eSk4q$i91(#T!)MJF zU4ef=0tiS~z!cI$O&U;U4`Z1v6S5SOG;;jb_lE+OYJX6>CdT~CuQPg5>_z~=iqzn) zcZCZ2Si0MlQOwneb#b`=dQGB}%RM)p8Cs>1lTtCfM@LhI}h(K;IQP z28r=h>I|<>XyM>0|DD&WFX)Tu=!cvw$zqd|bCaL!81gs)f*wIY{_}VZM1f#XWxzL? zPT9ad4tMDHzpM<}WuV*DS>9Fy?G8QNuA!thIW;v`t1|_pS*O7FamF%liu}Y!39ZP< zYszFh6zY*H}Vosw>wW{90qq7t6B7HUXN@7F{I!4t(!=&2uXmr;EQ>SaWwzsx_ zM1pIKQkJ0aRI&H8)05#IUlDW?pij1rP>h%^D*Vn7%p+(ZAjl1wmGmCvH4;@#b<%$P z)k@;y(Cii`&&*?^qCwCqW^{0ydY=g#9X3Rq#HU?P@B)J9{{1|Tdt~1}Q@Wn)xClCo z{9*_TmV@%L=CX4XAcH{0&vO``LqpdEFL?e##)JgNEivh%?wg;Xa9$26tT$ z|JOb-v|S{Jdt^khe5|iVFm>T6LrZ<(g8%`R*%ReOjg%AgZATI4vtll00rn?jek032*w*B8KXULN@tY%lz(20qqBuTn z8eSa0Ho_eIQOBn!s%p&h=CMy3CIp!u^kqPano=9fUjMlh_NFEgs3#%g8#6+|SN&}I z&Y{R@W^x5b08VYKu4d5W8&|r~Kp+zVAcD~DVffjfO_<-Fp0r5#2Ospr@Fm-~9GiKU zmLK1_aMM!X3$^Dyog#nDc9rClYi`bwL@Ggqv8gJ$vf2I=KhAyrQ(YDkgj2vGQAe4h zijdANW{g3(2saYHM^KMC-+0V>ca$q#H(+q)ZRXlW5$XP;F3gL5lK27;1TZ@zhRHS* z#eYY>`JUTKPz!-Y%lasPWZO#w>?vTd7yvB`K)=s|EfSA}V%+Y=f))CIEgkPdG27jG z>DK$i7&SjXf)wleEVAXyF1=c{{_cPb|5*FnLsu~VzugMtF1|-cBWq^Fn0Rd7-3g|u z&0Lf9=xy9-R*etnJ2Gb3fF0geF)euQUiiq!SVn)<_{Q-rn=UxTsypK*h!g!!$aN{6 zySZiRtJyEgXH$UV{3+cvn3jwSX!+N#w7;BQ-EV#Y=r=%&jc#`0rK+wSJZG&KUCMg6O+@QU%0oq3 zDMNpjSKkYv9#!BNfC-6OGA$!tXi!j#zXvxq-3IxYtAMI-_*n8xY)bbDU#cj${EvLQ z_%0`IieqwP@tA*XKV&=02zOV-%x`=zhp0Ro4RAWhp)y6Xgxv%cDfx#zWLMCQFE@Cp~(pG+w2@Km1sJ?QI zrh^OYVarQ;b>Wvse30XUp2p$`0 zG<=-;R82=+C$}}gaJk0sOm>tZ>zp~sEGu>$L(#QnnzXp6akn%rPr$em(hCLY znvOPqP!}M9WfJYeNJ7350JJtatSkmQHSRn+`RcWldOT(}9mp1^R|aYKEA`HHN+xSvH40~k87-Zp0|$8| zn!n2WFZRIz@-}!Qw?mM7|8(CNGDcItrb{ym`Z69CH3P~x4?2l=*`UAv=UEVq?s`c!m-E`Bepyuf z2mJR`Zl2=)j>@sxZ(iQQQ^WKam^eXZC*iXAK|a|}M=u|?_yAOue;%)aWm~S3?vB@y z*bDvUB%BVvC{AQbfw;QMt_7KW%XYy&?aMtZd=Spc7|{ny2?);Q#G)O3%Ooz8)=!%vWd`=piT%NL*+_^W5oENrZenZkqJ{zt+< zCwH|Fj+JpS&0w~?5gYHDH14_`f?^Xd4*9pS+%V$;8svK&4FpXO!;iJXDnO^nJhF0z zNm^C9M_DSJm-KnmSj844CWE4j#|Etw{M`3ZL!D)EhJFGQg=Df8$9r}E7Hz3ZLBMe) zvaxF-=qbv6{MJoP2-b(_7o!CHryN7OBYmQ$OmY6rLm(^i?!V9oPXs;mz7Cs62|H1^ zek*`v4GtZ~k{BVI8%LYqxS;yI{|@t!ANJMu_Zv$`*=09SS^zsi1z4^rUL5@ZbkenV zoNs05DR+xn+5`GnkXZDCjb1Sdm8M{zHVZ#?{!LxL0xj4`{!{TG9OZKilsKQt;&0Qj zaLohwEt1Rh-$ynGB4%wh?fE7~lF?5vTr|w}eEOesN(XtG9|3OE0cazUZrkp+ce56` zW}D^iz4$Ld$ZRgfavw<3sz1_3FGzGXzN0_Aou#bZxU4{+5BFZVY861w>Dy>NfZQ{d z0_o1STL9aKH>-ramQz#4$RLgg|_iIUN3BvTJ@yZRY#~HlA`OX)2^9Mvb{I z@B>xFj-EJUHR`8J$N%2ehs7mBl#~)5!s@1H=3$nFi#vwb zck?0ibErZ@A}-De^0(4@C6E2_ie($drWDt*aS7gvO(Hz04}i z7{2hmxxp_U@>7OZ&=#bOll+Eb1Ya}xkFRNvNtAX*k%~8+-6WER$T@BBC zaPi>lfpNWRicj_45Woj|rIvFd@|>6LUHe0Q}>dX$lgHj1qa)19_75#fKDqRPzZW& z`VArE!z7RdgN$kuF%av#(kbqS+N*s++8%x&mGNEpIQUFu25*G@@@a}Qp5%oC zr_1con2KcS-*T6d26fFh)McEx$m~U+G(=MddhoIqxQ&n}$L!&-XY}Xm=}Hf27z<_b zAZzwcF0<})u5xbjg%p}099Oe`J)LZ#$S*~jRaq^@b6!uzTqMRKQ;OcQT{ryYgBApU zzRab+Mq@!+)=0Wi|8Uk}x}>GdQU8)2;0z?@rN~$;16J%}4R!5!Lmv5G-1B9HMn>kA z3IqIQG6&T_N5r!BzFj9kEv#tEo3F1BMvz+oazzI{#oin`AbA-583}^5q4p31!Y+1D z?Xc2pdDZstwqn88Ki6Y{G7dWHJZo!DdMX}R;^wMLQ)oH(5tII~2ld9W_WUccMrqmD zkquB>J?(%WwB8^9fE!J|B>ofez(HLZ{OoWyjBx<^<@r|UAy~Mer?wE^`%aYU!=!^P|?_OBGt1Xft2s06{D}3_kwNwhES~JKyH{zUA;N zA{CMnt`7a8g**1g=p;vz$hPnwNLxxYxBUV5cylC6MWYhM8K5Qd8c+baKmqjf8CrhL z21NUxQhPZFZMLQfFKej|Q+4*MsOcU9Y;#Qi%2Z&?cFm%0%8T{z?Z z&H7k&Nncz7_hT{%LpBP4b*3)s z0puX(*i{zD64tA2;L5QnfJq=5xro`;v%E!vS82 zZ0zE)ld6=#kIk{?D@OJz9s}YLkXuL9^$Xr5UIPOe;HDJej=^y+v#iWnqc>L7gMLe#m2GB#rcnLU0H(2MRGtj>idcS>r+RXk^ za{F}VvW=FQvU_)gzYs5Ds;CZVPyg`(h@aDsjd@5%hd3~rYH}gU>y=SEK~KUAr8=0F zDaC11TI_=tfKosZJY#o`xrau*4GQ`}YaXP-s3f1?6a(m=DduE-mc6(zdwb`Y$dOWK ztC$+Rww4(O9H3-sa`!RFvV-@d(p&2=*y8XPZE5JcPgnUVoo7B)yj<#f&~epaMmTDD z=%4guW7L~jdM7a-Xm+brOn^%KgBOv(0{d(-n}pJ*RjtWDJDV0~cpXSHE8_<{l^8Nf zV{w?urUk2Lf|nd30C53IkpcNaxIM5v1@A_s>(0 zLC=^=jl2Od`kmhMW5J<0l$t7+CCLT0K?`!|?;-7qTD?!0X|cngDDRy=4hB=r(l{7t zG{Fg>7rn@LL8si7Bn0Ns71oPez)PCbzQvQ?(!cBPzkTuVsw4Z+s{?kO_o~ghE0Ice ziU$Xexbc(b`JdA(80gn!=o1HZaGM21dqD?Z95vS`!kF(t5&RIaY=PVBS%TNjq|U7P zrOo^%EAW}Z=sVnIOpSM0;~rlqW{n%M?&o=!qcIc^>mbA;5SlcI%#x#(nSF}YdAHp1853`MK9J<#sIB%x{)R9iT~FCgq2W=&Fgv^ z9u{C7ONW{WWCaG=+dVc)a<+ongUgDmbsYWA!VH_j5w6CAAq2c-)>W6*{8Usx#-&Uv z>f1~!v+v=rih2Ak0~couuRj6AF-U^B7MqMo!ARp{CTG7sC0Q&B#5DeS&B$8eU^3lk zh|Z`c#YD}Z4$LxKwY`>i=(vj4nRxwL(tzv!&qLNcbJbr!@Z)J-gh&kCpl6sN5t*JS7!> z$my*Szi8{umEAfm*(2cq&p}#sjMI#WOkA1&Cvkg&M#rmi&tfP?wrHdlA-;DwCh8>r ziK&rDo@IRh+V#x@vmY?IAV>@ZV9km^F$Q)LmA%68Za~pYX%_+W+?4k4RT}>{doH4G z@xyGOAYEm2<^qTZaKCg0e_oH)Tew>Xs7L zq9l_#FN+1M0&rzB!AR8%RD1l}VtCzWa*<70O7sCz!;|r*an%jr=VFCQMhz;ix@CxL zgN4ck{eT&~pZJ;fT)-T7xC3?7w#S+NhI$Km>*|2n&k$Bm0dQ1>i1zW8@BZ!ioO+!s zq7(tg4LjG}3zB#G#VWT(9>T>4i#~v=TUNy*Wq{a%tx)9tqPoxtwJt}HQ0obqLN$p9 z3s~9DNW7kQ%yCm^L1F-8b9#&_vB*Lkyk2fE(uK$Rz*Wi018@2-%)G8v6 zI7_${jTk5LaY-^TFt9~GycqV2rx~5wR8F5Zp&g#@&ySz(BN?FI)lDu*G=idi%IrB@ zPRq`FVuUbmm!_!z4T!KO$ltzuQBGivn~cTpiJe&Jf^Zfi*uLIEgT_@#;lOMQ?{b zjdJjc00g^va4)BO8+X}{zolxF)oJ6R^O4ectN+lyk>|C4)|~T|wI;OY!Nt&>?KHyr zl!>I}WIN2yZU#DF3N`DPOhEN;Fpy>pIx#3IN7M)k+^z!KH<&^4%{W1~&6`P3##;%r zb&~m}RSJO9mLtv$6d#FZ3qw~yZ4vkMK^|mZ_BMk<8}s@n>ZF#1BRGC5czp>>Jg;db zn=wfTq(K4^VOh6)(lq|pJc30OH&tujy8O0$XHC3Y=0uHaOkKZBS#2_ZdT!2ilapTr z6o6=u5!-pnwv8-#m}QHeM=E^s|1~nTI2y-`P7rUl_rohj3?A+EbG!<_zZVG9z&5sA z^tv~co^Ul>`%+J znnHK&IavXf3w)**Q{#lwwMw%ig}^(>R^gOWQXmP4D{|+V0DpTRtA7}L`sMH!aHIU= zi=}e|X3R%_v!hoc3%w>k|HzHe;W#M%z~_f~F~1Lpk{R{9ilb<1iGvv3#uy-%O}=uj*>RDQnlWo$ zV^`lu3GEyKp`E|Z6{+F<@VF6vy$D8QeD4EIRqUcc|e>>HRiJ16LS zaFc=fHV>U6L0E1JsL9{w0|bLJ#e!@mX1WpGqkJ_#f>lQapsu5F-`!d~gy_`)mOIp4 zAw9*3?ib|7Epn{FbP7qb9P|$eDw<4hmftFi92176<9WCR^U~;j`eIcg~GpM-0Va+#;YTn$TH%**V7}(X1BOUdINt8 z)Extc0v5hx1|p6(+Eqleou%%1?ucD1Iac3#Qb2A5mX___S>wA{+4Sk0p3F1Wq(CIq zLE}3YSHPkiN=*QNIZ^ghGzQ(YvKea`2+fEmFSL=lKp10-0?}X}NX&z{V^;ru4aj{> z;5+)0+yGSx}lZKC^a#zNl4UEzcV^ zJ41Cdc9Lj*Izuqkdq+eeB8t~1c#vbt>{jsO2HF5nG1fuXJ;=8(r?I`^fjZocI8}~p zguc6p>;oLR#J2EH9<>EidpTh5zz<-JM@;oj5{h@i`1&x2h2h7N=M%h9zXkz$7u%md zq-n;9|6gnJY1#sCc6L?Kg^0!dE7>iT##17%R)L+Z}%I9@AHO_A8Ve&Oa-6IifO6z$MEZ6@zl>Ab~#lq*Z z|86-|t9HHp9vH>ocfb&1WJu|1zZOHgT*Ju-WH-!RnTO8Vh}|i1>()E)YtocWu;&L8 z{hfnS=FoE6`oNF8tXKx#s-^3{G?JI{o+q?U_so_8w1^FPoyaqGXnD1QmV7j_F0;Lb z!}o4dfF~o)sd&5FGblVxCCvqtK7ujc7Gn^;ZiKys>Ocsow;U83}xE-Dy^bjey=eD*Z9#=>YKDAXZ;O)ELoyx8*R862;BJA%7kuml4{dKHq4wa}pKpHt)0xp9=i&N_< zeNzAH>UPnZ;5B8Ac=+WNA7Kw+un`Fm-wt~Pu#Np#n-hR^wQTm(Pa%kOY>C&m2nTm2 z@E!!~iMNr{W5|LRLO8rE8>fPw$+7`EKs{esykP6(>*VJqLmq(@4n>pb&p~;s^FZI_ z+8bQWHCrqfCQ1M)71&7%fZM|mjI9jVj}>w^ZQGzB2Y&l^c<=3Hzc;B}zVL+E>FTN% zcJk3NM^}~P%Y!P^qBh3?5M?^5EU~eAqX{qvMH3-!*>j$3#D1mzf^i@8c1m(eMm$bn z_YQq>oIcNs`J&VmZDMW1@qOYceq~F~B*B33bwy#py20LhOD2(HEKYYmle1^XKEvZg zQ<5d}UlbcZMiGYY=<^&Ox0)jS>|h_xe;%(W;88%(DTsw~sfO)Jxq126w`UVAXgvYZ z(KQrLgzt!hoeBFZ3+j2Fs)D{zNpJuBbjhhI+cR2k)@i18?%dP)NM!S&Vc;(gO}XE< z9>8af*UtltbYRS%?%QnpJoeiTXM9J?r3Jt?ejj%`CRBIY1R$d5Iaca)=ozN(rXW(~ z&MCa&K5#((W83)-;u@4Ylh%en*0m%bSI;gI2N!C1Wh>BjgB#cFcn{S}HdOgJb&6(L zAdr}HFpx&PWfHrIHxEL;E+2~{d?YV=b@HMy$|!qL@_^eR&Uyb8f|Eid=KnnRwE)6x zun)TojzEyun}ORwh7v<%ff6UB4?4zmt4%cu|KR_$05ih!Vz2Uz6X+N$`MTXV$$Q;K z^ak%#XIkAz{XN-( zYBsRn3ZY#YCi80n-#}f~b2${F*xPGsL28hFybhl0{=?0JPRyUG*Y_DLcBski*31E68uNhjZ+!^M^SIoPl=+cxbN0LmX4nv}$}* ztF!QD(ig|CELiHP`6lX1>y?(_^*^p<{++4jb6}!5g&Cwp5)hiORsmqgVpOPLA?Y_b z!=QC|~T$s zCm_t>4&Arn;lKl0n>H_kKF+>ENxfCS3qz&47-^P7E$Jc zE_!zO3uz4fN`HUQFxZtP!h$sFf?aFYXO(42ux-@{pxmHw5;3X>04Zo-$A%YKIoMT* zP(PW@X_fAFlea?7D@|0D180XHNj|PrHJc#C-B7hMFEvjy%iaJuYp>P=%-;RetKCk- zE>+N@Rk&$DAdh=z)lxPw87e;ObG7yZKR$uO`MT>;*{92VUBPE^peeVXvoo_lE6W=d zEBVV}FF<%4$FPE#>j!kgEj`Tw4LU}`!FJ&smSpvUN|_?^OQ5Sa*i2FZd>_3M?>LXj zP21)0ju_~7VOwE4@K4)%EGbUm>^FN@4Yr49O`)?xgBeCIqSV4YMqkz-HqDYxw!Gry zQ?P?Fse~rHQv)tcK+&t1v)+O|A_(TD6dn0%=@P=cQM>eGU{c8KSAbb>;l0Em4t08? zjRw&Jc#@|1od#lWWg+&5>5atC;-1Bb8W&m=|BFA7Rlt%k*@$F_LD`g|(& zJMbbf79?d$iSjjF4xRI4W;xIg)n)1DS=xlf#TcC>W&WC|W$QvTW_z%EWM~)e*RuWY z#&Cv@C?#MF96rFvHM;MVy!8eAI`ik#T@hfMiwNf?(vzxs#}7ks zHWDkYZ)_jY0;eDdc++0q#}&oJFwn3evsOB6cB_tUXE)I)g5628!-s(ge*Fjc3pLm9 zznekG%C*?ZMPJD5eB?Rbt#CUXxJiWBHJN}D4G{K8aQ+|5Cj=$&$k)Tos*t{FCsxeW zJ^jw+(wJNXRrF;ov8Rn1gNN%a@@csZ()@BVPLEm3!x|vBgY9zN5<$#K#7__zaI`?t zUZ@eu5n04w!I%^aY@*n{26+7y!yOTB2tkt#c%)_(OFAgp2pJ+$U*Fv6_(23zX`@% zEuB%{FZnZ%gzSCriH85u4c!(!@!@n^GgkC>ci6cxy#_-AcQ!oZ_2#o8f-7nLljqJ z#9lJqx@@6!o;nS64k)4(9B{B>-;5|wjt1xOx8#|dkE2_eE9}pE<|Dkmwb3$lS)b!U z3I}WjF~OPN1A@cO{!>5`)8v_zA>y8YT6r`Tk?nW)EfpzI1)9CUW(m{Z+Q|rI?(yVT zRp6d;xY2(QcX;tgQYHcA-%0A(?i};HjAePb&U5ZWtJ7ePHzHv|T2x@lp)dG8kE%l7d-THCgd*}j z{ptl*qQnF!AVX=P-2;2fn;UOS8%cGZ4wOxA+NuVn|Tz%yIM-{M@VT^L+}vAx)%^a#H& zIpKR6JT9cEPv(onq8mp|=P9P}-fhI;9^31ugs*PL(>XFkP#03AJ~pv);07Gm_av88 zC|zJ#L#jP(!*x-NlUZ0F`H{p0bgrR$i!2$Xh!OY%^LnpG3M1!QulL@0kDZ`C{HT#% z!-vhim-xN69V@5vkS0UR*UcycO~WottX~8iRd$KwX(S``hADLYqDx4Z)T9NQu*Z6n z+waF!|Lz9-fPLoRBOl+~{P$=}U&`x!t&>Qigmynj|I zeLQ+xBj)M+b`M^P`~aO-AygP#Okr2U>+G(N&zwBvBkg0M5GvTIaYahZ92{xVtN`nY?# z*L$2ef+#>zr1P=PxaJBo{+;U?#>nSOUM{@6J!;X&pgQ$o zPt|2?tg|EXtT*HF?L-yl#Ss6k=SZgeZ6^z?#rH}-G!AO-^fWY(F>dr9Me9=k`MA=! zv8PTg=Klz*d`-l#AM2?+DGUpohs03KJ)6B(tfyK-0!DtRhV-rVG^J0>)hGJaz1ycb z@R<l>ukZ?_q8lY2 zl02wqvht)QEHN4Pv{ugUf2STDVfbkI%39(Dr&}-nd`NP+hUcj23U3UVTWOBUJ6f<0 zJU;lMK;LG>5hCKAZRM9*J414FoA*rKO^WpSmjWl*4VE6NCW?rA$D%MYc$kT^X^UR6 z<^qr0u#eS|rcfUA^a8owv*SRgPLGJ>S1Y0F6VW}S2qspUD<4?0M7uhxhvOg?^5w@E zc+862$_)QQc#VCG?jHtUUzxXDbgd-yDT>qwRg=`-V{hg^*;F4atx3q6>hf@5^wUed z$f&GJ03qH}ghwy28|+iSDK|_mVe!9rdqs`ki_xp=2_dGa+h~BDVRpo2#DkR_?=?$8 z!LaM<*(j8qLe_;p{Q=fzKg4LegF0@4)S9jr>$}!kqr)A|Y0TR)Q&mO?^A$qDL2;gj zW+teW(QBVRe_*ss9wb!_mOaSvnFF6u_ZIzk0V`SEj90^GBKW(M@@Z8Ia}}b8?J!%~ z*ch*EO3GI(OhQ{FcRz-ATh4_o)S?vqP9GFl`#=Bmzbi_G8s>*zV8HTE#9FpJbw_+( z2tA6tVR2L?IM}$-zc}|16v`oek=g>*7HqO;2ZzpF3ytuRMoG#qoMYy1+SS)q%c$Qz z&d*coF9v+|p!lsofwX4SzBE{4f)_zVbIJ+b2(yx4Vt6f5{-70%X4|6eGWd#aeY|gD zpHy3ZdX-d1MLd`ujJ^2R3-I1Fr}N!M@XnU8(X`I9U*zvO?;b5ydpa~ORCN3xN@+uU z+a;UZH@Yk5Y$TXJv@Nl2;-J?jch0L>G^`Gj$OV#(`W=NDJdBh$Of9Xt$0RW3zh`Lho|T=y}n@Ip{fd7x-ATW2qx> z*k*q!E%og3HGLK8xW|uBBzVmI;NPVC-eDy%(YRmgny6q~yy&TCN15Lk=`0hIg5t9% z0&VBJr#}g@f{Rk^c^HkzbmkO%I2=cQiMCpsr6lscdG;1J6svx(ba!Z8^~M?cI!S|3 zEpiHc-lx&z9E}a8F#Fs z#v>Q)GL+N2+e?@v<&c(ct*hHU+`+`j9@R`Ikz@p=)4X1v$e!lovEJN_`u1@DE_h%6 z;Fk+RD{LLoBI$Q_btC#W^i`c->3iVtFY%*`V1r+{^{cJm9T|>B2GcgMZmJ*n;E|Ai zn-olA-UaS#$%$}nhYwnozs_p)+IfUzOY;Q8^+UhB^IP(((SlL$IWiNL0BCN3 zl7yy|w@y!=<9y>EdhNteNQE_jQ11Q?cgy8tRifu7C|`;i3;B2lzSG@LVl-ytM$TK^ zJ|c9r-tP3NcG{Kil?iRF55nv1`z`{IPonMQl)mUkearv?H@Sg{uQS~;&pGfLT!$^J zl(T+~E2kBl&j|1-C*q<;Tjaq?Ek=J!J!#3%UjpYy&<-tor<0&JANmQDzI~$RRE=+j z$##1AV0+2%BiwUidtMQZI;)jzBU#(Z_29pkaAy~(N8uy8XkIeFq3M3W07btnGS{N@-zGsN-wDIG(W`Pa>Lo5Izc_3@2`xs z`ZvwpsGzBp$Hhzn9{Oha)>WD_VS0Y5{K((V^u%TTS7Suz5q~}*V++z zS1jfCx8mZZs|~v0x)yj24ge zbUkGm-nl=8!ou>tu6C4b193_sn! z&-RE`JCWhijvfDD%f)p~PPMyKJyn02+E2QA^$a;BVyf@@k|y?TZu*zEt?%v^?p zX8QITRbA-ATT|xL?5^*sRVql3SND~FOFR-*u|+El|G-4Ugm?SeA(ese-7JYxd93`% z#MiXGPNVL;Z4qFn9H)1@ge#it%d2!_s4??W5JXlBtgM2Jw;T4Y!)@SIYZbW z#p_1|ZUcKri$}PAd9vE74dg|QgaC3lU&Je<3q1gEhch!vSkF`g*|#0V)c_@H`m11t z_Jp!!^B-nj5TqN7;&8V0w^vi=&p#|V{O?vqh@O}^*<6!j`a+Kc$Z>(HtC#IB8!SUn z!IDRI!ITx&`YsYla^5TP-ZJVQh@3zLU9_lOL!O&HCPcNAzur)KRPQi~ro}~p!Qr9g zwS^IweOpg0me$OMjco&9Jl@u8)Za+~o$Qf|0VTIs*!j2xoglDRW;h-O&T(!0?8$9g z{(7*JYTwcp;WJ`czMM6LF^IvgR`Ui)8yB^aZ|If8?Jy2bI!xOLy*ZKP`ZefdPC5Ck zu9+IB92f|Q{W_Mf7ME{>Q%5K_8*0jMB`Mx~w?*>?r_*t(8vW9Z!Id?q#jbB0Fw78L z>d}Oe38h00KnaE3)`O(`zY}SN8V!|Yh==r%Z06q~3Gbh78MMjGer$oYstmf_CcWTL z{ixy^X?*SgwfHkYl@LMVQxwX&Ja}qAWxjJLG0(zArr_5DYhMOofViXilvC#^el`q| zz#HupiZjxYz$*OY;rTeh68`Y>Al2%{_{@9fgPAWs0)PCt?Zw3L9_Jw*CC1&M8P~u1 zg*ND_1uzsCm*SP%*PL?8vsiFQ#r>a#9m_Ck@t8Q=z0tXqWG*_48@ZW~%hx{8LW#U^ z{o%xA>($)038e`N=Ue`_UgxCW1Mx54+vqh#;2{Jsm| z*wZ|)H+@&$z3lhddEtH5Jja+6JH47PzTyENIW0thkzHb4JECB?;6N(02gKN*O z+CU=s`+WEz@=~LC5j(!SBuy#-GBi9mWYHFW9Fmn5<>2DykK z66A^HR{4^cmrJ%&42D^vDGSNNhZDZ~Aiv|{`oZV+@t$LU=Qcd)bclHNH1~ME(*WHN zb?>GeEqR_*V}uVRHO`|0R-PLRYEZkrOfO%bYoK-_FOjZieCqo4ZMb%P-GX%20?R^O zi~8r{Frn!38ruWPyM2`YC`UUK-Rd3OeVT=-=!A zR4%{z|DmzgQY68|$&U3{1QswQdU(v+Z^E$ls;E(OM5n29_i!QC>DYQBB}eShxNAn1 z6bb;gZ9ZwA4i&{w=ei2pI4ytGZOwl+Y>75Tg?thIa zG1Prcq78il;%3m5dWBhv0MEB$`B|~E7Jri`MnHOrA@nO1AVjcIm6xWcVN3qftIm6V zk0$C*?lKgqtw9`Xy`v`q@AOKbpxKUJWno`8$~6Pt_4y6*a`0QF8h1V=g|{$(@WBH; z@)kPC;?)A8Mui#EzC}lO`@x?p6hbbr&_CEq7)RND+ft%zT@!TZ#8hLN)-LAKru?v8 zS0KacICb+1Z1(x@;~J_gDH2fnqoSf52~aXG>i1%&Kwug*7B#o6XZb7etL3%VYQpqd z?cOn7Zrn>oB=ANkGN4yzBp7#!9+*6LK3qzvHd1+XckA&$Wo_hg#&&c6;Rsc+-e=lq zDY537wp5{qp+8$+_{A0PS@Y175L22a3k2T>4IdsoA$I6AKlRb1Q4~eyw?(Tm)TPwH z63^3jcQi%#6w_#fA4=FH-tkpCJ_moi+~^?svC{24j^bw*qRW}#B!3vltS^kdxLYto zg4x(>1`AdUM=mN*?mFDH(6>3%^eaX{ms43`+iw^&K2H!JV|~LSWW;HCl}_1N?~lNs z>kK3LLq&x)n^QMY>*7kua=t7YX1QRTK+%P8TAO*wvL1A2H`T;!-v5r*_wVj~3@sCr z=hCg&?O5_|U;rkpJJqC|Ejb9dGA5}lIi|o(bf_iEbN*;@Zu`ypHB!EIz9NeWDe}fF zQ($Ewu|F?=RX4LxAutNhRPJK(6u>jY2x;Fr5t9-}KhL{9p8Ek7^y~Gk#V|n3j9S7} zUFa^h#6bIGf7L!$0w737+OqX|{_~)1QW_0XP>!2Cb>3*)4ue(snk1QD?Sv5uK9d~# znf2&}C!$XKxe*qx8grYT7?GfnfO_{1fNl^7>llF_KL672^3N&KNS+TM$-{2Zuz5v^ zV~bCc%z>sFy6@M?5xtmKk1L;~De+|d)82Qy-k$F*psU+ZnsZC$(|%9zz%nlGTYM(P zdn;Q#!S`<)yUk#j9lLxskUA-pUcBf2+(u`esZut{9d0Y}`iwEesiWXL?V}e@{yA0~ ztm{<1{yqE0wu({z9p2yLLJxA}4_BmeIyZ36lpK~o26&UWI5$aMZ7x;6;GkJ+QN1Z)L2_n*At?d|k^_>12m_2b1j%s-0+J=? zoFwO*o@)2+?z+qMetADUAD&-d>rOjJb$8XNbMAAWySjMwmcDmkRI>2L^t5|}D{}IU z^sYmMCI}d#0<(mjb7q&Az$+9g2p?~aq%Cjt6(%_8qx_!^ZR$(i%D=@%`nG1h@@t5- zYt+ySZ#GgFoQL-ERyD5%`ZCLm8IL&UsRA$da^w=b`@FvhSl}_j{RAk;i=EG*=%W4d&)Ik|$ANC~5v|tieOtf{w-4Wa z9?8k>E=V?O+4SP>!v65=k8Au35~3%NaWQ`cH+thRG*Gzq%Fz@;3~|)O$(g@83HHk1 z;peC3Ba+eE^W=W^L~Luj8UFfASxJ_X_2S$m5So{yY(xP<{D%EL_AIN`Y%{zaE^I{l zrVLq+K(HQAYKNB8dW^A(*=kL@DUm5J6otOEbTMEHi2CeP9TsXWns&6Yimvsvt2hZnZ`KWN%VStt_6o6vz zSmkEKRnr?f%SFC6TO-(4B$teZEtd1$0VgxOKF|NLouUGH&%()EiZV7_vOCo+n86+* z-oyl~&Iw%3)mx7}X)e(lV0l_f5?CJSy9-mKffayJIMuRoP@~)D?+6XC`eFnDh9cAt zu=gKZY*aut`rsaJ>ssEiSzLt$;Vs(2>A9K z`(dIrhlGa68N~*=mw}*b0YtuGLT)szOdqCO;mHjW>+%x}AKyh>xh|_IVrd*fyM8kD z+4Do-fYUVvNI)CI2M#isSsGkw4_%G)PE8tp)zP|7QcZShy_cTcEuv?kf`5^&d;`Vu zW=AU?@onkbwn@IB8gJ}D8a2SWu`3k|5s`rXJJb?7u8)=~X`}L4^YI^#M`@d4BCfnpw4(MW9uhkhrXEQsf){RmQ6#}tJsUfWg4rXfX;vE2VTq>76N0Kb5di@>q`)Tb}qpkD%x%&oAbK&+CuXv>|yB zj|PoI#-_Loc&{<>5-{wX(6>jNO2XXJ(Su+4gMYMC;;;|ck=Wh?Y}ZcAnw2j{WpmsV3;j`p9w)p7vh#I4}8EV~*`IzYmazDSS7w>A)FDv^}L8-D5 zRz^#ctgcV~h82H8+o;f(Rwn&bzaJDY-<_rpkGvXyH97z4H2GoBEA1Z-NHsE7xXCnu zQ{SOH-1vKA?7tx1cqM@I%hUb|_f*TACU?&O^W=2WjPIcQ4AD_T{UXZQ6Ln#nv~LLc zHM^BMSQQA5iLGl2w|*p4WIy8)jNlZ_bQ-ls1u5y40n(`3@iXD}x_E{VcpZxZ@HA`L zry8iKpHF*T-~G+ciHN*>eKLux&N33DT*NebB&TqC;t&Yr-1*U2vLENR!F=9e=M+0G>?(Q`ibdUv{9^6<%?A3Xm{wblKmv5-FLu1IiX_`Pby(r)$RBxueAy&%myqh-jm$$8rz9 zvkDmLxhEyPco~#F3n6^gv6eVSQMD35CXh817JmjRN5#?xLs$ATMA z1P`1@Sl?QW)IA1&7Gitc^wO!8PvCdX(OmKzgg) zAL9Ml!#JVwhIxMGLowRnB>odWD3Z$O)^5~JKCCl@f)wA$djtdkmBSOoc{VD&cl0VD}RQ>%B|+oj^4*)qWn|#oO^z3RkSP;Rn!~ue)UN?PxbkZsXYN8 zA-Tn%$R!m-OVK@h7w=K8H1rEa=sKRnT=K(+?*s<+7|%WSZ{=g0pJ5 zLy$JxIJz)`ELIob$Y)OmO9bBEqO#ea`NPSTujsE$Xn@tuN{D`cxz>FR1ht?aB@5v# zbQ3t{J!7++A0_V1a_XP1h1EjrXp2`fb`g~M60LDVw4dj!ovi_ce>gi9pSEbwH4^#y zG)UI>#_?$kem$*)to_0}q>d#ci=g1wo5Q570Ec>io`_$dZ>#pjv(QunZNSJJ9# z1Pw-u4R=RYS|q6epaB?8uZ?Dmdw=SjC6;x97dTSC^ZPG6Rz32B2e|t*xqCD+iuzd& z+&-v1zwLkF&edfvOH{C^1cx-BdMW%~h1v%IH<4Jgzj6IT`5Y(_`&8M8ozuVsF@Vqm zaU{i7Txgn<>548HwPNz7U1J&#nw6X%#Jzrw#W9*}z3~(t2B1K7^8N{@60Xzr^UFH5 zDCcjbRu}Fw`8eflCO#htzr{@**i3aCAlXU>%^PO?37(O&Tz~#w?aBtlPu)jQtsKvxaR)FvyV3W&5Pl*!5z|l|3`_hZ+ ztxQs&j5L~BZ1j`y5_tL%Q{(ggX`q4i&2?uepLDZ6K17iNh5=R}PTT(_=^V%|>$(=w z+bKWi>rLnaM4@}ii4M`LSFs9^FQ`{1(t7WBPKcT=HCqM3#KHbj@0xWXUg_V*JF-F- z*FQiRLwl)^mdtv9Xgftvak&8y z1+Nfx+t&!mKe#BtsP*hBh8p}ga_lBnX8JNUCmAT{oD&!nCO1AC5aJR&^tE}NZg+O7 zDm;d^iePVO#1{44#O50BLyq+uXlEO{%a$>nbZYN4W*&W0q_p6KDwD#SiucjdcX~k% z1qFV!NGobJ+nWuJ6yzli=L~VoSebtiM=QeM=Er2V0pnEmHH7;Ss@9O#)oI{HgKO0b z5I8?>>@Wa|>O-!1U;fd52N5{RSK4S* z4&uW1DC+R2^PuQIZm8(?G~lgF4ZV24$RcAb*+%;qSKMW}pFOKMs#N}$&;0vD!Uz-( z2MbMK-pJAJMZ5-8*pKZSK5qp0ELD|mm?LtcNpzA+|7tD^Ngx zr;@zsSvm2}<=Yu68oV>1yL?eE%%ul#y#NwRX(dZa>- zOwWupUFz@gk!EQF&}DCe=sU;~2iYVZd-)^%fE0w)C0!EHZ}4@?7^y!n0tk_7D@h>r zCms~@yew*lp`FOi7pG;{df$~yxEClu#j{?eQCy5U(=dUFK0^q|McEmil(1zdPnj;d zN?=3Q1KZ?oW4lEppQW-852Y8NFVo1yayN+Nxw#8cTN9)oVb2 zBqt7SHurzWyP-lz17{b*aq24kkkU zu6u?=SsrB)I7Ihw$ixQ9EZi2B48r=nz@S{89qIv5jup%!DNul_Vv~FVeA4;_fT!OM zHC6^k)j5AB0DFwVxQ|Ewjn00ZeUlM$b-y`j`1O=l7bM-uAmDd-JDh{j%Pq35s;lJg zt5Q#)j=A)r3y2-m+~`YkaaZlM27IeIQ`-}Q!g^vXAsrHs9(`qd+rbz;LrM&^GuCmW zOX)y;(&@1=3aATfJL0)RP)qd&R9lD($;^o}S6#U0G2#GRfjOl(^F@fqWBb^iQ^+x} zZ`NN&vZojEY%)%muG->YO<%ucM_s-}u4n;3mm|N-N-x@_>unyp$Q*q>p201%G=Xz+Pz-8c=qQVBS0Rsa%a;+^~I*` zEQYqy7~nKO(u1iu#A?Z_SNFDHYwdPIdjb$UZJ+S@xt-~+A^X42ZO>I7nXyb~FKKLv zIf@^EUvf-t2&jDK&#vk{LTN|}pBGesUC8l$m`gKTmXiF9BWUZF7T`;!1pdj)BiTQ= z%+tO`gE>^t$Gm>S{tWal#kF6dXjbphk}Wwpa@?25Ar`G$Lj;bs0akMa!|?k!f8vcOi0U9~(}>!XTpXGuT)EnT$V?|{szazOi1!hNgrC2@GZUXA?e zgg@AwR&S>hH#7lbRZX9p?r825(x5HQFSrn)XsnN9T0Gmf2*hOhBbBa@Di87$Xd?z6 z@zRSFc(+riR1pkq&6KlPS*m&}&qf3_5a*#?sKK4$%a8P9uQ8zJ*Vrom&5*a;jPCP% z1)=sEJU7exC&CU}P96y<;-Q)n)SzDfapN4ks3ibY+{^w9C7`47fGgd2vOC1v+}TQM zAQ1yz%?FfiqiuC+54J?o@6GTiIJu!7q?aljssV_(8aiLeVRi%P=<^xbn%GJd zs>hBgFPfAMd(4-CnWy`uAd$8fiY`klp*Kl9^jMNgLf(>X3Y5)Qqi}ejj)A)6N6Wm* zo+Yj0O2*94+E|ODfka8YS^NRw1~A8&w*|mWfcq%70MyDO#rcYT?a;E(;ha|rpuPm= z$8n^a7D-VXs>?uoV#8@^V#G+^)m_l2xR@x8=Gkamz10oitbw780*~j61HMw^9vn;b z4{P~lH8b@fi|QP_16O#&(4^HOcqBrEw28vdLU~+_l*W2T2e_)hJrt^sS#) zUnKg=p-4*~)QzkRqw~nS{ib>j#iD*$dCih>Y% zES`lp_i-Mzse1raB-J}F$X)aEjsdJ#K7u|d^#d-SWtVEX_TWC0O|2_k0F`-0z#n61 zA0R-=wAHo4>uQq%n|W0H@nfUk>E;QYo{37Eu@FWe2hs=nE!ugWC0BpDGP%h$WRr-s7H-$N=g? z=C9KW>h2TPpbGy6u?q-UP#%1X=nGrhqjoIaJ%9np*~c{?94woey{}uo z;w1rghe4_R$!@cQr+*6a{@0LDV?6jXsbDE!tDY3iE-Ar$hg{tiC-?hZfTpVo&qe(L z6MT_=5m(#FGGdQfntw-Lyr*>8_NJ@;_U>je2o~bXETP)MAWawQ;>FITPgekWY6W04 zurkZ)0DFUK^%cN7iV1sgUs@^Mj$|Hj{enN=GvV@CjrYP7i9hfa>8!wj3p=)p!7hY< z9k2fn`v>io8N4KVh0@6Zbb41_K>61xWWuKbWURl5U@s_E@)nntoD@`iP%+Q9!$2?3 zwyvV3?~uPNWkc0TYg!Eoct0|C7LK*l01vVI6a&!&lL4>FffmcU{8hLX5`Pc~=rTxr zD`t_YGgGuoTPD z0Rp!{I@5Qtm1}}0vk0w>yGCQ8)#M-emqFK<4i}O>xe-&z00=rD=JKL&|16zHhEE4u zXm1l98G2yjp(eHYmWYoxa)x@Jylp1E^%~JfLGuanlcB>M^**mV^+AFQ#q`+z$DC?p zJagEYuj3Ss`tJAHX=9>%c&>Xl?OqHd>IQrRD9kKX#WUNhx=h)^%>roz-5+}jB0EQ? ziHXMgbz8vL^FPoOfM#-EPY%djFtk&OD6Tx(?X%)4C_D0#(g4a%`Q=c~LjsxNqN38S z<8yNJ5sPdPU*_B8f7kZqp@)A^HUKZtMdoyAG2ySK$T1Ae`J0?rwVxvH6S4d8XyT<` z77ISF-vssYRwU_2k!Xz+=G>-EU$_pxz#tDf(4=|;y>?C)7UaLni;HYa6_aqNAPcI` zJjTx+r;E*XfxJoS5nCsXWp(unCwoa zdJEM|&c>>SLpjTKm01OqyYrwm(Aol5{L;?%-WYTZP~oEQ9i*Ic&hB~DmHT9@vg9oH zb`MGvB#Y@YF+==+YpMS->g{|Wjrw>(c}j3?IF>8m4VbPReOmsI78=yyKdw8O4_>fGMWZVL%0ya++?@O4`Bq-i%H0q>cpz z1XLkmSKunbW+CIoH`EBr5Xi=XC=se;KXq=j&fl|pv=07dwOFt}GR*JNx(hS&+e&Yc z<}SA<+1jhQn)Q?lLLO2rxN@f5z4&M{ei%{>`%)T>?( zw)S)`UZ}_hrFAh-<4!wnBhhJ~XYV256j}To0}RNgmoIaj3o9 zufm_0yz%-ZCsGc=OF{&1U@7Yqi%|pbheGG zK&3}eRK1G}8T(xRPDSV@IV4J^m!HiM{`%d}W)vu*T(k3zMalKH)HJ^ak@rHh#~}{= z3xWUr`Hk!z5q7!if$GQO>{l%~HA+{w*-68ObKGJ8p?Ih(LCW#~l#&%fXrZhI1PY$! z@ej(29`voWWEq(mm#K)=c>ooc*Z3olt!6_?`U8BXMH;YfyJjMp;PJt(B2)^Y(Cz#5=_^SNip)5Yt_jLq?QLE#MRsypmgDBm7xh+JZQ zbPN%=mJF!Z;+$0S=7WdNCoQAe$JR`NSCbnQebJSxJXZDAR}YAMurk*ryG(2#6CQmZ z_h}i>*w&3NkEiU5k?i@73Wyb!lI(se$(xh=d)g1?f!JqMl+i5PzBRH6_Uy!I=6uJF zU%5&*{@xvMn_GL&7l16LI2&^YK-;?-uTI+W>2ZsSUoa+neOEq1ZD#r4AwYv5MRW|E z&BSJ$Woo>SmAMd8K37%)BJ}dXeL&Yn^D|xmQ$!DLDg-pyUht7!`UQYgT-_2+Xj7Y3 zl+Gyl6vTdAfD<-3JJ9i7l(GhbDH~9Ps+DY3$RirMoU3c7Km+Pr71QJk!TI>Yi@=+o zQBMEd!KlI!-!aYc!u@m4#L05g?JvbUmQWhGp#Ag()5VJ!H~7fG)cX)3w^{h?N4B1} z0}Bvr0;=I_c`ql7>{zDgz*cT!<+x2fpD$|8gGZ&p#TX4^AFyT$RJnLNd6$Z#b$Vf|s&@MOk+T zg%mYobu50m+^dLxGem5b0mjBX#`*cGC>f#nCNToWtbe!_ij*K;7VyLyv*g z6Bd9alb^DSfgXg6fvu(r3J#|pvL(_^`-RVQ?g1SOpkIJI>rJ87g)gutb zS{UH=NY0$5$X0j)(iZJW{;{`SjY2AYK<4(b6?+MiiEYjH5S~j~ZT#+-HQ)^}zSD*; z{FY2nJGGvI`x+G%6Wf$1GT4c<;QDb+Y4qrz~gT>T@_n0 ze4XNEUf*<)y{r((QSymAE+mFZ!oX^ew5*fElO`|;)ciIFX&4a@`i*!uz8BKyD$?G> zVYV|xBP>^>)5;KbBo*iUA524lHv zc}mRE#sl#BfZ3M;B{Xq?Q>wM}|0kxr&*FXkG0Ow%l!0lWoILI9FaQFrjDq(uCXV|j zWe>xE+U?@Wm%6*oQ%#swQyZ_p_O) z@`0m9r8NM6I1~R?KTfgwli`fH32@1~FklSk`TC#R^}jEIio6$C6LLAR6V%oFB^XqL z)bNhLJsxgFdd#2jgal$04JwaNQ27YNq)R!zc_&gX3t2hcYNDg{@0ot|Q+k~kY>N`R zVR}n%HJMXPon~2Q;5^ObZbpk z9Nl%o?0vq8>4gKAP69@mt!lGX5XqptIe6b6EMqy5x(n7@goj^XRw+@JO$EUJxnQ)6*_lWwQ zz)l2$JPF8%d;#+1v9o^J?9)IYNV)88DXzR|aa%6$!Hf;#DsbYbh|e*f`#QZcyw|m> zurUi}n(ssHL7Mx3gz7-1Q%SeW{Yl7t{rWQz{uqp|^=wZe@Pm`w0eYd@^JWtf8>F@ z#Re$HKt-_f>+=yHGk*^MfNBM0x2nebb3&cZIhbgGDf{*`H8X7!0i~Cpd-;{C6l<%y zAt!-!_|+K%i29%?@Dfh%rGW9Q8hOz&`J!s!ZeZi-gvJwqsR1=Suw(&JjZuD1X;F8X zH@l4s(FYn`pXw93Dz4{%y7xK|{)OwD1rh&L>y6{nZ6-D!3hI5-ye`W``Q5M-IgohN z{!H4pmQ$7t5tvk$!^6&dJ&ZwW2S1rNf)*}-WeV?}4$XHA+MC{ABd&%- z{*>h2Jhkzs&M)r_SU7wHeO^%=d-0IneD03Y)1kBa3;saW2^0`-PcZ27F!5`&r(=V` zYC0j6Htz>uZ3{BxG?1p$8iAyJ=KY_KrKk6^&d@@s^v&>88}{5MrMs+Q^eU+@)mUXd zs2#(>Nn_y0vIb5>wVnM_Qkq)nt?>3DPFz4p!;fYaT3NJzH|G_pvJ@_eK?SvEm#kDD z|KuiEJ2GsG8nzw#I@K_}@u6l$I%?VJ84BbCoF}t)j{}dcyL{&d9k$X_mS#uh2T+LJ zOHnwDLmZ1y3pj_n030hbDD{&Q6>=zq&vAmnJhd5re0J38 zJ4f*m6#Z;Q#qVN*=z+OtkfvO+?WVRA(y+YZA+cAk(J4pqe5OPJoL8waD>#2sZ&OqdL4d6UcP{ zzPK|RjQnPBTh0DjHKVT{uyiy-wk$~-J-xhF_qoQ`Cswuj`U1JakZROFaz!2`=Y70y zb*BVWKoy8h*T~!LRq{jniGTJjN?!g0puTiaY{OrAtN>zXQA4v|dm;o&I0si(>`;8CE-_C!2 za+@`b;c@ay4Q4N8CSOqe>zD>}+NW{ar)S|VAgPl$sQ_gFbcL9Mhd(YsF6d0x-Bd*M zsSBiJ5AR@u=v5M4w$0xU>^R|De-^lbs5bvjS}KqZhR>5&Uq*wJ9dtZNAld!HpJv4k zwB}n6&%U??PkGP#a{4igyGLHf>7QkHZ_c-bfR=+tJ^)nhs7mT-AVg^A>n~6|-EuQN zs2=b~0BOU;Nw*__aO~uLqHFv&39v24u57JJ61JatNt6Pr^gv_?Xmov=<%I zcf+bqgQ)_5hg!*HApM6HKD1cgy%$C4aFR{KG7S$>H0QHF`%qT?cV{DUpLLz!Z}|H6 zS-WU9$9<;SxV3Kw<;{GLJvL0#f3w%Aw?t`eB1`&V3(CHZT12+Wv}L+2E(9 z-~%nKe`H60B?KwyL2}}NxrLtw2$Uie=&Xk{d~@IRBhm|8~M+P ztj=%!@!tmj{mq3dzuDq{8vM@}$A7M4{dY6}KmPvz=OgTR%nir|M|Ww~EDs4cx8dIE zSACH(zxz%6#OX^9pEEtbsr)$8Sf(5`dN#vX?^xAImD`t}9}gCq=(cfXRn0XYNN4b$ zY;9}SZAoZR37t;_g4wHX5>J#8EMuk`de%Hz-Y))n+2yZyArSnK2SUsv50Q(%_PPJp zk3E~D!TVv4IzI57|Fu)szkd9`%lxm?{%2|bn>YV+Hve;-|BE;OZ%0pwhu+-3v;hAL z*uS?T59Rz1v;BVsvt=!R__bT!-;-de-IT+mKJfv}jMaq5?fUTf!o$<)FdXdt zbLcI(LUpdYzqT0q>vycrsmUeXn`u)1k|mpT4<1Fj^SF#bsdd4ytVWeL_S-EwbcmZ- z?;v>V7y&`7>-FKke(~2y9L6B8u}?z3g)qsmu1R@DPuy_Tv2IfBivx?Hji8}1n_*_= zPDxhG7md#q!*Lmxml)YhERZikLfch)=bU<%l_FxDCEED38|-Jg+9p}hE?j3jBvy)V zLpv;#1G2t&z@?R|iv$r1T5_uRNZZZ( zb)yP18~5w<7#s>pT#VEf_{*L%B+UsNsG}pZc@zCtv-RWZ*XHC@V-Mh=+FM4U$)zFF z|YN}u!QZk+$@?a?cLwh3g2{pmB*QX_ycLJTLyhcgm0v>@4&c~>bVRH%t1p zXDpSzWW9IUbnzk6Zgg6xq2wxwHMhcahUy9!g!}Izce(}U%b!{8KC5}!MiI-2%F1KnU3^Xo9@vfOzO#64J%)#vu#RUzA&-Q(-+MRf!*i`JiY#DWo7S{H-`?2 zT=%zfyd+MR#b;+mPYujZt&(*eTsw4KEi$2FYy3GXOV+82O7%NAeqlp()(b4Gphq&? zg;&4GMs;;WA~s{6#bsP9<4RzHVJVIEL#YILV?6k?Y~)Lq_u1nPO?$bU_vMHqCk3HC zr~lUth_Y}^in4Ihtnm<#;v}0Q_BtpIxDIVsi?-|Y4n&a2+jr#p}Lh>Qj%G?a7bORZ9%u$MSPbgq`u2UHgM9ijXYkEE8*GP+?Zg$ihU3 zog^$E1`gNsF00RQ`HuV9^}cHRb4)*MokGkIN!ISodo){5+46F%p1%AOFp|Fh zSI7`^=jZTnnTd%mSgE)}2lfU7{b(JL1k8KJKZ{b*iD?Wa2`_PDs2QK1kJDHnwN@ypW8k}`oElusjP;%eg;P6R4Q(TkIM?5}QI*HbC51NF z9iKK3%T?>N#nXcAE(prvul?&1t-W{Xej@Z?0`V;x6If4al*_7D!{GiMBMPnNd>cN8 z6c~1sa2S;u)y=uoogKo+gprSUZy4G&R6kb|rUY-?uyW_JIFLuoO5Gi%i*tZ(R!ri* z;jXOB#DfZ{mYAm5;Iy36&~(5(wv$8BcHK~7*Xiz4DGDcfT53T|Cy5F0Wg+!ei6I6q zlLhRG9vp4UO1rVPlpmpgfiCd-5!h8KWC?3cYHw7hlyqfU%{yeMjA5hX#rS0r ziqe;{d}69Jm+euLFq~5LgiDf~6?0AO1GM>J^&;->aMjnJ zn1SS<1c=j)t7z@q2eM;Jr!;%^|Lkz3Y(^#r6vJ2}8L!8pFJ)S3ux@6ANYp&;SzIAe zS@|@?>(){*;JySV$F(FMk~|iUL6j4mU_;Kl__gGJf^4%A?eCr zBUd|_cfelXrVaB^)i8uEVx95Nr+~fz&Mvv8BoZk%(_7^iHrQZ2vQDC&r__oTnd7)j zKt!65i=WjrMFbc2*Jijg32(xUR+U)WcpNe|1X?FLLQg z@_RbiyeyxU`zs5NhJKZkU-pVA-_77vngr_ zzC;cIbkr0Y!7F;8vC@jna^0v(Y_D$pl$_6K*pC{)aB!Jot#FF z6S#&n@Vcs8L``H!VoqS%Nhfqiypgh+qh++5_-;ajT76U3!HqU2UR-B~?5!o}*J*|S z%W4mwG9`01gO@mPj&HLwyO0qq>L!Gz>K#_~M9he>v}Cp^gUFASVm^bg=dz?U$3or=D3L zW8a7NxXShvzl&K-H;hhV$FELBXt^*`22R9>F+r_;e}6=4YaDsJS{__u>vmYA74sN7 z>_HSM_rXAtftpd|moECS>%LOvLot8gLPFH|LOPNiZ^9hM`cQFWggdu~4zu_4;hCn>F{T&SSo@L3=4enu5es&)#XlkjRCOq>ed~$n>1j^> z&X+YXwYH5^j8pO+9Q;}B$jt4>beF=%+jFx4kx|q#j z!pdaAmKD;8wrLQG!gO$|c1Pr{=4NZ=8TUKO^^PuNyX(65g?>9t7?%Cnpj56}4H4R$ zEV*nxW9HlXpgDPM9U+BcTPVSFuDx|jnhL;ByYdoSG_1);M)e#ZlN^G#zpwg2-n>lY z2+W5B^j^tllyc+k;pcl_OfE!Y@-%D$vPMHYGU@P*L>TnildhQUqdXce1i+ z@)#F)o&jBPuyP@X*iTgEFZW+0+?}L`M!PIOE)4cr0%8#Y?_zrdAb{S-7qvLk|h6~*E;H{Q;JEV%X)R(57hd~ zlIFt&{36ck8|4+VRcg{TaM0~d@8x;SwiO)4EPfj-L4DD`evDA?lRy9~4r9c>85hDa z*kFlEY>%wHD<`@SFQhnNgvp^687Pqhk&kN_!Bsui#|OYxo`KIAU0GVMw5~()dN!^}1!vKZje4gKc z;-7caryRkF(Gq&+GHG4d+S*xU*q3IbNyV3xI42QQLbv5~Fqpm{<2sW}r!nPE7=<-3 zL^e;5I@M1MJNCSpp9@V4@xx9t^IJ^I_l_(Y#rv}kFt*X`^38Q;8ExeRo&(qL%sa{e zjFit5<1j_mV(a~x1}>Z&OeTh!s9dHnFMR4|Pj9#YNyOm6peuNJPow0{t_K@g>0;@6 z&$SGP;sYVuoZvsqRhc+o^Mz|TL!oWN&J-SUFbV5pkCkc zX-J*lUo(wI1U^$_=14Fm7oq9V*E zg|kkR?_?9RD3QAHz0I1Cr`xNNr$8omR3-A4K$~ZI(tXcS$boH(Ez{vN~hlt24_`Onai@@kS+AmmZLPLlvrCe*ynM;n{GTe5ZnY&xZEmtRY;D%LK?=eLp7U8M; zb!zi(at8ObAY->waLD>e0sMAB6=Ws5sz{VP7qf*tyo8!S+gRT$B7iAtVDTH5*qV;} zewakGx+BNuLmvVGI4d?MX;#j5W}=Kgmkv<&`?r18umNPUiKXjOml0b`q?#CyQX7I{(a+~588b~ zdTilT2;QWS(2&`4i8Si1ro27xY^F-HYe#pi2zB^!&}r$@v+TkLt~*l)+`(Z7w+vl) zOf0gJp+vvCb>}E68psLtlR^s|rZW|go?S|0!Y~go;)WuWDbi~0dq(v{HaW6|9cpm8 z6-aPeePYD2I>-x_1lf-EWV_P`SGh$DEFbuZZnESwQIrO(LigPN>Ik@Ok-}slTOHa7 z;^;kDqI$6*x0coiHCG`4OdkmfT# zw?R>VGB5}A&F@F2It(EPQ!mlz!sR3~GI3xuy3QUGOzmu~R_zr^G<5gtTRJ}}Q(*5F z=AIw!vc~mgt7NFTBHjvkjHeWZa9pwGEaZ(mEt*Xj{@uFgyh#qaFKutEPz}2rDosGG zg5-#x(

hBied{c-7(XJo-L-uP&}VQiRlmLXj!moeifg-YqFRsrGm-q&CEahT8FLKgDENw38Gvc?^Ut@xv$u%sb%+vBV`JJ+ zG>DF^TdHeQRp}4w-)xH*Tpmoc9Mph*TmAKaV*o)J`Quh}s2`@8NMcRL62G5I(mdDH zrnu)J?6G3a+kogio+sDyZ3J%Gg#nX2;weIVr_GPJh?jG&F5@sZ(Z2S66J&K6Cyq$R z2+Z%~wukTaur`*%l3fd5S$n3$03do>Mp zQSK3FjKGs41vhONr%h|CD`L=9p(nAitT?$fO}t(0oh7_IAgK_gC2zvPN=4mm31ee| z!MfgqXxzIzmBk$pq2S24AJDKtEekKX#D|}WVLVR+xx-wB|DrwuPh3if^Qqz-xz}?v z!IAib7Su}GKwJ}EBt!6UG%mJrJ1kZKxoltPU7O_J3y00`u8rNw8f(UY4badw-?j$h z8oRlg2q!pT1!|`tnqLQX1mY&>{!~{SSMn*92|2IcATxxtg1g_W>8P@54l5<}PYkYY+dr;!S(Iq4)E z0YVAPZHP4+?`o&#r=>IPA~&|b1(vcHH)}R*YPkvz?N$yoPKO;{kISQFsv)+0L z9@L9EH};X^Iobzz9T)oFrMoT*wlz^J2$D|kSn3-q zDDMn1aWD-eDkdcdKaH(R^VU=?T}(G{sX+x>G94fMvT|FF)3-bwAqp9Ce)*9-ch7?M zD<_j`q`zt;X)XWt;UeM#)mt%KVnnvV;rwxuK&De#*6@H|_+4r9G*FkLpx`W&O>C z`qCPScSVb(Y=;Ax7lqf1wP8&(wFU?@LeL_uwZq=x+sf;(*7q#v?CcVx@flC`w9mY zBoQIdLw_8)TXVMmrYfL&Rn1U^AT;1rL#=({xJ|+ymziu#{)1H>tj?Q(A znH5r0A9%ItC%wEjInjWWc3G#&bHb+{i{w|Vpd}OmfwCHe>YiaVZ zyu4J9dtqgPS+j1=)#oWb*xQnxQZix!C5i6jYEU0~diFVFCH+_a3x&XR%!EC)?OX6> zFP_qLo)3=urcEspnZB1g)MQ2!SIaFLmgWd!?Q-xj8*pRg&pBH=XYRu=^dK*T#ZB{@ zbypyW@WE>7Uph@M?d>!{aDA!rC~uyBdQNq2B}{UwbZ;KNA2;4nDYM$hXUr$MqG4*n z+9mwQfe~PgI(Wt+DyK=^#W6YZ$f4MtK~b;E=LJd&2GAjq2=zi; zVPPa=mX~6ZdViF1Q3I)1PzYzsACR?Javx=rg6~R0_vVO5$8*I44VpQS<8jmy(FuzC zHa=N0Z4XS*=n&^9RENW&RbC<{(UBk1$Q$iMAB;eE@&e4o+Y=GuVxoEnDk=@%e<+Ch z>wf<}5g0789EgZJtlgZ%Z>JxwimgpI8|O|fG$dtZ3z+xHbMV6&4KfwQJ=piltqi7= zwB<;_JJG;50lA*r__ifzYL0-}Xt7WZ2g z4XS4NTHkwsV*(*9+J$x9o5x~mFq^Tm6v>EDS2g4R!#(H97S#f@fw4~I zQAn&mu@C{Q5$1l76=?VaIqBgvQbm&PE~qLIW%-5Y{8H*orX0swC!Wd{<5r}bnq2Qf zAK!*(=dH4*e+)+sfo99dvtKW!K@ai!kr4rhnX)=h&7)S9YTVhiw*o!*7q`AE8g)CH z`ApxU>`PkDQRiUABrd8$j3IujgI#P_dd9m8ZBtBrKu!P+X>N-95lJF}j@`f)Gc=jR zQqx{5ev??(eePLPY)MdCGqB^cSbaHGGk6~r&>E^pDkIAGd% z)5D>;Y5wRaYZ>p<40c`FCt4Yu@}QqGX7aFJaq=1CN+OYCb&G3{%+5U>{C+K%GplEs z#1|g}8)90d;wzb|G}#YejN-Wnnk`d5N|%1kjiaY1p}Bdl+pR~Pwvotkaka{0*<+&n z?T}nltRe@KA>kCOY9lI)kw3?8+IN+b)I)H;A~su@w`8*>*pi;ruypA@DTH~J$d7U< z`QtSU17W*luD2u)29Xn0Ug_hCTv`ngQq75e99Sx4QkXiIeVHiC8HO%7+@ z(o10t54QA8x%3T0usgbwqsgQ6?%REE8#-f0I^|({E}R1vo5p~H>@{85iVRfT3x{&n^&Cw#ka)TC zjEzF%Pqw#aZN);iCAxiK1-^PYt(ajK3`$wyQ4Y9U-jKgg-B!3^x6?=WTTffE-ClP~ z@ybek@z&m|u+x%G0F8KLTY5>T68K|h+-x+xCq^O>pkJMd30cV%!B2(y$Tw@s3aU48 zlT!N9vr3`Aye=3H&89bWVIO##+*Y#lxEI`1Ye|*1ZEoP8MAmAVC%jW)UvdJN3D(29s&nZC-}ly9(D)_8Il#)Ak~N{6eQ%Q>?^$ia0ms z`gEE`rJ_U@2eHiScE9Vbr92XlU|u-NX|!RTP#@FeF=$%^&}|6CD|f z;3IpU%w(c|?Q(x>Z;+opoC+Pn7Ax7k(YaBq4k7__trN4pXzWgJdG^I-1IJ0(FZL2y zwR(UQY}=txgPdSj#8E(n-1=S=3eyfEmu_To++Lg5=6d=#O7YN{6u$#kz&qZorwBv) znOHO=rboy-exBYA4dEqw6_%sEMgIb?iS8^U(QmYOF63PzQ@NyV9CmjGgXutr6xLoW zKgm`*bI^@YQiJg(nZdfy0!87D<5)lAKuoMSx@Q+ivv8Zq>%=`bcX@z)Ix_xV{sK1) z@}$>kp+goH2bi;2*%&_OmB83<8TJw^0i}@>Zz=eq8WDiTgW>ow4S1G<>uZ{b*6M9? zIID@I!CYQQVv<}8d)YXf&pjr1G5K)Ey zOEna2l3pveI)NtvSBeLw*}I<%>|N0kQ=O0=rh8T@-@>ICdQp1lqpIdx@1&eKGHcn? zy7~63B-eN(UZE?&zFYL}l@z3NV(<;7JLTw`WC zK5R@iV~4tOR0+HpZrn9vIb*m@_&M8+?CUIv6ICL>>=aY{H!msq&XgNL9>fjE?~z6$ zv0%<*g|ovN`3a`nZ#p$2o&}C`u@0BQ;9N%Cr{;0uRVq9R`3KfEk4l)V6$)6XR#en& z-R4~D-K)Qav&$7|Y9!s*(iv$>!gTEFiCC<`!kl@HzOLX?i$!1roBu^!MEgiw!)U&( zf@;DuY8(N&y;$WGN5*4IiwagF?r%D*_oax;`azx5Ek*_e#8MS`IdN^{TaQKWW-yY+ zjh*GmceuQDa3=scDfzL26LY?eajfUvN;d!jyo7r9h)HBjvF|FpX?cjI-*miL2gHTe zlmAi=LHj5L67Op|>vBi)A`1%dNP=lG$K|lfSu$BGI-R71Zr37_+bXf8uy3*9B_{n= z)U)%?==NYLJj_qct*Iq~ws(%o_KTV~v}1+Wo?ICcyHE-;ILTSp2^th zvVc}~+kjMcd6h;${9YOBO9t(+Jk2#ey@~=pEOo50a>!H}sD#)V75!5=XeHQO3Z|KF zngYH7{?9RsP3^uCBbF)#0O;(j7DrdUHcuq^Otd|j>U0tZyRM>zJA6c2^QoM=Wn-!Q zb|c@9ZN;(Di-u|-9nXnqIIHqt5FIUtS}1P6Ih#6lV#$y{SytzDKhiEhM6$r$BIYK+ zz+~^a{1f~HKvW_w7qILoagTG;!N0Z1@^NR~lT>jt;OEpbfUlaQ4e%%+i1y?-PF%EO zx#gNZYc&DJr#^b*{brlL8QmursHZ%-^12@EtMRrb`{@gczRN)8 zW(s>P!_8eq|4l6Xwii3(u8z#a50Yp2J#UI)H-}$Iam|_|P#P@n(b5XyH|0;w#WOk^ zseBu!##8n(-aXsn$bkW1b7g#&#+486EEu9M#S^-b2lFZKOq0)~>1JpOI9XH3v zumd3+K+I+X;!F~MKWA=@lU(CCHfockdH5S+Zh})y-tPIBO;KR0`sN0_ch#a|_qZ|B zwpITwND=51;M1j2IV`XfbkGE^1F7%ykfy?pC z`!{k6&H%XNjFphwQ6ACi6=a5&d%ThkZzi^OY>>skH*cet`31SU+~^Pba<_#W>!wJYQr{GUy`W zFkfF0C_xcu%xr%LLV{iTzw1BF5@diX38wb=gfJzzp{O@UdFN$67jDaGH$&9ck`6^dIjaD>w7v{VZ#=3 z>u*R%&z;N&@_|8UqQZRRJg$sKf=6UJl-k-W56;bT(q;CRSE5$9-fHPvc2v&M z7fuD7$D~hfG86#2TIRo_@uDem!lwBM*ftfg0HD@;lM~$>tt2P%w^k|fJ)YmmlHJ~a)w_DR0JqixgLv-mTwfTeiKG`D5g z7&n;jyKZ@d4M(%c(<_zO>R5pt;^Ujt?w=v#4QrjhoN&ILm3Rx7?Cs&^SW?4z=zZ;r zN(27u0!>Ta(wd20EJwS*vut27fiZWEa%p#hRjzS5ceC-^v~E)*_^H+iur6`-3Mp>f z0{JRx9O^onqwESJx}x!C8>-1(C;IskS5_NV=BsEE9KNL2K%uH$`fr4)pSn1&0VW}k z)9c5~jT`(qYAfT3ORwYfuaERkc1O_B7PmjKmqd_5?B~%J-b8G&XMM{l;?tFoD{$Tf z!eZAaI3Ss75Z_s#=WS;$ic2X~hyy6N?{TPt-kC?Q)zcnD4^tpC_|+|PY6Gi)Hpyc% z$LBti=q&xbvgH)3@b59$uG@-Uq2MnU0W;+XN}LdG6TT4bShd*W z1j~6Hphci5rF2)-vd;PCVq!H=)rerFvulx*ja9L*ARlEUz1|a6xC@ln7S*YJFOaK@EhL$czxxZ^ zcw6>S@F-5E(xP1rr$|hf>-3NwI?|uYO7%Mz>@~%?~YdD)Z{KD$1QYQ8V?VE;+1S3ni z?KqoQnDRbEV0Y$2DKM`9dWumB+R>iOx$1)tb2&|f)Abx1RC>$A&wghkS}s;OuM;T* z|L#0!O|YM_u3H_=ys9451U!zQpoZU85!cAV{2=Ssn}DouNAima@v_G!ab4tH+;BJd zwi2C&CndQFDcn7ikZeSNPD)y&7fyC*)oG&W;a zH?O-nv_t>QL0NS|@$0(t_^e-;uEl*RiufJTfJiar)Gr8?T3N-E)vkuENglDAngaK3Uwq~3$;x`okm+^3YghYiJ#cKbs(@5EKSLrTO(MqO3V2|{5s*%w z_90YFw|^BeC|bt6Ue5 z_9jP{*ZPQA5#EhTwi$*G>ux%qaIk5g~??}E`EzI<>WecuyJ&JXK8BRcr= zi%CLS#uuod#|eSfwKdJ8yQR&W&btZ4^E3U;h?6ea%31cZJXs$Jny88`Bs+~9ui09L z5W@T4ZA5OaDj{znn(x)rFjEC=uZ$n}0ef;05%oM<8>9V%0Sy$K)#S|zmXKUtxu7Ct z?x=!?q6N1_p~Bgzq}~maeGTi1PEC|yV+lgI2S819a{?Wsv86UrX9@~R@=MRK4U|bC zOk5Dt+FGy`p_!dp_07Oz3?NZb?r55F=e+W3(i2JleUscwgfy z^jD0Yc!xO|sJbc=GqE&M1}jm8=oV7#mSDRr+%K`o0k4Sdhe4_-JkDxg|JgePH@~uy z=NT*ORJA#=Bw?E6Xq38|TCMFo=+x2t+5i4_AjYC^@$v88y=z+=NF5Y{whNtv0zv<{ zu&{72ze4n8u49TlYm5KMXph@kRyp| zzG8N<6@4cY)5;oRNrt}X?Izp!EIGo?nz+oyGkt9XM2oH!v`Tv~;XUj%FO@yfE%N1X^~ zy#AW;z!iSH*QmYcF>~J^O~=nniE<`|SfE@G*T5Is?F_6)M1HSdj;2FUXXxaI9NEKa z*vCz=kkuG62~uV~^iefJ62zHbanHK*~H4Kr3&R^l5YZF-&n z>_`0n9kG0Q3ds(VaJF#n%%b9A+~?5SuW7%lpkEtcAE{bZsOq9*6x+7Ik;9Tfi%Z8T z5!F|!(LVBsRioBW=zvu3bF z!Mr3OY>rqQSfA4?o((dsnVD160$)Y;8Z9$6QZ(^sP}d9>CLpczV#q708=Oyzdmo`r zcvb;Me0|t_YqBdN*@SlFLT6{xv+LKg^P}Sd6DkoCUf45EWHTOr0Y9#_kWdC6G_ee?GW62<(L!ejE_(W6IJQ1eHm#Z$*!3A|?TrE<0nGt=xEGY|vsvM=r?&T@%M>Bf-lBsTM)pac(e~mF z_0Jub_ttO)h+@K=!Ti4ruyre|Mxs!tP<(|s8$(ZO7MDGD&^*2ZS(;!9MK$4nObc$< z)%`+P#(|M4Jnh`$)vHdL{34G3V=26jYYMOuZP$5w5=fHouprLOD;nMlCiZ`p#XR^T zpEsAYD4p+hPv>_?7x7<-;U+!%k7k`VONw>tA{!16sv7SDcF#NXgF}p8>qigBaZlw- zJDM;AqZ?K5|B`oFp4e%ZsEn5#*qqF8`E4nsd@WviL2(Ez6xP&ek?0mV`;rf!O2jBFqqhYKs`7E_Dv60d&u$MY6 z#7#Pj$jX!bYNxn`xdxs1WpZM$Z!pXV*1 zOCig#|J%~^bN zGu>RLCoK4Q?wL{%b5DQ%As|durUUdbvU@;&lxfLp6n?4(I7_+v!P;)le?t-19i4Wr zl~9%p!3k5$`X+!vjQueX@{(}wByf&4;$@ou(C5T<F-}6No{qKrPa0y2+RjM6a45`) zhloYUIT2?zrg5pE!Bow1Z{9ZC0@@aQ?dh4;=9VY4Nv-Nzj1vwOyq8+`5g`Rc?+IbU+ z2x7q=_6-=Veo%KjN~!5j7Vt$WKcVO853iZzirg#?W+?N^^bcEEhCo~0W5Ag2Z&$$B zsWO@4#flStS_h*C5~w*wwM6>vnbQaB(W=xDw=|J2+(l&sbCU!wZNV|5rC$?bK&mwE zfOcMkHYSh+&3^iI#4}TO4csEr#|i&scOcD!wE?5;=^7SHcxE!zg_()Ts;>F7|JX(P z_QM%B`!gjn`7B{NLxN!dqdUndxc#=K7+kv^Lc6o}G!@G0XghS+Nz!wZ2de_J-2mB8 z^?XSbW3Y^?F-VAPtEFtCb|dj!h@0F|3&)Y`dGO%R^l84NTZ|3FWmZ@`dQL2~|8RI> zr)$TTdPXI}RxF$pU6hjWvHxgbQ%E>7zneE%y zeQOW0g*U@wEd%X)rMg2KXx_hn4-%o```_Q#YMhNjWo8h5Y5;g?)5yEHo4=J67DCYC zwgr-5fbUt#L0;k-JrCFv$*5TT63xw&TRc<#Il0PA_3c|OFP4Wya!h7+8eAj`SY=J< zo>mmYx*sMXQiRNJOCxWG5v~T{6Ppp27}X>M1JzWxhc6a2;TG~~DA25xTx6(cJ*_Qp zQD>i-o+lR1NutqM8^Ps9jgrL5v*En@fe4}W!k?KMn=p{;Rrh`L59~I)XV(KI6_qw_ z0Qc5P0MNvRl%UxEh)}nel_P`@%?mpqq}ApBV7&R`m}+~dK|3w^oyZOkM&fh@o`;4S zMs$>9aITE50J*q&o4F%}G{G3z=fY`bz|PF6=HXutQsn#3M@Sq%Vet<%^a zD*o@QVk1a^28E6BqQN@NUs~t95mmR|In0QC2bP4 zNbBL8(yRd&nJBTLcH}bE+}D=t`=CerM47d>!WR{IjGoYqHxm2-w(TEQU^kJf+6{V$_rq`)&td*u!s!WIv2=7Zb@+VFX3 zmkS%4*#4}FTIKO)I4$<~?`~|PX8iz3q8U6;aeqw|^Nkl~$RJ*u|46$owL3!wxp89H zq^>dg_qfj6NzHu9WS_Ii+mFaOWd#C+3ea99mgcsqdCu{Qx^4;23c3b)?;=OoLo z)!@J+pTH)xVA=pl^86oq{JN0~_rAX%RHz+%u0nGDF}ALKnLC`5ReoF(SeQZyj;_~i zdXs@AbMj7u+0un|M*bNqzQ;Abf7Y5I`DH5;?-@s-B3aj_1)axl%`B|UwpxM3!289B zOs8RB#}6W+RtD zJ2LpW%P;etk-;OwZ)-A7p+~?!q}4uhdOq%ZiOBc7n&7=+8a=(nuMS>saI&Puq$K-k z+(c_n7(=ikQ()A>p8g7ne{v9p?%sG-ImU;etFukSG#e*w$Aa4X_p>0AzJ#vP52^oQ z0ymek{F*fuj{qISH7$^PZ61$;e|B%LgFqs+bQ)L=M!v|gy2@P*j9*Q3;Zo79f-+jM zF-(_~Jqsljf}8#{9bv1n>TkQZkf(nkUi0W0XbB?hIE0idI7vmxi{fJAn3Q8v6O|k<90`;Kq0Aqt(Z997i=ZpSG5 z_y)T=$gwf34&GffM;Te37&Ok56VaHl8(f?EyS&Q;hv=@uvc;3XiBtv>ti9UbW=fxKgdGN<_i!x6z2w0@oj@# ziX-xm`3`>XUTqh!NGbJbU2kIaYV#P+k$%?40f$)k&f!I+kT;Cl{8S z+rXBo)?aMj&`+7#S8VSd&KdIXh`qBxoO|IR0p$oJ6|1h3Q`#q=eA0ASK=8; zfcr@=t*0)#ahr9+@TJ0{(srRPpm7OWV=iuI3%Cp3hYueHa|><-tbb7BM$6&`vgKE> zX)M-f&-iTs$>G##{6?(l*!@9zve!vt{bkK4DH2n`m4f;AJtK5QZyH^leN%R57$M{< zaPKOD?)+6G?5n(WY#+z_V--k~si6jG48NAneAu3*PnqNTFuq}YEWdgKC4)?k&S|_T zaByf{%+Gnbu?2r8+lV{w&TiX=(>+nOsuuj_1*|bjUPlSpz zhc1&l(TlFJ*VR&JR-uoG-4VTVI=r5^4Me+Hk*eR|j;AXxIWl#+ zx8-~NRtAsOy$3G#S0DQ{)C6JR>2_$IrSgm|Ftzr{Xx(rBfj3(3SM@AAx*Ewekk zLP|SSa6@}7a?of8B|6{u{FJxEW_^iN+p_+=!XKnJC!Pb3xLXBTMeclvt2dgGPEclT zuOdD1G1HO!W`FOUniA()Ix7qMP#pGDb#}(JcSDe;UP11UY*#^fUsV8Wf)7!@L%iqt9QKvZO1v_C96g5n~kf<96YPIEY#Cb zd&3Ov2Ww47nOzJ+$P>*;LrB>!~=AC!l|?^e-%rV53WltUT#-uX%dmACn&Nnm)Rr@%p@u@ zvKS7wbP#G7)!Xc7l%|R#__|M+%wB6zE%Z!FuRHPxYN-iUQMxVl%c$6wp=IomD45emGK;|Pg8Tk;A~Z# zdKA7dnUnA-Y%gOx?zH=8w82B|zEuBF%SY}7hs{UC^+#XtUu-r>U7a^%dzEawc+*}T zym8D#jGEtNZ&=)Rop9m0u8IN|I4W^KmxB5r6*lu4B+4Ad2Abl5LWms|;rZzf@R`yv z%(b$vG;Z+H^yFTqZO=FQjI$L!sY33v{1ak=O5S@Q!3o5ry7H=S5wpGG1M0dAKDJb? zUzG)~yowD;bdi4NwG+ru(xTIWS}kGEN7x(yV8lLvkd-#9J#ObRo+#BtOgkx%1*P`( z^|1naz1|yj?^{gykJFUl6F6I%BSCy(qPj&|ARrWU+o9YrQZs#$eXp*r9}4aB)SlA% zm=WJahY7M_$~%~P%D&-=Ve$`0hf@kl{chEi(jd)V8nV2wy5?9;x9(3C#7tC`otnJE z{MVXsJ_ia9kk&dj6&~!^A_ld_V>ux=bV01cO>>6@t*Z zMnJj2T?=m`BapC=tDab1o|}}$vhiW!$PXEEV>x?<^`-Td^y|7Jvxp_zd7h|L(kSJ= z;0f-9{n}g;khMAaOk^$cgkWpQj1xvE+;w(pq^keo0Xc>%TWWW{O-e`adIyD)w>XT< zMw{pJOoGB<^5uZnAxjzZqAj5s7Ht8%(fNeZY8gM&6jl%VmeH4F{Nz$Gtn1*Y5aVK? z%ysw?jpmP5A)>xum;xLgUj^W8>anA*-N18kyY1&b6*WQ17lv3^6ip*qQp`Yf+n+DW z+q){tFL$ySjy~aJ{rXPrFL=rnlVDf$%T}4NbtA{q13cbS|C&)KMT&Tu0|WK0hIkAB zqp~u}t+sU&`*GkGd-KvswZb=alH(qP3|6cuMHaL*RfW(=jYOxeUkak=rSbUvW83_h z@;{XG&jq8U&Tl~+gwFk2v4h9Z>x48Fm6>_PId7@F=v=qdpcg{6clr6P@hEA(d3u|{ z*_w~V{P`ztu6TjFY3QVejhjnDIHFfYuU)pMqzs{2;tn(MUZ3VbxN6S;2wI{1fkE8I z629{APF^#A@_kb)OdMXfVeHUSW`!dc!(p9e-ctG}$&m+MtMRu`*&UJvU{DONbG=Bo zqZ_dB1TB8%B^^u;1qVf}-6eI^!$Q)w(j;pkAH8uTNhRmRFS@Iue=~_Y3vsCVRm~@# zsLJGpgwyAqzPnnF47|AFQ{}C7IC`Y|;53tf1L0U#eb9+@TxlR_Zu)>6GmPbt-HC3Z z z)TjYI!x@o8yBQG%L6)58Kxdy{g8+gz+h9mvr^B7WIp31#>t@FpYIlgouPs{Or@SDV zD3YkmxM8+0bsAIjqzh41*AE}$?`K>#ImUDK>4yXH3<-^o6NCYcoHRn+bu<#vMlzz= z&NmYSh$m#FO*_JXpD%#D5z{tagm<-{0hHyYN^uy8s z=xwxNb1klo@hr?R9KAfTU#UTaI*l3G1G$4nIR`nmH7@jMppD0LXv{^?frkCeY?8ce zm!_0cn|WAL{z!adrs;mvNx7@!eZIatZZKDn+0i*EQ4c>q8Pf$jLrb`(kdd=1L1l?QdU|rkvJ|}Ht6Iig$7?eJbR>3Z3o!n7_)B^!g7nwWK;HGE8QMYr|m<9Dw+qFRPgliT$Ka2rtGvFxC6^QPF%NmCB5<&W+LvL z6Z*Sw(r7XX0?zq}qWRAYQz5%19DQx%{s?U=LY8+enIWX;v`^Cf4vcz8X>TcX3=yqV zA8Su;8&^H={4dWvisOd`GZ70;0oeAU3u(V|CpxP`x>F6=q>aRDo6uF8)4QPqs2bak z9eS9sA!nAWXY@QHK+IKkWm_@xEvL7<(<)Qh(v(pj0Gp5Csf z)4$l^{5^jlI=o|=1;&Cbhs!~N1!?aRI~dwD$-fR0bfQqK1HK&=)A3E@XCM+19pUBG z1hEtrqL72Wit4Tcfd6`jV{EqGqZ43Dhe-IMOu=V$H1Lg07<^y;z6ZRXO97m5GB*N2 z*9gD2fHmWQyW6b>)Pp)}CnU+Z1Q80i*v_c^^sbJ|;uxzFhJoL@O&e^h6;K2b%VhA@ zq!o49sd(?#!uUX5^5oP#sZ9t6vP`}Q-=3VFa|_Psl0Z@BRdG+5yYHXjrp=p%g@ogt zaz~wCTk&Pi3Tj*S;QDW_MXu&5mn}_CF#$dTa-dJ3@%>1?+u~u7C*MHJEAQxj$XT{l zw5uU)!`P&jpZS(-bzVa6m7E^qXl~ldNm+6)ab|rGxlxrwT7B^o$XZK%tmW%gM})$T z4tI=zxT_d|v+*@c*9>g{0Rrt6@PRx(90$QNL-{ZlHcoE14^LWg4N$|=@4h=;07(i4 z#5lA3?EhQj8kK+=PFI^FW}FJS*On-3>J8L{HvkbUrfT!I++GoBl-(f1AacV|nW%Pb zu|cnRJ*;#+wQF9&Q@3i8lL%@6CH%b{4wSSYi%cFr=dLjaMUS6I%C92`AU`*_T$a1w;6@ zn{!j>mhT-Pv#Tv4*GUSp_!ErhDJ4elb$?nTlTC?mHJaJ1s1X6ATMeUF(gSETpYDl& zTzl0|HliNNi3wolViigJ)pMx6<)+_ja4)rupCt@NvVn2FS5Ze=cQJZkUr>IrceHnB z^6UAU@=BUR%^(ukl*;(g!~j+5y2|T7fEFPVY4qfjj8}?@Ry8|(LAwuLB2Y_JGQ7G_ z&ADnfQHit5Tp)J>{6}+uIQ+4pJP!sW|6dGtj9UJq79NK6~U>B!?KmVQL($(>3_ zbR1x5^XNkFJ?#nG8*t@ZD;;NGtrn(;=X|o75mlT;o1jZ~eH)#GE{Wd*HU0Lbj^M$X z_2-D$4xqfPe*(03Qp&2j-^PglIB9lh$pbq7y@)F8FN;LCs&P+oUZft_Zm@65ZAH_t zMr0403r2x`r>6e1(3aWP&EI|4iNh60c>E)F)3l40m$4 z*9!sljl<7qktsbg!!Hji2uLIf`rrgjED^VcT=EGwG>PF*GlrhY^5>+#!`lpyUKo<3 zOUOBC>u_nZ*rbY-)8NL`(s_(o*#z-({W=VJeZU_DMRhc zhCp{G;qG>h+1j`u=L1LvN?hSO3vZ`7J2b>N74)+U!?!lY(ku~xy?09`@_neD-~{4> zU;#8xHp};Hf$z;M=#2g|2ier_!%H|lHITjZ6TP%u z95&aP*!#0J9y}60R~oN3QT+psr%f{mf^&QA#)nSFm`svhw+g;Q$Oh0sg-RQ&9!u^XDfHsG z8yu88?V-Yv$hVeoe&|TG|vz?(Frtap+lE+WXT#=HgsWKulDWr zIDTY?9ndenYCR78E92;kp7iT@aDF2lIob|dSrhr_=+|v)EL>(Bk$tFIOa)0QHtqat zjV7GIFhV2{ei6iLQJtD)Ws1-9s~!EXGrSkdLUbC#KVN%Xk9@o9=X#7eR((7)OU~j% zh{Sy*ByO}%AKnvTynK-VtqEC)yx1a8BSg;63e@G7#$oA~!A~*RK@K_b{t>#*ogstu z+kh;{3t6kQvLI52Qg#d^Mwvk-XT!u@`|B?DJ6JVNb6Ki5+)m>F>eLuOce;@th5}Me zttMh}p=%a?sLv?+BD5_mSj){#9b=H@(^Aa_KmK#4;VFu=+7j-!YGg*o^`dGDoXZ=U zOtaN)l)0zFVdB>-%alGxGOU^h@%ihD0k&(}a`y)xi@R=$ihGZy5fLe6ZrkXqKnAbv z?t!W1GfiyijeVs^2h#1Q&q!24P7}T)4dyJ95r-Lec!=MS4mqlYlc{=p1_H4|!twEO zvpJ}czy#UB9wdTd!gjj)X;l&LZ6fh+bPh3oaV;2zMdKBnl9EzolYeVn$tLY+HyvPV z1W4+T*Srs}o-#=JZYc2le562V2v2uAIu~*~6g=M$P7)KB==kt8q#F$bnwC*m<)y_< z{D3pxYFWB*I@PVAC=BLryVyi1?~o}OOmmL8mHq_C3Mb z@1zWWIMdemn*;}3w7~W2uGl2Z2&gY6(PrSzDX}29AWLWJgwFVOf>@sqTKni?^}Cah zaTS4Zy9TBnoYPNAJh(cf`}Bz@s~ zO`x5GD8iNK#E6kz=&n%U&luvEn3aP%C<0LN77p#x{LPL9D$HfXl((!6XNLJLv^=4W z&D>l?&!d=BA2a|$ow~wPsaOHfg^8H4d9f2rOd|*%dybvlcOEHdRe;cs1l}lb@pT7hD-OxF}DsMHRFW zymriFasi(q)j7NhPHk)eRKklB$1cIKNoUD(K`g!!F~BwU#=y+r({4#o%gOprl)jZV zm~}ehOIeW2l9YG-W{kN}-i z<3Jbaz}v)w%}ja|bVPYZTf^Pbnv~!=D&wsSt*cLS#R_UbmPh(YM>6~fhlSAlTK6K0 zHtPBkNg(%}3c}KQrpFWAmhNq1)l242di1?6es2;#i~qG3RCw70$KK}~G3V<)P&*|F z6zo-)hy5qiA|@PgXNIHuQ~2~uE$A3=sSM~_Pv7axlRY%bBZ^FiruC8RtG84|hQj4r zU)#YjjN$}z`@?jyaH;0zyp9%px)1QWxPNrujJ8C!m2)M?_A@9{6H_ik?5@607O{cx z1@PbD=iROh>3$1Z-A7&=4LB~0ai=sbdmY61dtDbWY!&T-7BAEMfdT_?xuRZ1NmK9J z^X;V#$VyazoqBLuh)Ft_E<}jx%|Z6XS(G|AvjESEw}>YOxY1qW`fx~Z+VhJ+0V2?! z-D@wnY(Mba<%X5$z8^YgPgGuPR##e*8Kk00Na3Nwrura4f!aRS+L_Vo+L?~TndV&6 zhV?&PYF1ZVnk!IO_(KnFafDSW2gU8g|ma@q-dtVi|oh0n7H){y;?{0W{K z;}s5_XhqZTfm<5vv$dRQ32nPkZz6&T%1z8Vgrr)O$EVX5fqMbjl?U2N_+b07nnf;& z72T==Njk*~Re(9k){;}+^|?SH9jzN_siV|CynkQ305m|}8qzJo{Cy&i@LDhflxR`Z zqW>5SmSH)14>lcqTl8e~p8si%03+~+->cs=3TTN$|Kfg_zaYPX*I&Qw`JK$DJm7Bg z_SUp#QaYB!3%W(1HRkD>_5(vAEB$Vz{yIRks_;NkPHXWGjg0gjr20y!&k-pM`6ESn zjv%zBXR)oj=5#-O@HhcYCgEfIotHDDZ*Leokk>H%b%*2WGMay=>k=PzJJ8|-*Cku% zNIDE+c-*>({Zi&**42uzB@oiBMAi~S2Mfa1zuW3y#{qC&3dEOUrDNpnDH@MomWz^R2@oZ}^_fc`knvC1R2US$ZW?t1N!?yBthDTSIuAF8& zs2?r6-d@TKyXS-IfMjZEQ1jj(l4d%6Kej79$M`!73B!~w0B3#)`=dQh( znQHJp$ms>df_?;FWhyGu=hTQuk~MzrBnUb{P4!m=(fHbt1L2d@JNyRINF`?4 zN=pBym?wU9AW(1Jb6334fEg$m25+NomT7+tFXOwGy1FZDJDeNmb1UbvliaQA>F1B{$B2{(IM8-0YPBj@q21@vL=WX7f{vG2lKv_PJ zGOv!f%s`?x`@Rk~M1Jb1jN)6rr^Aa>e=bJs)>YC)2GEt_w>i}0?d*!@%!)()`e zxbcpLxPAAzH(-3?M@8v(4K@-xP;I<2Q`!?f-oA|~S!p;e#_2%btPC4i%%q-9Y~KhP z1j-0kOKr^;6TC72o$7Gt-$RqzDlkah#7TkHpJ=ar#aIXZv^G0ID4zq0`f zX9r4e?1O4nZG__gdyboG~4S zBqc!Nt;N4i%tV^8uPep#ar_FTLl;;yiwY{+H|Q2;u7gwjNW zSeo=mzvRiUiwk)CRMcCQyf}2e0Dt3PF9@mE$>z#g40gAS# zS;yXsHNx|k%_Ts^JE)=1(bLM6A!^%ZC4m*f%PbHJbIj}uXn(TcHen()-6e$T%WSzZ zww%15Rc;Qp#I{Z6uc$A6$4i57eA&-dAX8qO!~WGLcb^vT3>27eFWK(Sb)IAjzodWl zV?)CIM+&Xe#i0~y5am^q{jeYqZl62lxS$P;S3&j?A5{faE1TK2&RlQ5qMo*gO3rrd zNMs1V1O$Z%AG1$`nS%?$ne4Wr=~;y;h+HZ5*~>|~n>BadCOsC!PKUc$5_D;MPWlvY z=Ui7oxN26GNgTSF6O}mtN;=T=)4NF9qaIMx_xrEb3`#e)^u(qiB3GA8rD;MzoXytg z04$BV*xZCQp(dcK`DDRY0uK+N^Zb)0eas}tWqbN7ONLw4)Bjd%ZNn+mZxswv1e$tF zZo5}w#^eGbp&5P}zxTN6!J(EZp&U{sxMY;C4T|aMr@EMC*5;*U&1_#N{W4TeF3upX zP~c$yzC8WN>AAqj+!S;tzX;o7y4-*=b&YnfZCAFK&n;B%Q&AhG*Js)4=m74!fXTRd zz;7*vp4^OA*Dstu@~T=Bc%En5qTOZ8;Ncuu98lp%>@N`8?*7pcNN2!EV>^pms-q6I zuA6J0vE@KSZYJ7of9a7H6}uZ{Y=MC`*1z)pi`GXR*2&?N*7;R~?O6L(Cz4AC z{TxIs>xeEeY^7FlI4A`XOLB3L_eY0|a(!ecTWt;rF^&gca2QdhH=`@2HwTy{6J$~# zHN>g{W)>=AdPRH*MBLHsIfH45a%zk_786s!3RDYS1fJ#2o;_3NWEDnbh7ZMXjn{CE z?=?8i{)vhzQeuWYAWYqk=?oIkv6g}>?_K+}ih^dS*y?0tG#9q)U*BTtehXjiGh7D~ zfQ*d3Dgm9A3Fv7e4WZ=2m(Jcag<1p>kAW`mB`WX0NhlW3@n-mCekJ(R+Ss10!0%n4 z$HjhPqo+7YPjuyydSJ`m$ z{2b3blR!s=@71^t2mAnI zu?#X-27UG)pIDd4zk5ZxmM!6)o&x(3_{4W{`iIyq&k}gsx%euW#eJrwxqI|H=-8|2 z{d+bx6L^-r)O=ZKb7F6qMBmjJ^so1P&u>tsPyCu}!RO-b^~8X#*eCR$`d(Xunr^E{cirK#zu@(_Ey`T5Wf_Jc z7fMIeJ;SD=J>kb(21AKtHc+C>>_Da4Wn^>)sA`Ah5MS}SMO(GN;&QX#%W~%2iTa=w zjA=9jLPEhP=^k9z2erKuU!-^fN7^f;_vx+lJfcc^cwC<3j>|41mww!sgO5SqaW+nt zwta(se>OulreHejWQ3}5{1r0>V5@*_vdGG1p|*$HglpXh)dX5>+YQa5pAT%Yum)0U z8Q(Ll2ds@;KO8SQ2lZ%FK5p|>$!iF5i$Jzqx}?O9t0o$DSO@n!oIR%p7iJ$JcDnHK z-CF=*Fz0&;qb06>z4ul0@#(Om%;_;a7;wr!%Z>1Zx|5y9BjTY!s^i})a*?(pa;!FVvihqZxH^PEnRP2dwAkto-k?}cHbzz0P6fYR$OXTpHyEz?Fy zz&B&$^^}zG1s1#xfbPp?eijylxZ>M?d!BE+7kJG$@XV%LhHDE%6A0I*3EGY%?xc~i02^NYBoY2e6KRxoM8zLLCn`O?a8A!w>edHg_Tu+@*S z|NpV|7GP1W-5)5Th?Jm!ln6+NbVwse4LNk9gh)$Ehag8BYM5aJh7cG!q;m!kX#{C$ zq`O1Vo>ScU=;kWpjpF@RlA?V*yKE7;*Kpa1p<>d+esMLXdQ9t%FPe zbG){4dAd>ZE`YxqI1*% z%jr7~ZXyEC2s56G_A-=?M~{3szq}Yr9||4a#?=${)SxrXKjBRgo;wz2IQ-@6#F@f) zl7e3C8;%j-`iQj^N$q9ms7v5-x&@cY6U01l%}9xL>P;8fY6%o&MfV2!wdmb5^mTxu;q}$4%el5z z6mRZkak6=-W9|s+_6eM!u^@Ufh9V=g=LG!(-|M?!P?4+j>3a#k?gcXdQkP#x-@w3O zy56gxxEO6Tl#=Q(TL<_ITpz(ye;TX*{ztCvWf}mafEwZFDt63?(N~;)+E$_?bJtE@ z7~aHkIYkoZ=_lKzOl6dxY4CBS_ec4-F35};=LNr>EwUt;AC&%kPTKF}d^Y#(rl+k2 z3quEMF}F(8paHmAV|&gURqd+d`MSXg30Dt#870O{gKhtodwCBx=IfnjIfeSw2enRr zeS9jv!Bcy^7_W$?Kbm}vLw3>ZgH@-Ysyrh8fC}49r|HH)fS(Ed~UX0T-hdPS!r@*YVMs{#| z)j>ODUh<;F+XYz3^@8$|{YVHqO!6ZIZ=dV;j2-n>-57oR&>kb3p{~?Ee9Hr=Vk+qYh~4 z`DUC{qAMuv?9SF{k`UZ)8ghbeS**Em#`oP>a-vUpStGOwI~>KnjFPLMYA6#PN7!_qzwa1(s0D{$`rf z?J#gK50l%ZI;mM>2(AwPu~BOld@>aHVFIDRfo8egM7)4A&?jTg} zKM?-yGU&+ClB>`IOV@5oFRv;9Ox-)0R%G2uW9;b)rs8Gmdv$^Je*tc=S8<5lOtrfw zZ`30Nz(w3Pgn=BFk#)4Pz6J6HIxYU3i>05}KHg_~@G$V~7|)S~ypbgIqehz3T!tfwLK#d` zaZCHfj*;N6L&uKLv(W_C*JEXUUnzvci&Mlb5|l{;9)Fv?vWdN0b42kaQ;qyQMJu_EpEicxBaoG7f6YBjfID>ij8$^p8qxb>n9kOxpw zK{O)d$eiGnCmY2><`e-aIBu`3sH%LVijaJnOD~2OK&lVH{bXW^@=w$nJD1rFGOt+o zZp&ilUWu0H7&!VKNHg2c0g|jMNho)1%;-Hnr=<5c7wzL>pm51;L_3+y?~)9&T2jWL&ST{6;sPm0`I#);b zA?2*t5w9~FOQIw`*WAnwy~z>h!=s7$t0&!g!Z-x<9wSL5LR{;7XVB7h#=O~qw_jm0 zmd&9l&t5N-i^dOn%ix6b`JLaXMEDrlN6tF~va(gdKOCufQmRR$U^BE?5ebe&M&Bd0 zWJdE#Wvgp!PGn)zWnTo`(q(<$*uCtK0Vv5|G%`B6UOnkT*NIm^SKrWZ{c@=r4*p-p zCs;O~GB-3ld4iQYZ%(;};*(cIULQ}@b!*g`lxg&w&peEeBmKf8Lmmi;rw9v(tM{-l z7a`EK_D6_C3{TeIEx0FYZGTtpm5`!o`~37`>xszyEAjfvO?LieQw7+lK-{ zLP2Oz(UJSOt~-7;SJj3cpt|AnPBK~@;WN~!n2+J_I!CZ4fdA*68y#~WJp`q<1jjX# zo^l%}^nZjC?$1=aQff2!w}CiIk}~KXd>_C!eDdRWeRm652#5L=q|aDmoSJ6CMghrC zD|Jymm1ak=6$mQ1%v)TTxw~@LB(32_Gb+i#GM`m<{r=IoUxr5iru`FbMFoVwpz{I# zqxy@@83SkOI4PcbqqG?hLGZbv28zg>SIj@ghjm*hhf5?+M7^koMWVXtVDp)mty*Ql z0ge<}a$MYw>GPpN-=_kYOR_i{IDNDPd3BVuPf`jXXg2@QHZ?88ivIHbujy_y)-&74 zb7kKDU>IT9omqcY>f=YeP@#TYoRF4ycO^qny^Up7BG1bx%JPLAPEGypbEExdY-G4G zLGp2=7UF!iLSD&rFUnjjo0Lwbqzs2T*c)P~arix-kG}2;2iJQXxlf-H?TkSb#W;lO z!EXG7`+`gq7e`?NcGWZKDuU&soI0A-Mec}vSS;)h=vK-w^b!nZP)vr9g!Ri3omDKzrBgm*ZN#@ z6yzYw(-8bI6Ty%ud0Y=17|rw_T^F~tacV4#XLnj*p{Jt>w@T9bGrOuBXmthVj%O#` zzl4mKVT#WuVbS)Dp*T%;wn*?hO{cxYR*s&k)W9sWAroAVfsYq}UhnkLCv$G!k(k0Yhf8zyV zUkwKbmI7Q-#6C$3pmo+F0Btr2-6*o={RR-Xy@YUYkG5nl7hj zFU@66{;^ml1Z|f8tp&io5f1anMSMi(fk0kLGTvIu)6J0AzzYIw%F)6Ke zi?O1yT`+Rvl_AHCj%UB6Y9WKrM}A!5Ue^y*`RCONC)9KFK6Ea*Ece^x=bSUA_A6-BJ^zCwyAL5i!T%vS=FT(j4Mno9m{0B zzJ4%%%xs4r+C;$6hg&N=rm6M-cV+@UG}NH=ATRl|^V)EzY+@OypZguDm~%~HsapY7 z<`G3N1y#~-7Egbe$eo_MOU09VKt^3fuLYmG|Ob>`yQJ(LUk4*x9b{QJEXwFoSmnqdfz zyv`ydT?Wo3MPDxuQg%nD6`0j)mT7QuaJ(%gOSe04YIXT&efl&p7A=2=(0!k`*i0YY zZeAwGJz6x@-?X9m#F#&KxZw#-MyFu>2*gdles4LYD&TUu;FF*h$grp58R5+)O@ID~ zneR%P;8m!2z3%o11GnD--uQMkbOgKiFKqq-nd7|wJclx?fyCM_+1e1%;nDfcnxv?J z^tf|!+Ce42T;1^OZ4?Ts>K9hpLP3QU*uKZ zWg~8SR1#Bp1lz*SB`V}Oo%D=Mm+1Xl zPHVXI(fg_GbXDj@ZwdvMvYP09g+JhGw*gz7BZQH>F*}1Xi;tKT0QFeJcO=u4B}oY<#^WEVW*b$-K>%syXA6V2*qe$9SYLAI7af zZiLu*geG^K6nEN9ZqO{&P*Ks%Nq7^ICquJn(>R7p@J4{)@t zqN`{WE7&*-isBt5Grx1LwRHsZAU5I>Wa)3sP-z)J5JXHWN(Q61>zr~u0}v2_eRx$A z-AeZu#PCbCm``r0gheOznQNuOL$VmvJDX533)rInQ2li6?(blA;rTqjT*~;Dfo+7AuFe9W1J&cYl9d%q=)7iK&-j`KA?JQX5Lc^f;S&Zsd ztNiMB$~&U0>D?SQ>l9Nq%3lJOX`T)nn z?zZ&Uc`nUEr+o%5%LJG7#Cvh4Qbhm<+Nl@6QQ_IpC!6yk7H3;9;I!jVJhQf52;tQx zVG5|Os~ZQ3o7TpnjQ$1Y!;({Od^N?+?fUYB8_|QdZJ6`tJQ?aR_ z#z8IwKL04`DLZFkV?TZfqW&pyJ>!xG9webi_YLRBs9t&>@&-;utiY*yxd1>;&r89; zO)6Q`&eejLr{{`6ey+YKm*!}TZ~A9QyqjkHNq6ecCnskMAiUDe%B6kYR8rxD!_jmY*`Kr z87H`L-3nIh=A>&nT6BZOa#}-oDjH(E9%Nw0v(J5}rK1~}nkoVssV#PK^;Mg&a-bTJ z1GAj}D+kKTz)zk$@!M^|r|j5^NWL;rQ&XD+3dw?NR8Uw7ij3+PmX*{G+XAd2sGsDX z?6V}?HgJ1uqQSENTUpFj062ap9v)wYA{Z7O1?`tlv!mWkvN%!}ti$Pq6fv2i=~gpT zSqjTyz;lJD+3?K(;Xw+;xW#v2W&26AZPvNmk9<%8uV9TI7SVhuws#>_f^3OvQd~ZB ziYRaC&#Qoxk6F-JEiN~U!sE9Y9%HdgJ(A;Qnp+uqey5hD3mC>(>10;VzMM0#84Fz` zPG7xCiEzIw{c}P$1cbfiL5i?FG&v<@X-bi*>1=Cxd3lygNdx%Jf7a6L!E99rd;7Xo zsgGn|cPc9@1L{<4|5&U1R?#Ku_5%Z}ztpQAX2tmc$p=+)C~Ea>7~uo3Q9$IRq$`1)RQS%t3Gl8>Mv&zHydLl$-2-wf z#^Gc^=~x2>SQLpBN+Oh;Ptv8qg$BjL^CCVyBE4}wG^b`fr*T?KcUd|5jKsO?oKigB zG)!&8a!UNpRG-pK_QQUbm^(b=CXO~6q)S#Hg^Z%nb8;~0tk{2SqbL2c)}`JSC4cm^ zt)+X#Dk5XZR5g4iEE+Ci0WL8=-o2~npQh(`qGdZ73zFdlyWzYqDDW&N+jV-lsOJ5c z$5r2cX8m&ji*$9UPN6!hWMtZUAAH+O9Jr@aWll~`=o z>;aFu{5aDiqN&{PXnmIFpAClSaoPzNel`)aY*2YZ=Q4J&RO6u6YU3*&G50a8#`!GJ zt{5&ES3(VZe={p1&0U-j_j_Rw7V_*l^eFGAqS=6z z=rdsCYzEwMtgyho1eTwOfPYO2*@6Q22>!Xh4(Ct^`#%975c=423ZS zX3rJB{utRt@@WGSQ8DU=EsXS7nOFo)aAKSm3*1c`bQ3Kn623bEjPmHG%m?tc|Fc5M zg`6jZi%qK5GYX2sstVuoYVyH;$c!|d=C_QP`lnL60;ieFODy8xzDJs*RPNq^xSiDK0Q zg#C8Crt>sR=e&f9V&X0rNVUCw(AF^$!)MU`RxwG%&8P6|)fT9y%e#hCEU+#BX28#T zy+hQUixkQrn3Ea=1G`FQWIk7{#}dF3Di5OFC54&TO1!-DHjxZFQ3y6#X+Koyz66rq z?_}Pm`m{5Km*R#L}EFY9f{rSJ$CU>6A_%FHF zU7W9z@p7NEsL-0)!;?nyMhXq{(P)KO*Nf0$5754`F=8`$_SwB`MrLb>*EE?UfB7rYH8ujeTQ%aE@V;1r*|(&OHE$T#km|vi-=t%uuwC)SDMM zlI>H32FDt<`&|vtqK^+_DNibU&XABNEg?&5VXQQq)ZFA@fFHBTnbcaU!VCSN(;d^K zza>D0a<#^aYi0_R0pxvo^4HPXvabJF66uOOKqBEkE5nK9lii-IL8-+Swz08^%gXo9 z?_kAGV@8Iii~C~kdinTpBffLREIg~*itw=8*ey%&3z{rkpJ~v?9Ap=*eb3;J=+6>A zc@)O7Q3Tsa6vvo~-WsnpCA0trutUF}Jm$i01vgpqs+?X*b#r7FQkb=gM|VX7bfV^v zZ@z)UA=J|7ySbOl>6I+tl2-ECVYtZ<YCmvQ~W`6^lfV! zq%K7xU^`@sxtB|C5%Qwq3SgzwBc)}2@0xGSLAK4x$=*0ZxO6q?rQaQV{_$ooVYe*6 z#kKHiKeB;HPh-tV@`uIx{fxzqSq$cRNd!z6ihxdQ1RBz>^@}F{Lp|)3UBH#Fo~23v|BFaOsQpvZrum!HzlCJT z=eAEXPBS*Ayme-p>@kn@Pkw3A%X;f6$2=VPu+T9wGgES0E$UTSm0yviAU!?Zz2v^{ zW~qI$1W!457O7R~sAC>+%ur}x=+iLolv`AV2wp(6gfrTOU35uDS-8L_n-nqLP%WAQm=1|<_}E9NR|VLn0y6XzOuksSK{=?8Ch?<7!Q9npVgR044l8{5ZS+v7 ziR$#lhwtIZ!Y-AVOVZh4N7FQzCOzyU65@fr`GxiFn5Y5oQnpjdyh15QRDn&seT*?sNUmvgMS8jFpzyz{hM!SL(l-f3X&PX@4#>WMLS zmjNaA>U%PZ?5iRlV2NGy1Lw>~=J1C?u;KsG6K-h1sd_WnZr~rk!}S4*{}07MjJH(X zG?hs=hlI4GayGk|{T8AFCB6hV#XOYB)-5h}aCOwR^KbC0uZMkqwPek=^A19TjI-Q% z=V!$?Ib961YHLw(+kY4(|AmQt$jxls0Uomj{&J5-f_mnx!-$6SrwWsPzBah9);n|l zj3%l>)6h)Jm`RsgF+X6EvFotEY2Akzco61?SZxW*SGUnmsxC+0Oy#s2Hc9~t`zI@n z#0-A0?tr;#PNx3`oHtgw6&s|q|Bd$h(Sg)Q(b)L;Kvd#)ipX zabQ*1EhA7p-Fs_qOto$l&`d~>-_9~biSuQ>f!;oHrJ`z zJ%)cRU_@^?V;7QAfq6)FM6CaP#@xHGu;J;FC$X0*k~LDFN3A1)&~u5CR%}>*mp`8` zUsn%T=iwEVji0N}u0st|XV*z0T{pADPZgajfjdlzkgaKuIkh&968hx~I{5CX?E8`g z!eV^eyF0MS>&*EwUAUu3&J>JwKZ|yMC9Fk?1|TT0&>wRkM@c_NIEU*pCw*)zTg1Wd z-5|r;*aD>yhYd%63I<<|^-Vn+W>s4?@(PQSLN_tqo7w7bJ&Ss-mxBe*CHqnjX zA$jLZ&U)} z`B9nKVY973K;^He?2sCup&)#w?Ms*y1BHAMS(tpauJXywfT|sAYg=a%2XqM)Yi~Uo&zIUK|r;%SLbf|6;V;H+YIXhn}PSa`d z@OI$)W%4Tm<5|WL+nV{g8bR~8Z40lsep2j#f!n)=V)f$tj7}Pj!qUMfJ&4s+cG;|s zs}0L4$DV$eqb$z~%L0fhjfREu=LIN=trLZW?C5NF-mM!eK&5%NX{cqZN81pb-g?vC zqC5TJTo~eaU_}rYQ^`)Gmo8PGDF?^tx_LFu0CtGvdkKyr@S@oQv~-9AaO)5?G1nQX z2r^#3(1L7N!1(oa0a&a-k&6UNmw#495dcVM3B`J?z@irIqe@Ec$00o>d$Ys3v!oFh z*6*`x>{VUG1&^T+&-LVj3ZU&VftHkhu8%ua2w&~C)TIMZn1g-pt^N8XwMrJ;KoRN zwL5@Co#W?jVQ$RFFe8OyA3Xqs{2!Q!>-#i0N0*q^DQOTTg7mW}Q&eU;So3~E0=iBI z9$FVWb#{5BYJ0vYoJz}uNz|HG0~v|HQ%ET;N8P*PE(OCm&z9g!`wH67*y|Nw`;b z#rhN|n_@|i$ffdA#sxGa_B_nHPl`WxD3*k7GHxnN-F2o3zB4V~sjPVVfF8nW^Ymx04ah86g>BEuME7|iNA;_C4()EGaUE_SxNNLM5}d1cSG-j?E3c>`;`qf z@;K#Kf#+$SGy3u(6u`g>D0^jZ-P=@MSvh6#KkmxCgTJlcR?RzvGd&&R*jTD{(%ce- zje4BEjH?{lvRFiLR7EMb>9{L6rT?A4B8X>b_)90Ckq~zuAASnJ}N)%-vlFU z>A~j=uX)t`W;E}yyU9~$Y6+4iVSWC;K8KQRu~m+P^4Qjx5KviWp3oS6G19 zR!k#T%?1I=GT5wS;cbwYH01&drAOO#kLHDE?30Boo6BP{?9v zHxL6XWYeR{qn(>SeyH}qj8D~r;0B-!bp&b7% zIdK!XG1AnoS8BLxIWf=P+3FJl`qOE~i{mNHeqQ>^}rUbfyB zM)~jfy1c88A5pDHz9MJ`9*~(Ft51pD+Ep~Hxx6kfxDV5Orar?RMPIjvv6kz5?YDFO zHrihj`1!I3E>bq^rso3qxm#!XnOUXX-f1?Bsn?gsUYH%+Nty z!Vr6IO&3T(LN0tl9u;U+)MI9keUfo=EsiRW3a1lJ&PA4?nm9Q|Yal`edHu&CQ->7% zC2S`jy&X8Vb+(u*Q!*g*fC~Zm`6;>_h+hU+PmGJ4b6tk1A-GUyQjBxrI@4*2xobuD zd;e_RCpa!gd@(_57@ZPIB)6;{hzgr;O}ou^>@Oz)E&_kr^kni=SlZ=1ROP|z$e1cS z@}s(6Q3D`xi&DT4&$xJEUatp?g={pc0H%5azJjsw@2G#-1N*aE7wY=}2=>-h-C_Nk zFCN)h&eFH{|-+u|;3Aq9t2A8 z%+F7&+~c+W#M*>?7Lgt{eZXIv_{1~^z@<8~`d%P^XVwz!2Oy~ZPwW6oIskH_0U+JZ zWiXbT{*~g$V#}YE@kIptZbf7(**Jq9fAo`hgI>Wd@z8^0d0abt9YIhkcS^qj1QfE-EA#)`vnW z>=^yj{yP@-)u`GjX}K@ezwFgW`=@IofFfT1Ly;+J>&k%B{Ttsa;{J&;$PwV-F>v=S zQLI?esK)R6Hk>vhW}N?8sWq}*ECLi2h~ZWc=11C`ZNL=WEsLnkko!bRqsEF+lrd=D zlQS)BWfI$%^r4mvKX%UNv*b!qGobcwrp~}8aE_T)((c22cNuU#37L4E-Ox8b zF*OBb>#V7i^h*wJ1K`4$Ds9}(` zXy^FF)?HN>f%Z;u?iI7Ocg_9WhqpsJT<`fwnFWzI)8xj=TiZb3UKZ8o*;6gfQO8oK z)gL{A=DB?j$sYn7@#5BFV7^hvOAc~ljiSOIgW|eg=LK}0{n9%>=IIPMN(u}$;~V+j zF}|U}JGwg&Zp7;k+WyfKbu67VoR$lO(^O=(>3^-!soq_gxfAkoS;aKgVk(#m%wQKS z63v~8BY5xo|iZDY_L_)tW=Pmu?Wh;CS10i2osX-G+7XZ`&W?4bn z6rCxOAuR6btPM;SV+wh;lEwqA|EjVbQ^ zQ9jnX?FI$D1D=6r)(k(KeXfyQY?k?P1qKgS@UPVG2y)GQQJE!-w|k)7iyvybLLuH& zO|MgVB95}0;qVDSs8Y%(m&cRFy>}-f-LOtL)2E5(Zr;q)Qa)C zTySX7lZxOMu4HfjLXo8(_$=wMYvVj4EGH~4@8jsM?s?=}h8?8Hh@<-anO=bLnxPnX z)irC9S^t{1YfSWG?4UWC6a_)s1htzTd}h zz`JF$;2qHl)D-?KI^1So@|!rgnXCl)j>G(|NeV6Nmfk)Ak(rbV-2GVhT&Tk^|1nn} z$7xNvcwB9NW{ycCei|btA|}?)tz(b< zeaJmF6`ebTWe6)iy0D^nh_n{YZ}G`DFCjM3a1R48Mb{^H0L@3RMQw(ZQ7jkffDe_N z6>m2IfI!Q)B7vGDrToDD?yBvC4-H<&&z|i9mLK)iAFcJNqCM}it%$#0f{UZYXV#jc zfpA|ncp>!@*T;Cl+YX_qmn<~awiG>HHCz(48Uty$lv}~i0Cz%<%?p>Kapfd+u==L+ z2cV&?l}Dqrlt)gnE8urKoAfz~vOooXwKcjRskI6e!~$0=^@%$aeW%EH46&IFuu7k( zPmoSGwLV1bB$dJzZmLnt)}%{k9EYD5RVZDrOqOzKD+2E=_lw#Z7(P&Qm*q}li%CO1 z3T5l^zolfV%f>2x|9T%S4_Ih+DCdzB9py}&NdZ?!Dj$D{D7lYvrGmN?HEk)gomsG& z-N^3RyE{)aqZv{aHK-}!CFk9*3u@Z`Vs|t---lz^^7Bu9uD<2$IW=>OAf9%WQ5w{sX7y#pCdLjv;ny@3KW4MQvw zvp<&N!@jKx_dd&w)+L_@zwVMDL+sV2CO&ZXXa%2sJ50?;Z=(LXK+lL-3R z+`gM@d%wyB$;;8%q**d$#;7)>31;>1R`AdHcj80bxpP_~#(XQ#0G@7>HRK zm->{V!3-C}eD>|o6bdB~u0G$>r@UStbohbuEg1EnPfv3YanOla|-_6w7?*T~qGE>O#6G@1~nav9gn;SzFQ{ z&WqD@OG{^@b8#psHLabMNCTE70=HJE66+}%Bbt8y;*C)IEwx`!Xtyfe!$uPH46pLd zKF8(ef!LadV=0FhXDxB?X{$M6c*l{!Ebl#diRO!R!)KG&pzYh2Ym&iT-??f|W{ zUlmoE0LFzJuXd^v#J3iOiV(v_X8&C;o`V3z`r#k{xW&rvCQ9KiAdv7isdwXrl6Pfg zg+ZUV@ycP2&7ls_vz!wjZ&j+Pn+mA{?(zDt4VWZGEk9Kj?77Pdqy|qHfbDs43rJ!E zGJ&OB36Mw|%Mn6eCzGR&BlSng6^j!2?v+4x@iK{VH{*UW9W_f=rxACdQOUul%y*`g zTR}PlpSRFA#rBfEQjgtwkHS_CE_e9z=I=BlY7W=Pmg#xHBS=Jx)x`t7k37+5{@h3B zK79uI6O@Nny!v*cqlP>FN6@n%m+zEk`|pk4nSoz6?o6oq9jl2s9wEs%+=uv_1oZ3F}LGiv5{d501Mb1U5@8>)+h5nNjgvaL%AZM;84mPyz-LbL)U}iWRg_O^0!ZSoe~g!Vc`x-$ zYWhmX_@>W!FTX0wWcI@9fIbh3lf`{*>BLY*ZtEhQB$!zTxbBiK&ua1=h+&G2>SVRI z*>*<6D0aj(SITseQqSLQ}a}@bxc8;g@$Vco_qK&DInO zrCb~-b<2(da>uXttPfXx|5vMt>?>29I}Yn-I?UGf3_v!(XqC( zjaKSQyt*ZkTV^tQEt|OJDBGkhLUW8wADfv0JD{PVLFFhR60;Bq7(3F%|FZ*hj>QJW zCa4eO>;Rya-pUj+wvGu{EQ9_@4sjF#aVHk-{>E7Wx8*E1K~2l3rt&IJh=BVj2fd;@ zIJ=w()Or2*953`_*0V3YYp{iXpg}Sc!}x|>e3seAy(Sag&rx-*T34+gDC3iJIX(+~ zGcnO0$%3ocS0K0~Y;TsD$X91_0wh9`YXTzX!9dI+{-li*cc+Q>R}uqlmyt1domph> zFM9We;GEZE3qZ3C3xgWlqL`{H;AhB@Q+ERu>8qqcUlyR}T0o=CxlCa3qbvAQy(2hF zXM0cAv?IYQIr^ivn>?=ofv*X@fmrb=nIagZ?YI=q= zBv$$eyFHjm;7Wqp(IJ)VXu>gE#XWuU z0c32U$t~+@15q-fPwoIRzk7Q;p+R%qR14##8aRt~%ETPSw-ta8Y;XP5^+Cbj{bthF zrZua_cqFX(SkqMj;h_m67jM?d0ZFRm7NBhswo~w56##e?it(c*=6|{lfC!Z>5fgHp zVi@twDm$PLw8@HxLiUAM9*S zq-OSWOpGSI_;}7jsZ>_&1`K&3*q+$-G{;SIv|~S2+4iI`uNza~peV*uH{u7-(*S8Pyw^k3Srd&5pRlbm7LtRX1KI1B&I37g z;>&3*6Gn^nMv_OgQMNDFqd|M11Z&yjT6w`HF zjv0!?lqvS_Na}|W@|8TcJ;FG$uMHLEY$WGQK!-!-PX|vdMpKFC^ix$IEnoJrk_)3T zIy%N@u+UI>@To^=TgiFl^l=1JJPgMAAdWdn*o6nrSHq$WKu@D6VfA@;g?G`es zw~-FqkHsY$wH`BEE+5o;pS{+g(REY3Olj9!Z3_>kWWKOXY7G|-Jo@0)S9$iP%>BrYsTKlgJOGqC@q#PY}9Ipc>T%jS> z>#jR|Mat%s2a|Z?;0yv8(Bk;f^W56$p*Op+vsYABd)t@~aN! zQf@k`<<|BAIA`Eu4%_8m_gb=rrE%OjunWzdL)W+?@9;@2^42!Zcu#hL0R@IKK*pb{ z5lZ==T>_N%Q;=Z) z%r&yTf6HZf$A{7;AV9)U`PJJM^B0SLh31n++#6`KZP>-HEq5>ooMTYuCbYz@oC07;q$wy}uJ)~bsYHJB!pU@R~W$bc{VZb$~H%_ex50JO}#y~lRa zhP3H%%?c;#Sc-EpNN;}+54V{nAK;E$pY&m>rUvwjnsj$1>jIrt85}ccjE~LHRjG6# z5&*%O-y)(tTwHM-Y`3&1@!?C!>$SaIncg1`_)T6tdeZxaV~+iXhHF|g0tlSlm&+?V8o1xapZj6! zFNo_oqAFi~r;TQiy|U6+dAhRg>f%zur)2(rb_HkYRR*@$#8A~QO`=PH-c<2aFqnY>wK$M8*q#q7tL5U%w%4l7q{9+<(7t%Wyg`?_6J)I z7KA|gM}fW^L98P$mD_uazjP($e?rgD;Wg`j?cdkCop}%E#<6CZ3XH=zlS`j7%qre& z{xP?=RfpT=qDHO~3w{5y&!QsPpo}sL?=kN-DcQ2DB+NJv`r<2>7CyezDCP zxWGJyE>`7>j&~?2F!-)NvJQ%v_)?>)wPio7=341EmamC=_quZ<%2&ywP|b5_lW-cH z0rKI?8_eXibwxil6TGq?0zX0O70fpI^i7&*P1X3V=Hz4lI;^U1FO!(GXKUrUAF(Vs532*tAqWP@(BH83**D;_12$zrnBSuR978a^;Ta^(_t^X^~Y>|f-wXR-Um2UMfU)33yi99PTP0EY1O8yPdjsI+Z zuNG_Ku%`#;0JhM(Cw{5fM?gtgf$w^Lu8F(ee-&!BWTaz-xRS2mUohJCrxrMf2i6dz zhhRGgT%Butl#x#bq!i`*Jf9d5zi7h!zD?K9HM;vg`j zQ2@H*ANAD&j|6{_;U|mG`2#%NQiH{|@}4+W;1=yT_rrkA4JjC`HF%Pit+>GOWBQ}r znxo}u!QCA{MX=pFsoBm6smO5&TV1>2c!m?o97&4dEyJmHnCc0Kv`@Z`wGL+E7XLi5 z=XR+9qTTCy{=+G+opwLH(+Hr|G#ak z9K>`%v(;BUzm%D>n|7z*kc$LH>6e(JuT#s+JvdZClQtVh*TQ(0|U zaBcwS8Zv#Po!41et$h< z=KA1&b|^^|^LEaySI9&drT#Go7QGoIz^2%@Cf0;jAeddhsg?uzeWpg9R+1{CIi|@V zHowunv?ixeGjrPCH2hw+Uf=dZyrfu~N&JuDsPOG%S*t>9-@KBd)T1##PgZ$vnN(F( zkyNjee0XlP1;n2X04t}2+3*N!(f+$AqTWiC=ocE0)TOu4`%IO&10(%X>k6*2B#c0)T>L2pV%x5Qv0E}OtVH69f$Y~^ z;T})`pf{T3C^GScVP{(W#H;W6CW3bb@>ravpJSQEc0#Mmf5DcMkkafxvu@C#>ujD8 zP}jU(SkEIwjPrwkvb1j)0P**%&M5x)QL(OGgC*~HPJnGliU-CWTC~zdo10MxX8Xy+ zH52pMzK~W8>9gN8 zKI`K*pSb$ccc}}9QIdSOES1i?B$+;2R-XNwNi7t_94z>G2*2s7K<20!H*h@^@01t6 zHV-lLdI){J8}{gWIz_lnDt-qWqXqKCk8+8e#0ODHqkUpIZ@Bvgp;NKIU+e;JDV#SFbm1DKe#Ki&`r3G036_QM05L zzZ~0X%AseMIEoxcedWecvKFseR&10v>6nmkja^bb7z)j_(dX9}_mT6JIz2wMaH4Dzis_X!9pOuM)=6%Mvi#q?k~)x9Jy zPX!3AjRHb~S5)rk`1#{9V8D=Vp_uc;Fud@;>~%s#FgPBV+8~r2^gvNj(Gl^)wEBGz zwqh9(C*(ow9>};^D8A9>fx%aOJC(K@pl6-kRe%l2oe!@5sr*r zlKo7BVDs@CBVbM9h}#*|`2?PA#k-e!nX^U5yy34C2eX&t-T5ow;N#+a8(~jw+8%L& zvXrblE;O85Ia0lD^_nR+ir*OGOhzO5OR z#Z8mPO}W@WjKkcEyf+6W5R`D6udQx6E6C(eNa&@oF5ly^i;;=WR7vv8&|}kUfukr9hpJ-stk!7yiQ{=92XWu$IW-ES2P~-v-YXoX z%bwH~2}JT;XHng3T*z8&aHEQ#g$rTJ&jAKpmuPt!-_#?)V%N^f%-PK)Ui2ZS%YWbuzNh&=rp67t9_$^ z-H}rCAr$JoADEJo&&2oDnAx#d%96024wb;^yT)6`ZOF-00y|hZ<-OO;AwK*w%m4b9 zqV$)yP?>|Yi29)RRs7qsmwpK{726p>ZW*@E$5ML3nd>pX3U*Z146l|b0}rd$&MwZW z?5)O8KATQkU8}Q}5~yp}p1lA>SdINjzUK6qkLe+m~>HEU9_ce&$yfm!5D<*$IO}KIZ@hfD!i10q(?U4}n7O z7aLb7VYl7RZsoyYr|L%K+HY_pmZdH0)6ch@*&c@nr&8&|* zl869fM8q@Oqh152Zp6s4v^DbX`cFD#o5e*4xWvjYy6b%~{xgo*6MYeTXind!{JMjZ zAC0F6A|9g;0T7ge>`J{4nU7ERj5OD2?O!g!dc!47OU_4ze`aitDkU+dk|^{mB*sWC zq`7JK87W%GbCqc8=`m69-LvnYF1cck6f!WamMVQhCt+i%*_9wEX^0{7d17s2vp6XS z?of?j_vU!OklS17NSUY+w;2((N3_=lypav1Hy2PC&?)H%xsS=+cx6!VcEs7_Y2EYK zz-#}B)AIe&(J2bz)H%$!u|2SOdNdQ!YcJI)jBda%8i|o)Y)zf>UNa6@`5t%{2J>_FZ@!p_tUraN)>9bFTGqsS7`N0KT^^p_ zM%yT+LsM907%f9>Wb-3vq&}2GM9MTIK1tJ2H|}yF)pBSc<%2B}!LpP`0_^T^ zA5(P%`m3@;b-r?@-_w_pzNqe36BcQWgQw%m3#U>o!bOCo(LgqVKhDO<`6qS)TE)ql znVA7|Jrm_CWmMxlR?Z{+-!8f7yVElx9J*WQl6`wYl>qyDRAN%g^;ci>sI{+@5cTx; zu6n7*xJ)^2tdO_GV018};ObOjdGy$LMTH;D`Jg>>akeP9EXqdQVi?BcG?yjc;I*nf z^?dJ1gL}U~s$ihPR^&Avs|&%Y+@7>d0~Y!PhHdRPvOEgrlbtzYx#4I&OJl7pT`v8c zf`V5~5RiaDvTi&Ac{4&eY{2vFauu~7RUA#^&x~d)5Iisb67Zn2) zRa(xPr%reIAuHV5ndSJCJo0YAi%hv>T&SEQs(_BQjJ0(!sXJdLo+(i9#6Ab z>E1CL;9=7h5BdIw$119-)sDk#rDl!#5)!Y&h00U_!m$4;-Sr`aoZVi0iLdEHb+(C1 zdUWZ{c8XEb5A*QBIW)HCd`x!aE6w)WY^m0e$}}G6D_U(gE!n%IW~FEPr30L*$&S;n z!q_N<)ERRbvrTSo<;;TDgB z0CK19n`uE%JgFm@)RdThdr#yO?_bJb@6H!n0RND#pxx{ypfD0 zuQEvLbs7_I@!eUT$?XQ^y6uq+Db9BjU^YtEvD>rW*?h>{bpF}rEr=s7*j%Y(pvIzQ z^i{{`tATt)d4^|!+RD&$nwAFBQ2(;|a7{iD4*l=5fX*nirGTf9cOG&5*EFW83ii^= zlR@<9J|Xu0);iNVp-=bFE_?AF!Lu~HhZ0pSMwj*3=2BB*A7Cy>_-M%axWP>6PWl_FXr!oD)vj>5Dj^4cYjTXVu9 z2^JWf`d-k5okoIhdzEv?`1Uj={vf(6MM7&;EQuxk{EhkeC;f<8h~CdZroM2#kuIMU zcP6oxoC8^3nb@p6x!w6T=-ph_DB`5(x;PZ8*dt@E{IloL5`1So)29>K%wkY&u zwRrqz%D@cz{O6|(*qtn`qUBPfBjeW;jp2yQX7|t5M8&@TqOg~UhLiVKPo`w%&&#PB z7cY*^*`9D|M0W}T`7Qo2UcIDQ9CYCa%NUy}@ytN{5YzC+a|(7|YuK;cSFd4=K&SYp zc?dh0i~rYs`FL2x)85p#*R%~x>J7O+ zemV#H-U z;7JjO-OuEHvj)@Uu|XTzyVl>jo?vKxiROCIFh5BS!z7|e?t$`+u#nWcOFS7sQde3k zs6^{%5*rY4_aZ`MJaPcPcVn**U_8zs;Ff3@5N5T|-u0OL;P9}(ZALJxIej-vNkO4E z!*z_jM=+z6A};!1QU2r5Aj|Mp(rul{c}8eT{-;nQrfbm|w{yQWzW4etH*ni&QzZdnMoY$gRkBfeNe+It@pif-4*Gf(odl$rWLaXwYc?j@)zqw;#oGfJ z;~Sfa)|-y2T+zSh#}5-OHYx&7xE5S|_lHF#P94nbgZyX(o2cA4|EY(YH-u9FH18o8`En`HAHIl`n--P;j`R7dYVYxLs}tBAeAB|vqxv_76~w^#tHTt`Er?`afb z#`tU-*mGwBSOr&i{JTQBw1TCg=+x>it~t5v&%VYFI*wO-@No~6=SaVNKB5w2nkRKk zOIiJtk)O<_bgiS!qH+&4HQd10?1Pki{XA-$V|;f{CKS=bWI6sO}&4ch#mzt1oH&+bgVaA2yG!>!QDrp zNAd%Nf!*X0K+a!v6tWW+Gz)36kyZG9dMRTon{N!uRBU=gSsplt_Bg`6ns| z0&_^5GZsK_E^1<8VlZes7mPQ{*Jbl+U5e(V*%vQAnv0;hI0kc;yOp{B!x->hx1p=6 z`wR@XmRqy$9~h980=|BTtd%&D8yej+#^lnV!!(>ywRx>0{o>y5k!6zHL5DW$45D`d zT%BJi(uw4?ZE`Bz7Cg^(^^6g_l06yx{@-hFf53nfUf1g=R3(iJtsH@6NvqT-RW~lS zsSusCMKX2kEw*w0{(eDf-cb%}T}|=+C}N0mH-8bwTZeu)E8nt0b**GUk4EfZMskKu z!d3$Ab@D#3#vNvwP1^PjL;Aijz7(#on6sr5UXgXyD-X;e5q_|%NfuJ!j4X+?; z$8!-;p&#enAm6Ku;g!XYnEa*QR9dK|@)>1bbXz#h=^4aqU|o9} zYP60V*IccE?M|vzY87~n-KdA|xVMW1egI}O3r~HTEbyG7l?giu8iJ;A(5Dd(hRoQv zN9)F-Z02p<)%m!({r%spHyZVI9z9Gc!}87dX7!#mIw@7OIkT_xvY+hr6U4xoIpFV% zs6H=)S@Q#^%GLFus7M8bM)V)XlX;4uCLylVO(#xSY1IFlmQol=@2q$vX zwAn&LuSMfBx@ib?Q~BL`0aPNG@Tpkw@XwM$&Wp;*MnG_r7&IuZS%Gj`AkI~@a<6RF z|6Hbd;r)H{grK6^qFeqdMPK*HSBGsszLC_?6e-W_PR^^K&NP;IB?>Vtkwc)y6~?U2 z0#ir6lP&kNuM$#*#>+Az$$H=tCbd&R`M|(c49dpf8Gtj8U-j zyOb-sD6o+nY?U_8T+`((qBvB8h`Dvn&6z)~okBy_#o6N~f=h+4axmxEz7H{&Mo9jAbOu+Kyw(g2E|FtwJ*<} zE2t}E*c0==RO_PL#h1wcRbinbqcTSHdlH@oga?P1ZWd%-zjv3gjYxppNFcssfr&x0 z$@I|8JJyVM_~LgHpF1T;%<*2gASdsGZJUghVYR7mXzons6FEt8z?3sG+IkMAu(sga zSQwDQ37=kyk=?!x$b;M~D-~RKx)zbJh)2@HB1ei>?Cj9`8#ev>DaOr+zkxlng(VLA z0Z=`SRX;`+0#{~&tvPOM8u&LpB<*~`l;%3Gz%!S_&D91NE8f?!7Za(fqHCnbICG@v zsEQFs*h`KiI~hT)mm~&THG)od&{2@wJ4okFPoxL35-0U1TzX%RsH!2zE==;%t~$Dv z=CWdW>P3E*8;t12%PgL56SCtpGJ5W1WO#EV1wK-&Nq)zgyHnMt>#^3%O+mQ{+z`up z2k$VDv3sz)8}H$_Tivcz@+UtHTE6V#Yf{UiW~GcOtlCiS|9@Q$U8=ZmrK6)`_z-}_ z<}DA_|0z8ned<99UyqLG6;YwWj^js8n|pbA7v&eLS`w+W@5_IVHa&d1+9=OO319cs zzgq?%4pny1-B=j3*xlqpAR_TtU)UxCr_|#{Eg2l%dnER7J5B^2$Kc= zUGkDib|JBR!%mTi-_e?_vDYQqIAG8vGLntR$f8$1tbfb$)UM9!rCQOGAoTifECgmz zt60-$6q)sM3F9eC3GeAHcKL%5j|_>QSqr5|tv?N$fX3oEz}Gwwhx}ZEdt5eyMFlSv z{H@gb%hr%rpijYPx`V2?{T8tD3qI1TI;7biIEp=g?gsc~*6JD>v7+M>iE2zs@UC!l zthS&Fk%}eD$xdC+rN)IW{>55^Vh}w>oN9Z=UZAg~wj+pNe_=YQZnS-!z`#sC>Z9fr z79R+B%cc5fp<28MhCH9{vXSk;b2%_g2p#^&0fAZmSmvGzSErA!QG17A%YLLs9_`oZL{IN8$+sO)r zmscZ=1`m3%_1D`Q4W5nb33U(|usq5zCBo%c@2y*U<$)$&RDdQ{=vqg!8cE!(5XjX@Pm3HA9vwZ~TQ=+Mylj0oFRrR0CE53@M=AmT~Pe(^~03OXr0 zkh43#VQ6jrxPc+0_F=j@dm?~N$HSu@IbLH9EEZ^InSXxssaoZ3poV##T+u}KuZsiF zEWRt0+${qOcs$5HAMjhAZlv)d47Wi)B0_>~Exm&q=(=J>vmfTk>#hlqm}ule6GPc0 z4ZU^g{A~b0sG2MsC5pwo>9MWLb7mJ7BnuU>7FEsjzV2Sgvb>6)+}D2wi-BI&JfDF&Z^{9}A@k=I{P{nqN-YK8-I zV|8d}p{Tf2Pe%tPDke%~!{;6k(9A20x=OVe8&3@P_h;a$Q@@Dy*s-&hdfZMX z0*>bsM7gp~-deAJ(rSAeq*DgBp7_SgSF~{+>h93hK4Eg=Wq9zlr#I5w9xR^rM!E0M zFYdD%3MzIgd~DKf>@FN#w90iC%zHYJ2qhJ3=82F2nqKa&HXz-Lw#q2?=}s?sIF(h% zI54Pju2$~stFKbi#s9J7VAq?vYahLNx@AP!iQhmh@F3y*Avr1XiAhO8op$9kd7pT# zm9bZdX#rQvpCAwO*89R~wF3L2+7$q<@N?9FnU}9q9Blp&&&Hn;f0F5Yl$a`lSm7*P zh@y-wC}fxTng}=zF4KnP?v!l*t$M{i$+L~8*L7oZf=w%|w(!x(REE*f%-?A*%)W{5|Y4N5z%TA!DYbt*{Zq9WNA zuA?g{ujM8$cnesqv_IN^LOy|m;Aamo9KO35tfZdsCn9Y;vnup@uxr>iHWS?XS^8vs zYgz@ZOPLAfwS8b}o33NDxhz^mAN(@1peoACnEdtWWBZRigyQbD@oHSbNrp$&5*VnR zR)^aId#=DTCV1737J)}^T-F;vL}YqBf2DRiwa|eW!g+22JskE~hm25DRs7q~?UD5! zC^j59^gL+`nKSPK{0s$V96tLNj%(4Q=kk}xe_z9FgwY)OC5HFQELtv{>Wgr%Tu@sZ zn^HZSXgKdc7_)QhJ!&bva;f8}zO|v&(M0F6;X=Y6i?5{HL=!B?%4;$BW<+l&^@Q=k@0`}y10PpjqI96pjBR&b#lkJ()ee7^%&hCv9Z8fv z@+ARqJ*ch>RB83Lz~VIkX(>15YWZwBb2?gH=sKfbSZp5Doy=>FQ0=bNH=opb@0h%1 zZqRKwHa6ASU9T5Unp|~=3D6R|S3wZT8qe^nC-B0=vZwMztMhAA{nr{iOL7gos9DpU zRg1)ki-51|*?w~$z*zuRCC`BAQE8ASXHe&61J0Y0-J_<@di6v~ zA&$SedQ2(ke0&5a z{(IA3;%Z8ha2S37TsYtB8w8?Z znST6LuBVJU_+pPw-)~f|B~MS_h$a3_S5^J(l$#iEi^YdX_IMRGVx~^parKV<8l>-u zgrrFyEGzoe^0!@l-?3lYmCAP(+U)H^JY<2&RJdPi53~z+k?KN&-7||uBH$pCd zCmN%BVAzU*Vt)x@-TF1`E;wJz19sY4u?qa4h-y&Z`V7njoawUk{d>>f*P9ES?B%*- z;eK;rq*x~1u>De?N1g*cGSjC8nwWR}>N|S0mX?O^I8&h@LaOWzrPqRVuUzUI7dzSM zuVP;wa3$*Aw`N$4UYtivgq^j{V?vQR7jxT^#a#i(P7MCq6Q2(mc*jw&1FfwwGRK*JEN`t8pA<2siJYT&M@#z@a zf)-EFkM`37f91V+*h@3@r-BYS}nSlS+~^fpYv}8#clZ&PE|( zd4#?>zj9)p0<4(5dhW;N$MMlxq}Nba`}qcrRs+(uoVihE-;>8Y7 zaEonc6mE6mH)g+Pj1LyX26o=1YXGh zy;vCJHtp$FC)o8%R?J$0(80?<6MV6yrG9+cIq2^>`&$e6m4*36jrgN$$NgBg<6^dp z45&pMx>@TmH+4R3n*i!5gS-fnnxfB@###>5S#CP}!KL-)qrFAFJ}JJI3~d1#?IK~l z%3R$(%E<|G*m%#T7NmyrV%ELZj@^9ScTZnsrpK$z7;YjWdcX2)QLO~SJiLUZ7S1Go z+XlBI7-p2X-2E0h?n|6D2ao=cJP~6{lj2rvyN1yVzKDnjd18{mTAtXpZj)D$v3K&? z0V*@zjeLv++ItJLZ@BzcS-EWAQI2P=TG#zB_uVMAMJ9{f0%t3b*#rO!&Ocgvn!zf= zE}A>ZB;Mu*N7Un5uVyKmxt=MvRu@Esf;r!FltJVf}8uT=C+dTF$AKf z{kJy*ms9M6QnLsCFB`x=?sVQeGx`qqkTOLCoL~#OP99g8g0`e&jj7|J)q7vu0xx&$ zs{>K$VSLbe1X>CT>Sf$tNUcM}(qmU_hL_q7I@a6ns1_6JsU=cM8SJSJ zt_A!^j7*Fk%vw!kV~<>_U8dSAjTdJpHInBd*cp-=oEpw8H4$8&le!Ehvcn`tC9Fib zy*W+dMftPGoIX_KU32%P>gyGF?gv{gxrFj+Pr|fc4z>oK9rTn3>DA8oCg-WAXt^bRG?@}@c(Q$Up6SVVQS?+iB(GJj)J_=SoVTC%X#Y=pm4 zaC>p2e)IvnB$~O+Ip;&MOa(2Y)Y!*;0VjY}V~tLR`&L(Ouk{=4y~V5a#<149ClYA4 zDT5v!zg`ak9e}ScGC9!Tgahy;=wzvtB+AH%rm(Qk_YzD1f6({8Hp$L>Tc-`*c#X@% z)2Ox>-qDe`Y-JkBT|8GEeOB1m?Fffeju9AXJw5%(YH+aNPHdnJx7-a z$=WH`v6PESv$!;nI7M$GP% z>Urp72cdb}6rjGFvkucaSzRaewaMh~ zG`*BkP|$BzhzxuADo<#!&0K5p_)fk>Ig9y2dlw6Nc*`}=U|jx+B`mi_lz^T}nht2b zSZP651f9MP9(}pV-RUXR>8IZAcf!TnW$25@XHjEw7UkIf?cu)aTAw1s9+|9!_QJdI z@_HQ=wZmFJB)}l6;eU>1}+LCm#DrVJw+~PtSuH(Cax6e za13*zzB;dDR`4Be{1Q*AjpU_>K7EyvZbO8G!AL{-EVX;EYuTSU=s2mu5W3W>assNK zH`Z29xJ2@!L3s$YdMv?HmVw*xs5gDQ+PcwnaS>^IRQ@thEq@Tzx2I2l5#%dOe>Z5> zF4`tthly|{k<@&kRCT+<;w46i^QYQ)S<*uO6fMy=kK8(mI2$j`#-Xc2b1d1t+2zPO zO$Aie;_54KK#kz8GueD`z2*qkUZ2gwxUqJiKkuMSVw2C7YuI@hZTp(exa6BrV!yN@q9xdiJixtY|LeeT@Tl1fx`-MGD!YGlSX(-=KJ8)H+#j5?i^?Ykp~Me-SJhDNE-bSYJ{m zMLW%Uw%0BaG=d>5N$xRCGisp5F&u0psBxD~GAA=Jd1aNRx~rNhxm$ysO6zgWC<9$JZltlh-~=Gu!hu55i?keX*L;CQ>5x=QRfTHd61 z)U+;>g1k$7ntSKfCt5DY^bFjgPVU_$FQHDcYSp*R8eI@^7Ro%0h+q#d3^LwcWy^$1 z>n~xS4{i4A^YNXgEnEjIB-}zUKoB2XAzGC-NCGq5V|- zT{6o5AK_O4lz>V_DvCfk_R4bPp;C;^9I^;Jj2f@;eciN$#Yn(QJ_F-N-8dFeZYP)& zBN4GBe39+(phh9SV%Ivuii@)xonv(-w8k8JX&Q`PFc?nkT+E#esAy-ozqfdz&lies zsy0OW+2K@dj4GE&>cL14sr&0jOTE)2rBO zI=s{D1g2?RBCz#DT{2`_l(g>Q*|@|mm*cj>5$WiQO-ojaeglMrQ(m@ z$&~doxKlnT$}GtE?hvr5u=5{KM@DuruCJf>sG?ctK*!p8vC_56i_crBV4w|&?&{V} zJ!8INSwzo_J*&Gq@LSi`P2R1?8>|hb(H&F%AulcIRU-)C?f}GHD+#+>uLL-Och7{t z5gc`O1pmKFQ)vYxw#Xbzd>;JFj+H7+=N2#a98^BhqFpx;A+P6$o?$5jA7YROI(|rn>vL2QTV18NZK~{Os8oI>v ze?{6-_>9IB6=i%N%wO~Rz4TcdSJBqYf<$L#H8%&Yzz@=1Aor(O+O$xv(#}R9ByXvl z3lH{9Zv=x>`v2;7;SsVPGK&&Q(jKjRPM!MXe!-d5@9#*7nZ%ZeRCad>vZq>}j2oeUUJ{0UKo}nkSC2CX2Sz{+k)L$>bV&W3K22u5geE8ubu(D%@3(Wz}sR>GdtzmV^ zSlk6(mL{ogpuwr5JlWWhI^B@X*?ijel0@RfI6EV#SvkgRRcqp3T$5`fFU?i^-VHzW z!6>##$q*0)|LtaPKZY zcH$=}%HO>gNp7oSI7L3!ZXZs~KjOFHhGIZu?nrn;OAc(Bl`I=f%)ec$Uzix49M7wq zuZx_o5GR65A(DF(Zhh0#evEZ2vbMgqPcw5`gGVh)OV2z(%F<_foz!Z7Iq+MR_DYTp zvxdXyA+<`L_6Z9v#!u#D-&9Qs1Fi0igBN-Zrb1lr^JY%cHCE1Y<^8shnXJ#mSZ8Ya zrdO8QOrtBb#YuF24s!UoM_9FYa@3hvE~&|zpZA~;VBu`%?HkoqcNypa1hurN#2PIfg<1{@08)6K6r zja^Fvi$L-L0S<*G`2S$Y+n%2qky!_+gB1Fglh2;H`z;RwjnV{N6K6hK@b)3eV7O}n zOk%0y^;K0d?jxQFOX$_Q@jr87i=^YGlL_sS7s|NX@VeX(AZP0+hY4v_0M(qMvC z%FHsnJX+t__!(uAsiPy;e2OBB>&;Na5FY$8moK%Ky?u>6pXE-1I`h(T^fhU7@`Z#q zzPrs;a$g7$!;78TQ-OokMWxLeU~c>P<)lue--PWq>GoyGTa)DU$WA{f?%-|%We#Dv zO54IBgZzTMYP%TfJb4vl)4u%vgDbzI4^s0ihs0^xxkI?4tFK!w?z;r+-rfw_5n&zU zT9@_pg|~8cbsPwE7=qxYACUkx)T)ioy;H5;SPS_A>6g#V(_DydPp_85fS4`9@g8}u zOUoU_Wm?B*eV6|mkPK0M$E%>4%$1lEg{xT_x4(BK8f{mip~Ce)ZXFuU0rwcMh0HvS z8USa-bMrzq1@7(1{Okxkw&`JpKC*hmz2Dcu;|G!(FSdg{+po7*@yQsc<9dzno<|j# z_-5yHao?CE%YKhyO@Q4^SE`jPt<5)pP>Fvid#A2EhJIuC1Sds=UZ*8EpEm%3L3gzXl)9j0;IweilI@S)eeKFQ27K+3K6c zlgMa2O;N4LWR-UF05h=RU(Y&&O-0lMt;=V(doui*=0&+H0wo!f<`HA6mGaQny?4nL zOFdi2;t_yM*gqWGVmit9W)C{{J>iV7^`GeD?vVA* zg@;x6c|@`vqX-id9Ixl2U>bUjzEycuY_`IxLjkS1}p0LEA7jFC}+ zqV~WQW|l95JZeTV?Wd~6o}Z%KB}(sPcR`%X1r*-CXLgc6`qkstay*Y03v4_;#A~ue zzumD9K;koDbkHaFX!Ahh% zkDN1a8^TO)U2=YW**BdYG3qsSR3AJ#e)e=82QTY!>S_m>BIWw+FA$q^+(ES!rlsE>QveZ$|^~Wz5`E+cLgX}Y>PD7Dk3Yw-9JJ*Yq{FDmN{xoT9s7Ozn;_R*vGodU) zu}x?zeU5~Nj_;v4TX}G1$%uy1>hY5sz5vl@w@o^L^=jd{&o%UPL zwbp|D`SjmCFFddA0owlR9+o>GD-V5l+g8TgliMg*s6WoU`L#896YG5?8zV6IWq%8G zR4d-QJ&pE!&F&0W$%sdR7T`A|oe$w6o@FL|zEQo`pPuI^J~O@BB=B2|`tov-hE>_I zB#uQVtK2wSA0Ch|o?rTvQI+)foPf|^g|`HI`3tG)yp)9RyttTBI~sR*?^Q*YjH_NO zcP*AnK1Q6~uFO8W_00$__-)2Pk=fdj~&AyMrDc?^Rbz4 zhs-{1`?C+`pK{YFT-WzfVa8$&zxSq)VV`jO*%uqQXCsJ`+nc@ z^qNn=JdDGr2B!d9xG}1qT=^Rf=94EqYMCN1vKW0>&fBNnPJ}|G@GgzO(}=O-w;J)w zT)7GgMno~`!*tU6$lKKq2Da=A#H-Q+W~xFfjirL_UW5K{gEFjkzsO@#hB77GB~?cq zIvM;f)Ijsl7{6yaYJ z@3a0b+yP4Y;6sD+GmI~+92hm_Cbe5xyez8!k1PxhljIrC1A)u3J+u!`7#I}=)daylCP@re z#hmP|M@!_sl6o0O|Y{+fU5y&I)Cl_mSHrVD2 zc%C{^&r(u&=z#B0|*2l8Z-*xHnykVPx;Q^>@UGKom5__qSB{47N$w*lLNe}GTZ;au+KB>#} zR4#SasVdj02HXFolLr=>qqjCQjNyqT>wRry7F8;u(m}q5eGQWPh>Te(*0ptQHcF$Z zx_cqwQ8q>jNw%TF)j*C?*`7QS5V&@bJpbL`YjbQkZu#9GV7{O2?U!EwXrX>J$>bS7 zSP~O_S-kR7AQsK|F|U5`b54gtUm|(Y3`XMi3t^zu=%5CCR+nj^LKz<%ewf){TQCs~ z^Oh?DN;rpys6umY7nibH_cx6>H!Unoewwom_0ZSUH)f66{k8E0m!Il}I>Yy9l?QJX zkM8?ODs;W;(Zy?0D#0C^2-6JC`GP;~=Pqgdj})Rh_B_&F%34H6o}Qi@)UPZ5YqLPx z)8~RnqDZ-e^7B+9v+DA}#(7mypbCBT?gon-LzpIhE9D)}Bz08^3U(R{Oja!DTg4xX zyaT4lLfzCiMu&%UNjeOq=aI$b%SBG*jP24|c(#EQwI6hD4P76S4S9d_O+1gDAenM% zsMW2{f~ZNqlbZqiH3FXJKVyFeOshmTC03H%!L)ZCc&{y5BTO47OKTT5`i|fb?3B)0 zirF;7DRerTa{a2{hC8?UjR) zj6-TlmH*N+PZW%j`iF%e@c7;JQqTGVA*> zx2n~R!V-jFl`7ZoQdr1_+`Dc>Qm`mulmVN+Z8@uB^SW_2)v4|jJxXB3aGzyx2gg@9 zBh2;t9?^Z_gEZ>3nKDL}+q$W2lau|exd!GU3O7}t3UUvw8^EQaaD~jiZPK90l1(q^ z>^Kb7?z?LnK?lfa$Z(&iKyQ5~L(0l*OsgXH{B^x0)w~yRWnDf5H4%J$v%#Va&7raR zqj`Srk_r3h-yJn=N)Qt)Tat4cshE#kS1PSy?O2zYl@o&gc&INHdOw!1g_NJq(FP5H zZjQ+uj?*vtXV9&SVAzUuCjQ$@14A&B2ym-y=e~yJJ11)!8zn7CT!l`5#FzXR?UZ3! zNw%PXX^Z;I2%~tzo=#b(OF(tvBo{XsWFk#FOSJoHojkQt4Yi9RL{X(2?`L}J_w0lk zvfLOkcyH{AXG2ln-^;v#;9_QCmNgt2m(_3iS#`7Md|-)<2#MJ5P5GHB8onp4^1=A4 zH2E_}*Cm6Cw(`9SjSHphE*L}lP1WU^-MMvxz2NgGi{*yigP}a`r_VpBsMx-KhmH9b zgN`0j6h}R!crkwTEXeMz(UB{Q6Z2;cW^o`Iv=Gm0U?uk7zNT$@l4KllYO(uDKeaK{kvK0pegm!=fkBrNht}wQ9kMaglv@q zoMwJUQ$AJxM_W1qW@g31TdON8D|JWH{u*PN;13NjRNQ?N!zBw<(9+1h8~5ku2xHJ3 zz}_I{>m2cpEWz!(K5aL+s(f3PHuv!z^3UC~C_&S6X1@x;V1TuoQl~Q zlaa?zTIJ=DMKHD0rD{t@ShA^Xk}WQaHq^7GTAz=kH>G{QhPY(n)4Q#VAVmEVJJI!s zj|BvZzQMtj^@f=DtU`6AXMzUSV_~)3FWUqn4|8)~R6gr_G|vnUzQWFX&y}H%SZ#Rk z$vtiRD&jf)T;TQVmM=BsK`Hr&Jq-D687sDRQV2z$1OoIM#%t{eByXk z7psXKo>})!*?-K&bWY!lDo~~ms^`8=H~VW0?|Ctc9&y5t#?-REbI9^ayUpsc&B@4ie{jK*Uw0;u zySDV87SNVZxB{3=sgGns4jqWOEUH6kPJTt4NdGVlxJ}>4^I-^VJNVtNBc`0nAh~&L_b<3u|BQzmpJMI8Pp(s<%ROmF>Q82pZO2A{ zQCk1+)O1)|rTk3ucY8wHYgKZ;o*t}g0Myo!QIZQtGzOksnWm2L_e*eDQ4B7DSX%?y; z{4J;JEv@*ME3wcea@HGIss)0QT(Z_K-w`*~jEWdFRW%6;Y~nM~VVNjY&>Sg+K{kWK zP`X%gSn-Sx9i=3?s=M*n?@DSM6B8(eSXD4(NgNy_ztcnFnosYY>>b_rp9$3^!{7q$ zj{futCfF{$HRPNkq#69_xRfK>f*L5uWnJbsZYg=uhS(C;A;@z9l~)N58Q;dqFm@Fl zP=}6YKIB&ITtXA6mc4Eob9l!1S23<~I5|36fz0)!*QnXXOv|P2lX8q2fO5-KEs)Auh6G+2q zUKuDgx$LPZ(ttjyS?+$eBotg3HM1T3vSqsZwWp1c5gu<>i1kSc0S{56k^~04GK7Qq zNv6gDT$RPdPN=ToEn}#(PKH+a;}pI~GFCh8TsY!Ge{M|bJ^HHUZp&|*wfw@u9jMFS z_`h1VF<285SmQev*2(B48)#DD;rw6d4}!Jt+`}X_{S=*foRYbm_s%3m#7W;eDuE%U zs3tF(7}c|oZ6*|Vw6P#2(sbH^*4(5Ee|4{_f}8Dz(mi^cVM*bAHr5;3dpHC2$(p@} zhL?GO47Y%Z1DmW-v{-z}Y#w?+AKGeOa7fsRIk3}}V%M#%_bs{nI;(>Aw5($W7AL=h z#izKaWRBUS;k^!i4F-W78{VJe32tKpVMDGB;jJ022#-Dz^B0RU17Ge}R?-U2&-cVV z-t36pQ=-``vf1N9UbbbEST9 z;3kMx8ZThz{b5(*!S60~z}ED)fH{*Xs!i@#^kt^_i%==_@_pAvD~c93e=!=TLD=L*;Wj;^lLp8*=@AWaA&$)|sy3~g6e)#=4e=9t^M%l+|v3xVG> zLy{f=<9A{BOXlI5;ref&l^iU2ncv{H$HzDWa!Fp)(yAu(@Zm|~2w|X1|JV&D=T^v`r#2^H{O;{)XZC0oiYCoPaXJa8o?{u&6;W#mskC5BMjcM z#y4W_!;7jh{hD>N>b*cut9u* zE-yX1>dKgg?GfQ(wWM}#m~l7j#B$TY*qm-{%hbpJ*m$KK4$ zi-nkVnisP#x2^;V>_mSZRqGk%#}uoY5Tr#we%j2G_nRN)l)?^;e60p8qu;Kc0;(p* zxz$xC`?&l_(=dVdB338Q+kbYE1C^75!yFhiFP0ueLPJJHH5srFBjoz&%BL`2f-?^F zHoiJ;$LqY13+1~{|6}lwYKwyw>lTq_0+Fq<*C7E{-L66qDqre*lhGiB*>ote+*4yG zLaEASQIh7%*D+l7YH1+UtemA{59_#F_eB%2%R)HCfr)oatt?+?&=~a2sI3ldY z(zz)@7XEKI`$`roAZEQS=g5gV^fEhzasIw}x1-DasqN7 zQ>q!j+mgiM4!ehBC$D}O zM{`Jm%(Zgrq~uQP-NGTk-AkM;``LO(>&MX#`t&wNuVs%OaV6fA*V4{`uVr-||DvW@ zW)60i;5SaAG#ksQuxi~`NakTmO-(bZaVN$|%(J^dwlu+vOBGZYEm;&qsbk-cJdP(* zIbFt{se5E){`UE~$F1&Efix#b-Aj*N5qpjzpoQg7-OhIHZC&q${7J;j17fhXk(7Pn z3OSi^^Y7DPO}4Cb_c}VPZVzXN2KEuiDvSw67@zTVCZ*h~{5V+vJ7C>YQuq&Jednqr zCegD1)z?@mewq$}(FBD33Vz?T5>d&ZDb*c&!2X`$gR?Wz@e_}gdqEs6E+#tO`11ZC z&Ge70^zz>ZgQvc}D6UQsl*fWR%B@Em+wYlGq0P(s!L%1Mk!_y^1+?}b%&l9bA-~~I z%8{)wk=*2^#Fm-8MoYlj;W(Ak+$Y^l2MPCOXU*#g)4@vervvWrAG-GrbQuv%7v0Rh&JKx%9fcfAJ$Q!Z%3c zK;p8A^icmKk$YodCh&k(YDOf@!dNWr&|%?2FpQ}bJ?!8t(bUjy`zLytbNd4j7?9}r z1UA$=DiQYq@58FN9OUM1?q1>d;$Ibe7&Ft_w%f3qp4)VJP-$gaX<)wV#KaM>=33Vy za*AJk zRd=RdBF@i6pKA2hOfmsgX3*>b$gyuxZ)`&a%~9h{uR z1m_xn*W|Ef>@{r~gi4m|?XIjO>H z&$?;g{X4B?*Ql)7Q$9Ni7+?bo_c0%#$cssPJ{Iqh;2rIITpC=y8h>e~xlZ3jNm!nO zVMR;uVdZsmpN@lnoTh$Z#+jtHzQ_a0r9!X~b)a;!0}MQdrMokT-+G8$is1-QJN_37 zF#JR}^NeZii{-93fp#ca$Ss_nBy!p?L#YcPDg7b2MM50=?{cpamg3~u5+ARPsZO4d zJ+V!^&doL37RYYMSDQGZa^1cOI-Se$6<)){)i}@AAbDW)0I^>F>uBSsz-ybai%)j? z_&_w*kIdH`$>ONUdMKeW9YBNgAh%)BPdk@9E8_V-iSiT#?FeEfTpMFrF3(y}EB)E| zjtzn!4g#E`$+Y;vDWHbzvnr9SP= z$&^pB4Ib?8-_Zhr|A9p)irgd5{(P~0{aNwji(~dGrLzo1YQLDDjhTj<^ociF8LKw) zBFR|xm?CRd6G}G|_VjmOQkE_7`*^zV>;m0lKwX4E4@hCy7!b4M_@x%d?3EB^YS)y z;KtE;8Cv}JFAwMOU4e|_L-cq0Mr4&zbUe}59i!lI{H;L~$)VS+x%Y0#ImuI8h}uXi z>r;kg`?LD!`_6wPc9ys_mF#yDDBa|zFsj%u`+o0P;SDb1Aj#VD`jjMNp&2KK`K5^M zh^*L>g8P+z_l`TJ77R@vh}1~o9X!6cN0%h9`+unV?s%&IFMio8J9}NORV0$VMK0O0 zOGx%8viA%L*Cu4|z4wmDi0rIn@4flGE`7eg-|z9b{UILreeZdl*E!GgJj=TsxV&6V z6|?lX`cHr)R;9*fKRye+kslnIbgvyn9c+<%?&x?7o63wDHP${_1f@M5_F%ORijfwA zOwV{csHt%>`|1qpxb?dQ!=$03p&=U_ppP8e?wLGi`9j1qr_Sx)=Tp5z5GTx~#`}{shj}9#7e5C|a@n2c6Gccc^qGp)>3i3- z6^&>r$dJ9oN8xI;(+a;2F%?o@&$ZnpDew0!@G(I!s0v4u(abf)Vn@Q)f5k2-PSx~T z#CC|BnOOW}8I*~Fa)o2=3UM>?hB}!BQ@ZR+VIC&FWkJPaq4$@Kd1k0$yfgT4YpN;~ z1!X6-_u=bQ$Xr5;21netKLWklgI7iseP7z;i<=ZnuccSSp3*KT6FB;2oMmYdVQOa( zL1?B?Mm);AtSJ{UK3qIJ zkKF`|qSIfXOOkfA#!WEew4Kd=4y9PmNZa z$5F6a-x0FBi?yZuD73!$AeQ7Z@S|}kc{x|UG5;wW6a7t1zrpYbu%_`;eLc$4emiUnr$& zhU#JXCRKmkY^84kGansgnzs~z9Sn%&_161h)EW;jNLaa#om@BdWYkq zLKH_iYxaQeBZoVSLnl0L8mm|t8M*C<6Ii3kDck(H?6mTe#cbx7x^(i{r}>k2&%MM2 z7vF^j3cCn(y^ZuSy3-9o1y}+j%=XQg{O`-dZQIqo&Hyh9$zH>`h6#=z@l{bTgq;8BcsYtHY=Xx(&7EzrqBes-Y41mb zW83ule^OrslQv1KryZz3keqdMA;cn$wOQk9`D9eO5yr@4!`eSKBIiu z7r*XKOnZhbd}Lf>%AvRWE>5)h=S{p0jwYBt(u0)io7m>c%1H$R4!qYHn(2Wbb-JDO zbcQ~Z2Jbh-Ptb{T_OeCWQ!XSzW9d9G zU5-F>#MK)vsDjK8AuJyi=s@_&CET(k(0h?jt?GGTT&OIJF8+!aUaOMOBAHYClTG4d zxTdVL{N;Xi!4%fm2jEZuBzXElBPh^;2)_|qBoNd2l~`PCf0~iqU)&^EpiVTuQPbcLp|tL6{j)KGAs{W-3HZ5*2It3@mzOM7v8rcpVvOA#XPlRnrk$6Q z7Rh67f+rWwJolXo_mYK&8jp{-ZY7UW5EIVDvwO zkr0m`J+d8gfcVi-teNa;BNF$BYY}P(`PJ?^pe)Da-YC-G{8}t9MB?o1>@%9@@$uo$ zu_<{^eL55rlqhKl?HDNmlkLLaSLPCG+ejg#N%F_u`_B8(qCIJ0-O8UQ$(`ympAw}~ zL#aJN0qQ!SON(oa`z4ro@c9D;YbMtH&=UgsPTW0G06a6~sCX(P60#%9dOqUz8GR3A zxuCB`fkpZPnWNt8@fmMS9JljQ#-l0WG0lP~s4|B6qWDF9BvjRAqM7JZ<80{B7ikDd z)aW;!FNl%RxZlVE5r>vowz3!1uW?(Sj)(1E7TYWxvNXxB2+5M-wDHHiN%df$`lwA` ze5ktR>0OW;s;)8L(95P{B0%AHYl5Lk#$acc0U!gn`Ni*@1lhPPP%VN?)9Emtay0mp zjCa=Ck4uc?MUWaM`Hp(=4RRh2#^Zk$vNFD#Jb^u6>B}_M7MUDJF z0BYi#1VPMccYS#ri#W*vL_!Mjd$TWsF=k}^!%d308b;S!d@B?C_s<;~d-{`vCaN7d zpW)H`>7H+=-rRcowK}Y|RidZN?fmzwBO4R{kbb7{kV3L~lr&6^iS0`!TElq{rY~>{ zV;`qoyA!jeW>oQIVwiI~28EHkBwG?e%81n@Ssvi#PM?veVX|<;t5Ftz;$s1HZ}|jj zFrbZD?+-zBg_^{gQ1>wB=AQ@njcsda!?<_G{K$}h zB+Ya%J&3WLvZ{`V_9Yp)Gvjuo(sN~PsEriy2+yI0E2N|B>u7yS#W}1@C;AspD32or zFeAUz&Z%Bz{u8$X?dImD<#>sA{Z`$25_-B5CXFQhVD9dYSW^Y z`1%?rG&i-7=HZ542%qHr`JiUs>@6QdTN1K_xsmNry8W2;MLPdznz-%k9Q#74t+n&y>LRrt*T6Hx|o4?Nsliu1@R=eb~r%#t$;J(HZ*9;@-T#Gllc8NQsV>oX{q&mhIh zRaKGq3$5|s%p6iJnOG~)?$g3M2M_V+1SJdZ5*gAHG}ITCuVI9FN?pFGeeTE8{n`^> zpM1fVo`OVe=bCHfSZQWv8B7XmP2Y)~!5dyqX?VGAS#vaO+u1e0T0dXP+5Xc# zU03&*)@jb}@X-!V{alYyTgB1Omw>lN$T;iE>Hab(rx4s~I^S{x_CExyIc2M|o<39R zD!EB=faoNv`pr}*E)r+2OOB1UY8E^dYRhU7<;&!oN+05FX4S{|C#+5R^GWxkEuOqn zSvHAEjm(@oxzvqlN#50{1%YMB_wE^@Jb=r75u_y7w8-@urBYFfVXs;u>t@-$|qv79E&(!Yc4j4c~lZ^sfr7#A#?sb%5 zFCv+^pRt=!^EWp}qdks&HxVpNfWq1M&a0hMROY8^961g>)qaBF?*SHMNN;x!vdb~? zjFXSnrcp_5ypEpqPr>Dra#f%3fF_T6tI=kLf4Xlk2)aLQbx_p3^|v-Q*g<{f)xftr zUWBX?hE#oChP8g~+Zn3aIg^bx-3!`0_pS6$nS8H@Ah)e8_9F6}oEO zn=b`eJ*5DQ95B1uUuW}g>U)TvXC1&bhG6X4wHxk@XUxdWT&5SUr%9efopz;EYv1U! zo!0@Nu%h3^M(n{-$)BtoyF4Gyj@iWKRAixr8F)ha^(75Cks<`!TEE5!>OGe z$~ZXu#c?BqaXJjc|IFog5I~*=SJh@z)rM<+zJ8?X42$$apqGj_SGd+%mEmN`@iGHf zpQ4CR!xZgfl4=C~k#ea8Bl={u{neEut!15uOhX`pUobRY+CG%7`J804v8c)Q$gBY6MybV{xaas;tfn zx!4gY8Su)6d#S6EGUZacpmvu(C0!TEZnG_~cD*WPUsoTHqf9S*77S75tdcCmHqHx8 z#I^lOi>fH{MYz-QX_2nrd^%4p6xkSAG9x!vve1?D6ck^o8G_0TlE-9lL($*k4GJ*g z25q!IKO5f^izyC2*8Psx@VwxNCZ)5- zPV=883tE76;T<5-=`K^7eSih|T?;hXQ$)rX@%y2_AMELb&op?CZI(xkZD{R?fUiwDY7 z)R+GWR#gb0&o&MY4p;f5IsZNcORQHEk+HV&FYKN)dR4gpQ&J+rj|Qy8f_E1mg%Si@ zQ^dReYWb2yfUJ%C*I6-Uk6f zpme5ejFxHk^wC6WlJaOk@|T&tf`Bb$=<3TJs+V3FkE`EUQ;l(^^u|sutEx|aWe?Ie zKRNZy@`{p$h-XIMBV+#)V8QuzrT`H$Q-0ux?jDhUYj={hF2F)G+B z5KW_9SNcz~wd`tVrtBO*Xl^_2E%8cL2DUPdMcn5guoE^wU~7aiEI0X?CT;)WL#fpi zZ}6YLt#)jgo>Lv0pR$oVtJ_-8X-7@`g={w zXej%WM+a$HsY)mWo{w_$622C$_I;hDk?y1o_Eji__6{{AI$#=Em2Ds2=`>zFnVA+jDs_Ht*_r7ek+7 z+W3ejAg~E3?24(NhN9?7C9cu*|H^z7$UGzJ%3V`avle(murmFhHD?pQFQk7l*}bj@!Kl%4gaCOpDsL@?g2-xNN^H=3RwUspIHn&agxW>~ zkD+`v5|{>3HZ?^RDi(>k)k1y0vYhL&ZnA5Pakh8aV=A!`jF zLR^w`t1nQf#()vuMC2nwLv0vE^}*@&`ft0|!&EfFh=M60GO9Ur0Z~r;X^u80ZjaD0 zbD>c|yQ$s~|uEOka;j&n2g-^QwelWms#crb^Whe$n(7mu!q*oVa@KA{aHqOR;MxQ@(aF zM)%}wtl1;)P9DT>=i1@JhiHT=nl3H4aYf$>eT!S{rsi`w9t}>%Q7#pOsBsjfazE?a zubm<^EjQ!K(rdJntJ#)){lGHvM(Hedd}_}{p^_b^Sw zpapX?!fQ~tYV5oF~tYyKW5ySiJ`)fH8X^9EJ5HpxG>K*4{bK42d>gDsh!U1Nqj~8%Df0LjlRII9ppo}7)hQ027G*6t{VvnZ ztP@^$D`Cp{TXQfq=(i47@0G=`|3>xFh|6Zpw))P}hJcJb})a#<6`t z-+RUvSd8}Kc9ay~XIID%8}H6IV(=*a-zcO_$k&6kd1_)}qTc=dNQ@$V=vMk!0a5hP z8D-FWOk7N5NL-SqybA5m9#(7sbJp_a^XY`+$DMC#1l&DU4#5*4ph)oD%UGVD&xexNhyIdDeXWGQ+rRhVWHaTQ)pOVX zm4h2!t9NX-B*V8e?_MW?&_Psgx0oa%Ke$drPA9Xu9cigSyN>8?P}uwLLw4~qs%G|? zs#2W$W&zG)K!N;F!FF4>D*Q#r(z~4&Q5Ot!=R=`DER<(hx!A_q zV)Y+s-BzAMRpWE$E=N&XbSDQEeIAH*cX^tMq%>_V$&j&zKFA-4@875z`H@`jwWO>( zitfDdJ&@HUjG$*evVGxvK0vP<+dEF$P+R$6gQZ~?HI-Ln2#1d_|;3iL_bI#ybww4w{mTa#^O6qW8JPF!J zXfL8(tQEKCDLNerfw-@2iv|eUoKEtYMy+8hC&#^gUVmBr*JZ+*FRzF~GH@6}BUoC)A(pG}# zi^d6KGWCgXypocMp`{ai-cUbMR7q1Q-7SiD+d`gCv%8~YLDXxx{YpGt?~y76N+fOZNcA{hmnAxxpgQf90SEag?^ z*=qj+ccQ=d@`j6{%oBqwr(eQ(&cI2B-dSW{JZ@@;lFw3@OQE5HdTwg-A5cnHN+vL6 zKt!s^idUqt#M$2mGq8LU|KdQXIWzRV`69cy>!O#_%E5Igho`o&qcB!s=}+-YyN>|b zzRmUKb$fCjr}*)mq4($+l?U6*8#|>Dm9!(6;OQgnX2yP|_>D`j@qLl8Kmx$?Z(dL=J^PtAf;P1Qo+tIq{Yn}NCJW_C#Q4oHa(>C2Bcl9~$XAhH4$eBr z9xPXAbxf}6ViF)jpd^dCe+whKS)MQVGbR0Q+`uFKk=TCnZnMu?lQLS)?6sk8(2(@9 zO0B`25HUy2FtAc>VM4#9g$o`>3@0&d>nw~cf}mlB`^jpoLS~yod8{(2RrmIbzplhd zQm>Ueq-LvtCX!nbjDHw;p?Sw`4*A7gGpAlniOuENAwF*!Cqi75TwHC5oGnYyCHuQN zD|YFbOf?6jan;BVUwIMh_qQD6n^&j1&Slb#_)O*d9v0R*5*J(;#R=k&y3sD#x9zww zA>ITI4Vn}VA!k$)J^i~HAn-4DvDz+ZAot>9gzOz@MOFqg)ew3r+Ofam>sh(Lc$F1A zt;FWim`yC6{$Zo|3H80ZMREDVG|t41)IIz0ONMFJSD7Z)R2|+Pk}41q=}l^eZ&@kwruH8p z%1B%=dNx9xsW?G*bdF)p?6cBSx6`rhKk`X93Da5j8m64tKN@!2MC}HqasQ%W;L&6{ zj>(g_KZCI;j*Apx8E&59c|(Ixu?+_#%0xILaF0~J_oxqlYOvZH%t8W&xLN4#@0YVT zq6STG?R9H;`K-Y{*~uo`0r-ZpJ}dOukvxa%pvG=0xDXT>|62y#qtcxe$z$~ zKa$hCR{r%2w`tPg7utRYVotxQCOkejidR=ymKTJ$_9N9xQ$hyQ)pNNv?HBcPdH0mJ za%>cC<(~AUsOiky@RJG8fFYQDq_0=+uo*@*l6ZUY+7_(5tlwk_aSUG(7(rnlh!Y+?MyCaWC+C1ho@M4z~fIc z8C#`-9}Zc#Qd7p!m+%agA0X9?d$!3mW;=HGF(yjN{I%-}R#W|vHh)!0#x>^m*JO}l zg1!5YwIpL`-abjY3Lbg&;eeX6;>C#Nk#zL8aP5ZO_2 z(Eoj7mmajD+1v>H9JLqktTA#?^id+VVhrbc8 zjQumG*mK8FhoS0owrS#XD-#sA6?w{NgyH!rK&JS%-#_vWe|Yr}*CxY?kR162bM67r z9yW=d zG}yVYAT)k)GVpa$N=F?F!jx=_RJ2^m|7EFP3LgGfK)sF?&yq=jTTWZ(w4#?)FpEfP z&6DKzTf%vKikh!ng45>w$zB2T{{GYMm2?QHyTdd{>ij44(Fnfz=#diRy9YF8iulWY z-p&u^_JqtO=JLW+sr2md_1yUyuAsvEFUOlJo1S2}8Z7wk>`6UZcBr`$jT269dU9)M zc-E$E+wUULk)tL>o+;PaU@T7_XoU@Zcl=v8(A7G5c!L+Z`o->h6mM2&VypkMyZ^g|u5zPe(fh8i zAlo968fgyP@u;i;#a>Uc2cQbFk`kE~Vz5j(c~3sy{jChuE&3RtgyCBq0=abqz8NP* zE*Zo~#o@aaIFJidaFJ79f{T3i&t9;6$C$5VG1!+IzeHBhZdKp%5=aR+P4PC1ebRJQ z%Z?i7EWcTGZ0xjkXZ(=lgF7|Ji}5{mUQ%EcP|=hKol zyLQ>%#~{BmG5B@#)^y1fk}tSkzfy;g5-?y@BJB_;icod`_?_fx*>T7TM>AayNfFcX3oyRP6X}U*T7YTticVd}6}=DkeBaQCXw8_Zni?TCFmK zX#HDX<;BiCji?-PsN8FK@lV}kekkxwKm8N|isF*3wS;ySGUa1u4!aq{E-EAn5#N-E z+JmO5$iFZDYjeJU$QM40r9!V-9Eb%_JeRJ6{MVf?c8(OC=8Fxc2Fyc{*O}XjSS+f| z%I7Ct=l1+7{mpNmBe?u!6*#qpFftAu`!S%(9-}!k|3pGiBPih4epjqtUdVP;s| zvR_86#2gpuM=TgJ>=hFQKl-_TZqiOwg-Q~4NQ2RRzh6lI*+NPQzG-`6&{k(QoCOq% zGx$%dKQK|cU~(k!E$A8&FfFMj-Dvp0u_3bQEO%L<;3H7o-XLVq^JD4Y>u@6Q^6n_2 zyVb9UrAl@K9}TL_CSX*z*V(iV&w5*I6^V%A2HbX-2`>M(A68HY>n3ex-0BQyK>f&n zARsCKPkmdi6zFEnJvbyh!vh`cNJAL{mq~?i0@=u@IEhz<-1mK2P^3~f2@RnnzkFJx z?Dh*X-pa~hbzqP97DsG4;qHBDji+PDV)ET(3cY_Tqlv#qL}NeV+NO^$D5C^Vwvww^ zkGAQLXdn;xoR2FoBg7@38Q$*`R99#4qe0OgZSaE_c(tO}j}W2%Y!+M+^Y{B+jt+7$ zQ|~oU-l4(qs=;Y>veF{OT-_7#NBx8tRjo_WJ8Md*LmMlpMf^ScM}{ed2`Cs)X^-CnAN>O$)L?T7^31BW zm&}H{V!Pw*VsDm1l!#pM;mqOCKAZ`>u32=3@VA6}9&O$JCi`!Y>v7z)<1>7L>}}}R^+R$`2|Jg;XPV}|7F)Ug?`_W6gs(MiO*P#uj%fU|n^6X)@yo^T0*J%> zQg1fl_CzS}fdg?_FGNB>8PI|(KU%DR{hZO|woHbSqpiNp8h>NDS64`%iDrdafzeEo zgVTj)Q8NXYcubfVLC!bX2&qrb`;>ya%Vb{USR|F6*ht^c-QW}|l)lJ*P-Q#{Uy*Z| zgP43R`PcV{)9UiEsu{+PqTxLE5rYokzmUw}wm&m?;iu)SN^#gD9`t)>IL%PH73Pln z-Wl^kGD&$lvZ_N3aw}rboh*nU#i~(4Ig0VpTw4vqq7TIRcg+Xui*f$}5x8jg4l)?y zFb?d-YJg%eSJA5q)1Pp#9a&^5=L#X#P{@sXm3$CU$Dq^~gWCSAd}MM_J49SuLG)e@s}l6BOj3kv6o_D zg6-|VndC{qV$!!p>1VeBG>_pYv86JC`T=ka>V&FnX8YHtcq8E{+@vmVT=`EgwTO{3 zP$k(I@xA4Y`4t+!>+jf}l6(6o1AxoIa@B#Nu&tICNsdDB@#zq|w;cXRV{v%pRg~dd z&Q7#_2wUR=(mrK3Sm@0h6;+fZz9xSqeNlgyep6uBOIy+F-9eSQSF^Z{7~OId-akug zxH8zZiE<8T0;*qS>8WGIPAgVgF*r}|^*^B*F!~o$tTN(25YjmE2QJu!X`RK|L<9pQ8!(V8bUtz{Nwng{8{_WhiDiQkl^1jx)d(^-2 zIIobZE=htLJPr*D&^~Xw5M>Pnu5bIt^DSiD0CJ$no5LwrJX|tBE*^CT!@+4<^|n9> z5$*4_Dvh^?8VbT)k3_5DhPJCQM?%AQs(AL8jO3%2kiE>1w6Cl)6mGl&doZ{k1E+cG zdY|=Mtxp62o}*Ip%IR4GNgqBhhxn&vJJBOSusU`W(XVy`wTS5~xFqlRK_Pt)I+9WR zrUxR7IXd>7_F!bKwhjr;JEn@V^)4RbU!O=MJ6ob0(By8$ z#eV)wzavWz!zoJ(`!nZIRzUM{r!@cj6tg6^;MqTnkx@$TXDfrFE`_-xP^in#aUY-v_{hU>26 zQNQ;i-0Ux1kz3O6HBgcaOcZmRVA1og-xNO@PK>BGH;tx}eeJj1ywi#kl}Y@yf`aHQgTYi|onA&8VHvp0iG*^IB>j1&|k40tG>lp1Y2zrnzSW~5>_ zVz3=GJk2#mp8vBBJQ9?dtwR|H1)s%(Fu+?rk5j4z-0FmkFHFxjS?$_6QVhFFTa3im zS0;D4?djt2)5Zl8iSvT1Y_IKVAF!`_ zZZ8+s*Ef{6yezi7PaRv2Qd;ef+voY#bj!Cfg)eEG=Fe>xRYCMe?)b{x;+8I~m!oKY?nH)(m=Tf&e zGxX@)LLB!8?AZRgPx23I{q_f%y@DcHhDU!YCK#I-FIf}Li;p1{Z@Kvv7B@&9U-5nP zb@$WyLXA4(SIj|*77?XoogHV-)#I?9sx4?Lu+; zsolEnzt--%`vyze9pq!c4-^bLlY(mp@23rLl0DmTsjHu;GR6^lEZe8PDtJ!a~7nK_&#{}mAS{aE_J|O8k;?vZMec33| zVeU^5f{!_6{e_$n%9delnEPQRJw2T->E&np5BtwN-QxOO9SQe**hAB=YN@2?zawYH zMbddB4Sm)Zk5JRA1w_YKGSx2&M^u>0Kds*gUR@CIY+HODFBm-isv(;LGvZHhSZZsHufoB|0}9Dje%l; zsXn5SXnC=Jotsj@Sf9^`*^Q%Lj}V6TiPS6av1G5l2L{JDJjU}9wKPk=@%FcU%*v_s z^^KlkKH86&+-%_;Kaq0!fPx@WjerFmwH{t>KRj;xk@zn8*2WA?*zjYzfeS?k(3ni} z@;adEg_8aiV}45@w@7X1`b=xQU^ifAJL`dtfdPYycdzSGROTJQbp^L`;u!NS5qI(tpHOuX;2&p$^;(IFJUWH=_$ZVvPiC|ascs>|QI zL(?2lIxNcZqA6)c_n{P^{Mel2#(KzjzvG~wYqsYe7Hy6~i*^5WeUNe$rJ3RyoaQQ~ z&Bg>%GgKQO4pgj>lGE{dG$>ta^B^!lt70>%*7&P}20|*xD!B6Iaco)n}mni%iuq8i1VVgm8fyvkDT-xl(PT|2=+E{<) zxPnoNmG6TsWe?tPkXR8XPG)D=g*=W1Dlg-$N*Tvn^!$7yB%Z%1iKc#*p;yk*<-)|T zfou;OCaYMp_Ci1VK_rxoM8Kc~2hW;GLA6Zvf7H*JXo~Yifm6oRe|0%r4|=&{9=`0! zdyzk0@3?*bIfSbp3sRt8XK$8`qYfUJ!Sz)Tvp(4mp_lu8tEtA+KdwmhE(PM=n*k$G zYuwf~S5@48S3e-u6Pfc8^Q?YNcYiafWJ`DF#1q)*wkOT#95nyK8FiqfnceWyIv9IB zQ)@nwS4}y7J7Z3D+K*smdwY4X)z@;m%>SzCRT^ z9PRZ?Pi0m$8CThFVD1p>&@09GcdhCkm%YakRTbqQ#%O~ZizR1~U~Fa%u3bzpY?#E1 zyO(mVGVMyLpp8KEdkkl1Q^GIHr3k|XUOWs#JjN4c#s#k$&nj@#y?aB_w8lUNwia|4 z4C5id0FNBaxCYLZ$6>beDqtrG=F-p}ITGp}nRWMsZcCUaqJki_=$yfF8j17b3AKB9 z(-T*GM0if-iKNM%JF*q0@n4*f7lO|nkcVll#o|j?EI8+(2*tGCCts^pgm3>E`5IRw4;9KmYSs|3o-tYvaw)qMb}pQN~Y$ z6=%;ssjuy`y~a9H$JAk};TkSM=hc#<*ozMLmj^Og9mV0v419g`PhgB)H*icPD+>K# z(rAAl->ZRq{Zk>~`m^GR=0$DEfjdL&5U5$XE)*{*GNvr5VTDnwCe;2J#=8=-x4)mN zShIZg5e1qAh4qbS2(+DCUG`Zoh&&WH`<+Bg#!*)_;Vw)0E(>nzwZDN#OsmrT9tIvY|McL4A)c2b;C#n#eHV1q@}7|}EwabTrf);-`CYsw z_we^I@GLgzWMY{|7#AJq!P1-VgpfXNQC=hT*^{p8j}zsbRJA^EnLy$rCM+qex%4Nr zLJiraj}CUDR0T38-Mx0c*+Ea~ozI{C$)MSIn${962ec zCt`x0@^VyCzA|xH9?Pcb1SeRI4yNKCp8N+|?j6wICPgG0a{qwN+g(?dad1e{xQE@a zi-&(TLj$3>_C@iN^&t24~((BaE#Wi3w(Z~0-Kfr*#fj7yWmA9NQ zk9jS++zm2oK0lM!8mR zsb6SY7(~^PLE(W#=6#{wyouV1m%eKc?l8FM#>jO-5QE=8nu zhlPc*{HEl96ToDL{n)n|1xh0KEW(D%_G2^L1F_oOX>A7e@Bi27@J!`ltag)|fLgZV z<=51)7x^R4L=SV76s(^jP8>e-j2fHJ@+VuAuLWrtig(KkvUSb?kjMx-p3n zcF6`3F>%$nMYR}{+5aOkMd72P8erqwJDGj_6T#`YIOXI z4O12A6vy=zhxTHx2tEB>9`U}`x0Qm9C50OW{^|H_2Cyy|#<*}&YNb=$OnegPP|9a($q6{^SPwGWst)cp39cj5Y+t0$Sp70!5l?bW|L-oXQk zWD`J1bPRvSf&7liT9pDJ;?$mU-ml^%Ot4aTV0CpXYk8at{p<|WY_o=t5w)$m z4@!mI#=+nR4S(ZZ!4t*%5N47pD+z!5CROtN%99=;+Vl@&!xTr6@2Fl$?6{7rSa5j~qAp&3_?nWaB+ayDej`;VWz!|6d+by?9gf5CN= zidx;DPjH^JkUHlG2wg+aLw6moDFS! zhS{+|*rX7b!mwHpzAON)US@uN2q1jnZ&>4m_WG?*ap{7B8%U8wZDwA$o$`5xXxlA) zdVU9H?sc5;#b5lRHxG&Jfx@4yW!7lj`8Kq_3t19yk8#(ijN^YA_BglkM`3xkt?`EU%&um(Z@C7h+N;}Tk17kqP_bS+CG%7y!EyE6)vp!RQmZD2IHSiAPWq_O=s z&~lFGF6;*YVTirgW99Z9Dv%++^^$j~=8xhek^HJt_O_?iswH;(aV_OTMzlOdpCIm`xv%N zZ3zY1a4f3IWdjfB|_UR7qr*gxsAG>%GfjI5U$R zOy=;SmV`!ac4GSeAJ~nlN@8Sw9@nxgdR+Uq8nQ~Qaz8p@+UJ*YyTlwq4MaplwuK&k zt6^6dKHsk2ZsMHryuS3kYl#@?An3a2yE7SyAizAlvkG!7SG^`u0`f(1)J&c{@eh-@)C2b{Yj?`Ojl*M_$_YO%HN6-3X8;>l2+=GI;;`2`gE_ zXTV!7C*TVV{NY4A)Ag1U$fc0Pgu*1*KWDq}RMNrH)l^8R*VocKUwbvMcFVCzHzK>Y z2~`u|-i7n<;x@O*$zhSW+rFk+v=U<^5r~$z$&%Im0gF6{_$RGE=`(MO$gyH$rq(Wp5Hff}vHY|M>hW8WLje~V9-aG^1JGlM6NpJM&|EA@ zOpssZslN;6@)hhZbkXU5ot&C-txHW2v0oWHwr<${#wh~URz=GkBKX~;4|tnCnq#e5 zFCGn!fEt`c6hMFf_78WqQaJ1G*|hBwu^lmaJ*6~Xdp^HIbyzszh?;zb*RbPW^PWxb z+?m|dm43KmbBfr22-VG8+X4^HE-N%TWAcEHvtj)zIcJZvn-MAdn88{ zl7pioZhn4Qc5Hh0fjGiKk%Lhw5Gu1kp(K6{DQn)EuwHjaHR}6D7K2TCPaG1pZJN*8z+M zjeb8V$358Bl37hu&JAVjz+`#J8Xs3KjxJni?N@dwpGKdT>A~foGKyz=`I64l+QPOmlNegAN)4*S9(}ud$}mJD8}C0Yq)?d zQ!W8uu$j8g@!%WI5kxP7tG@q@e3*ykEk9KJdZS?v#NmP%Oprl1+QSrQLM{t~^&%16 zza=IM3s7fHl6&;IvuL%)@AAwcFxVb7di`9B#t<}B-I^uEg+jVZ-B330;f}Kb@Xj}8 zPc&~HE$@M5k+2nk6XraQS;Cbx=)^0ozp;4B4JcEuL77M0oxID?Vmf5K3M5dvpq-L~ zMk1frOz?V%qjJjI3gqH<*3dsnUz&ddluE($f5|Mhv3viH(nX(`Me%P@{nlBFGieK1 zIs3UHc!=iz;p#7-s@mS~ahPuDICO_f9J)DD0#XVh-5^Mpba%IONDI>4-5nCr9a4vG z_;0-T{yyLLU1KQ2F%DyU_F7NPIoI?2YpWGvhgSd z|D4}MCj=p_S3_h>hNquA88%^(SDf>;JbhV0>Gf>n$e2j|BvXg^p+Vo z@smpbF#~(T3<_!eK;^04U`PM(aNPF6DEy?AOa89)X2kmOlDF+z>kD|A3uGfPr*Yc$;kBtH!t(x0Iu-3BLruW|43h6#< zX2)_Fz+oH0N*G9!di@B&Mx~RX+E$rt?V@wjp-Y&jVo^@#L7psjq!O}hUoe&NisK^r z>v_4}RwpPOB?(5HO)fOt#tz)?J|34}G%$WQhkQxEjs^5Na5dzml}hi1-3G8M3Vxk} zvLmi%KbL)Q|(_QkZZdK<&LLg z=4*}S*YXo#e+1S>!skO?*U6MTOZ}zaKdQr0H;A-VX@L%qor-z^qJh>HJkQJHwY?|U zGu8J0UnDS2E<-3;@VNO5en%aq?PfP8itrx*;1`q6n*_R#vHohm;MgxZZtw0~EN4mY ze`h`rwLZ1$#+{S<8ANCQ5W|rX*W=rw%dk<->A_o$OxuY0iDUNrCI*zX55>_DxMyZ- zg9`2F+Q3qy=BjrNCs*x)c&+@KOp9UYsNbL*caQc8Sdf9^lOZ30zV5>zeWf7uP#Uq= zX#e-31}Aak9VPq`2JEkzZ{s(!m0lKR#P1PqgNkd5wIsDajsY$ulM!Nx@-kZcT<5N=LY&;kh_xH{U4MlU^N*3auMh?BXke# zGT|7bLH0zR(tiFQOsk_r=lKX>ZBk<|dl0Ux54>!-=_S2CgIs62T<#UD?NZ}X2-HGIb+M;MwFe}zpGBb_1jc$RsOisgRH27=haJ>6wNZngjt!YxlJ*1LuXcXNW9ov$xktujYAM!wc7C1{RYy8cp*;lY-~zg(&O@Vz^A- zI9~}PzjSPqmdzvDX8l}#@fM{-T($dw<-hzt!XJ>sTv!X=?&csuo19~wQ5{3kaOgJr zbH3$H7HS3%jH%O#>)?9tP z>WokR58kGO$yZ2s1!~5}%WTQ8P(U-{LH-xY;gVZsL(ah$5?Ox;=*9$LV4puZj^W8Zx-+;U{YK@gMdm&9l%__z1wmSe;NhuuDStwhdbndRBt4JHG;GMs(rq6Wg1O z#|5(Zg{4WokVIK?3fxw| z*N0yKNHc+gkFN-T>VePo9OXG)!D3 z{OJMfT-E*^YBM7z7bdyL@|`|+SIEk>E7_zXiWlXhF0DLO*;@crn1u8v$fqWG+-w1A zIVC(q0~Qn^mY7T@#OW`IaUYR_tu1Nxg(VVr*y7j%-=xsfxdi;_m}Sa~0%jg;j4^&@ zDe%;OEyMU+@a0bNPxoYHp$l9z>Jb$lN_=FY`PNL8@y9Id92RI#Z`XT3Ok{VpbCeA_ zpe_3}cXk?w|Df%k?VTGUDAhBM$^vLB#D+sWf(9-vY48ce8qx>j)q$FF+OfV!m|Xz} z!BdF3c}>^%T=daqBCpzLk2vb-=gzXhg3q#mT$oVS{6RFHbvldcDA6z;?50>0;>mLN4eSW^d&{}$OLC-z<4_@kk)qGAncMjhC z-z5ef($W^>Z3i*C?K9HA;lPr9sYB)Q@2D7nzta9nex zF?y5k%E$up3ea*Xh-QqsH;c^19{Fw4lC@JD1wYz1PXiWdU%WFKg?pU0R8i35r;)a- zMWsNx=ss)neSjo^ZD~|>o4!w2zKad? zN0IS2)3Mq4npl2b<%Eklw)1H1m0Cct^k&&Dm`>Kb!Kf>9>c^BfiobvKrV;U`)C$eg z0~w2Yaz~go5Juo+0?QcaS}32{)?2Ckt= znH!yZJ13b>xv5=(yvl%r<8>lR&guz)IF)~VG1-qxa+=l)4w+(Hlcl#4u0w)?TI5d; z5sdW$g7=h}Eom~Ad7Kn&U#t`V7BYbMGz&&&t@j3$E)@W6Q#AeOnLvD80}S`9#(eg% z3#s-whw^ZiTJ~4{)Rn+J?v(qi>n$L>_qZW{Z)UE56`NwX9snq8)&kkOh9Eu>Sekugbs0XP1AsUrNGOf@38h*7uv**3l%NZ0p?nmkw zUbkO#Ty1Fu9W8do7m)XW{#xZ;-ZW)1aP1*n`l&V#Xtzj3bbfx#aqaGQp54%uz|)ig z?+in!Jval5Tx#elJXX2eEUOqv{ncw-)0f|Ve59#h`jNMauD5e} zC{+1Jf2LGtq%>U+g*p~f_`5=Q8ie0dCr7Nsi>jdhNt%U9h(r1HyGu9*el28I-$dg;ba9fC$R^tXt=-FIuLMdek4qFIxN_qHu?SoJ63H-F|306 zsSN0fT{Qhpnlt#D)g=4^O2xYm8E-CpUjst^M*f)GE92)dNlE9QuhlLKmn&mxqY}Zb zjtiQNwd)B#dui3;lX28Gpr|U`J*0S_X7&V3y7TCpwOw*reoEuCM;Ca5i{NH$fFr3= z^qvkjx;B)B=%rN*ufjT?ah%1>@8V3MR7T5LnGCvjJho(so9cZ_mGnfv^CjWF|4;~h zg)iybLKIDf8ZFW0v@PT{jF>7>j&h|Ff1JwZ%>grGJi$m=mv7IZo7 zU7?2eW*kV*(Z^(QouVlOqsq(SOj<-d)g=DkDwR}GA*iXT0Tfz+R4BJ8=T*QzEWdvJ z>Xnc)`S(+$3emnE`&ocOaK1YaD_~oq8RavxPXku_k1q|@x)MkUzIOE&c;!&>a!YQD zTk2|Vle&?rzSV#-3H{Y7^VNK*@1_!t3-~zyEaJeTqM{##g;~I4jWJKc(FRCyX{nXD zsp<6@Spp*s4GqU8-wxl>{2;K^&bKCzjUJOsV<|&glhKSGTw~ko3?f7X5UAZJ2_Wlze$_cwW_sN^}5j6%GdG|!5MkY1_;Ik1c0K1oACk*e+E>1 zjDwIs<)Fod^}=QEE$92@%Rg@)k0H0>TCW1wSv3MVF!T;?lFt;X3VFSC0;8R-{Vq!x zl1I=$!RouH;v}ESw&!AK7wdOF2Y81CZ~APwE2v93y^)m)9mE~VmAnFf^+GPIt6o(& z>``>mv&2Z;C$EDy!N3gLNo8U?oKslm3Hb_JI8cXoJ+S*`=AxAbCni{|T~b2g7J7+p zzrFYa^1IPs_Rbt0dG9^!>LlbXVNZi?uSDn&L>h#^RhO1!yu;u-IyE+O_udhU&TfodvZJSo%g7umR2M6f+abbAY zVEOJh_tRo!pH6+)ugE<%IyJ=} z%6FT<-Fnhr9nM;IY9~Kj5I#M`iJvWhReaTh2hr(?Qxxi``g(zISOOwiB@MGp!x|sj zthziaKJv1DJ+2o)eY7A%5U)D}3U3%pd+XG3z`4`vUn5c2f|-Izxt820@VIyU6p1Br zkAlaDHFB|T=RO8c6kzx^2Zw2mB-@f9D=Z-uwn0DICzp4B0F*uMyt8|-Yc!NnMLe|yF&J%vrPhgRo0}f=oMP-Bh;i#PebHw zB<3gKU0>7ubFB5{q~G(w4Km{PhUFl1X$68p`@QqAZE$d6hW1*_+}C32hD53A{l@t* z)BfnWO{p_PG1C!~W)L0cdEI2>%~cI2a}XL@=hbZCkCna5KiT@~FKjtS)$XjLW9~2k zYEpwwfPqZE9dE{K2F-yA2b1fwWAxZclua6d1JD5eSrn|vpzVfIe^skrDOqVP@!_B` zVV2!Eg!v=w-y>2kp9J=KP9uO(Qk~!f^T{U_ZEbQcF0Om|QnTmXjnOZ4A>u0aP2bO^ zf@*Oh^|JYs9{Cl9<-F0wiP>lWOtHv|rEnA=uh?1o75lR-mGO?=Q{Zli9TKxMWLOLH ztp^U^)BdjI67yY?lN+E(!21Vg2_rrfvA$mNAU>C(09vW2lTAh5$zKj+Q&T=KT(e=y z+=*Vsvg}zk&xkuSD(H1ZI|$fg{b-9T)J6eymZ#S7SnHn_^S8r4K*Nv|YA-P{$%KYg z+fG$@gr3N1@0dgC5ittE{=+A;dTs_2HfuEc&|+#B@CT}T@=s%WB;i8`pv49@?PbKN z`r)Tu-(#wD$9k~Qerl?V#gncrFrpO;=nahS?4Q*Y@a513c884Bfr#xBQJFtYjMJQ| zCh6A(Q+}6N#?~w0cZ2T;;8QK`W0)dkKEm2x==~w-1d% z2j>wTVQ$aHElq2S$H;B?vakr4K~F{wm?4{R1QiXL_&jX(wa9m~@SFYl`T6qF(j)7C z-2w*V(qZ`>|J*GnUj-wC8$ZHZeHwh_$y7L~_=1LmD%s+h<<4CI@qs#BFyN?C1s_m|o)qEclE72Nd%3^ybzRmF2tDyHl;K;C^TV zl%*$Ru0hluw>7Vlufy^z-~Q5p+hk#0{pmbv&s4-;#>vo~&05gQ5QE~&u86#i1G-K& z$b?yR+Cpr9hkI6D0tqwyAuKrfyu(Fg)On(ZWCMJ;*#3Rz{7S#3Ltkm>fdAL9rd!lR zdI|>JZ36-E5pJuohB3}i;-XAYSjG0hv5o1zxxY!&TAxty#i>%F%YqaV+qS;aAwr*1 zEELaK*wR5!Cp?V4UB`KH$!+#+;_80}Dj`wYH!br0Pug8-N=nKlfCsZ}mkT|6c;Y`P zPNEyH<|+s$ml~{B)IeT__>qDaqdydVgQaWZ!vh6H5W_^^7G~Q?72n(q9MrmOGc`jA zoDXf2oFKzq5IWh)h5UchkbZ0)<3apq?IUp0=k||@emMKnM`dNaqURhzQrF9hsLWzM z(A><(zRSM)a3$c-v?E`TU6f=)38@=oTV4LX5#6C!RE_0Pj*= zn&rdTdPlC~a)W4tIVM5f8aZs?QQ#r~s)~#V(TPU)j&2Wd!1Jweo>_O}Ss}p0Xc3Hb zLUSFHkOjfdhy~{qGzFe2Vc4%|P8eqC>)YRG{28&rE{U+k+}fUq<8!=3aD_Whj&*O%y%L>j zxU*ja6VY+GO1%j29Nr`i%3@y&>X6k?@JNe~sSlr!^BIQpprgK3pk*cr;7m?c8#VH6 zcYBeo@AiBMki3nCPwy#pGg z0A~F1*^GmO``=GZz%^wC^cJlBdc6PjUJI2ov9lRDCrVPn?xhY2I)$$bfDL_x-eP^< zdgHioU=a|p63Cn3uRgTeizRw<{eL`$gnYWdH!2k8%ikt~I*)BxThp zcnzSNv(VS{F3# z9S+;R;T}8LTU{Dd4i2?Wr(0f+ChjYgj?}9y;TPGDEBdZ;fjY;(TjE-p91T_%so-c- zyR@OA)%OxPihL}RG&C;1u3$HUv-!gEqqbsnAL$^krJ>uLKc(v^dcq|8BpbHV=;;JT zBYF&T1r^(~nPDWR)H zdk^`~;q1D_B_%I_?mn%tKj)vrh!KhnCZ@G-uS)sV)^10a)|ml#3$uPrB&i(xD-U)| zbCt+&k&pUxxfi^}BPy9IZIfkwliogCwhxG538~H<|LxeQRqEdW0sJLC9!|`O(iOdv z>D5{`fB`K__9WCD`S68?M!o7x?RDFk^;r4U?*gb(XlI`oM{KtKauNMcMk`Y|+uyeEeL}|8lJ)|$eo2<(tFv&gi7&$lm7{rFbcM13u zUv|I1 zLg}4)lr#eU-N^neP`jeRJ>Lw>sJ@MQ%fN2=Dx5TOQY4|AroAVHL%e=ZRiF%QY_s)m z@^IFNw(BF_wt>|B%)T1#jT_b-#;U{(urqs@ZF)VP8}zCbrjT_pR}*C;0Q~09f5kN5 zqtQN(rlH#OP}%G(w$1$d6>0!QoSJvL__WBcD;2X#D+<*K4VCvJUz>ESI zwq_{Y(W$6g%LB8(^q80gQdJ;}ynEdmw`1Eiy6dG?r?p_96p3Lo)BS>0(txX|UA7pX zF%xIQi$-2?Ve>(8#|Mkif8%zN)H8pxZM&l zx9(eo%Dy{Q(rI;`SrrQFqLmZWyAH@!{TTkeIomg`FLJ}8^=FLe#w0d$nLL`OgNEj2 z%@x@&7_MDY!1c!~8NHS|>m>AbiaG_>z9m)hXr|9skKzvGbKxt~5fSQk+?A0Ho1DmM zD}A|5GQ7vsUxbx<$JMn$!iel9dhqNUHn!vDxuR7SCW}`3ib6+bhS52*bwk^EAA~J)t;Qm{Y zTgy}Y^XHu-=Fs1~yrVt9=33rV3(-w?P!R%R!&J5k0y1+{^bZg?9Ad7w@*0jyWPJ_&XI_ zpWw;5T-<18>G4!I-pED;_fv6}R0bm-rAYzORS(beL+eV9jkBcDIOo=ss(Q??YZii)vsyo8T@df z0*scSbRJO?c``?8t+DwTpbHij1Su!cJDGbvz2@aL#WN+{UqwA2=myfPEu8(Pyulu8 zQbqW$TumE>LOhLs-q`a?^W<{7w3yuE0&ct>n{$luUtIu6Q+aFaV^c$s{Ii!tDxZ?l z+tHY-MVe1JQx@OCNKzqhp$}XUPp9GVkB{_eg23~7am|-nJ+eEb4O*oZTy|7FVUV_= z+8_HNVu@z+HCcxKdm1ocfp#o3-`;6gWCpNrlL8)cWk|)6hUTG1&;#Zey6hLz@#i)=$zP+4X>Q&`u>G{IXliFFkMua=OXy7JEjo z%NiB;1EAq)v+<_{4MLy~W@`;|hPtGX+Hf#jSKu_naBQC~=13@jzFh;W{`%IKb(ET| zHB-+9so46&57T#B`?>;7E}BO8@olGX6Vq0 z96psY`f_^aS3(rc{C=Jfc2CKiwr3(;% z{j=cVcV?*UJBEZ4PiXBbz<3{&m6SRwQwZcT1h`k|LjZez_3nC@ShLea>`x!=uKJYU&!NYC>U&*vk~iSCk9b)kg(emO^#HO2z>RAa||?jQNkFlc{`wZ43oGH9@6Rwf-jyu%qtN^K9usawxJ3M==j+U_)e!S5Ar z*7xcYs~i9&u{Q>kTqD{dDc;lya27=V8weg4$t^Wp>Oy2A3eCFeBiGtlWt z@uJpdstXwR_ zKOW_DtyZOT3!J+(4)3yKRaiZ2=q74irY6+5kJOSDAcsMMlww0$>+O%TjTz^!{KYK^ z8d%v^48j%b;Kjg1NIqCwD42%O@E%Dv4fwczl|A8v7h2WB@!!6EILiQ#?PpjirlS)C zjnH>+!8s#Z?2pBI+k~d5h>emZqf2p|cd*TQ|x#i@FXr&I_sjmLuJ`?BNwIBF5n} z1mQuHya?$m{!(?gPG962@pxU>voh;9F*DybJsaLX%Y}D)EK~8-xAluz-DC60diHH( zfQ+Cl0t{6BUtEd|-BoV|35b6|%l(QkLJX2Tv4-8S-~Q2mjYAw5?la&dVJ)wj9epIs z=8Il6`#C9){KdpVQbYN!ev-T3pD_A=^UqU9V4yu!IxtNDC_jlAuUBzyvS`iZ7MD zBEQB)II*jf+t905_4<$Qmj}y|CU?KgW{r)tvG>79T94smQe&8z1PoB{R56LGj25tlk6lwQy=SRl9Yy7Qq& zr0j|{b0Qfs>qIkH2zUNuYmwOdVe5ViFZ+^0@D=)tFs$JWg$So>~ z=ZDdRi?Ns^kq9CrwXq>};lzD-Y;B<$H9Wn^Lxd5xa!*)xp-Dq4D(2$$-$T>MVN=iG zW>#K_puDWqpA;{J2RS-Q*U7c7EM?k-ROr)xLmCEo7$FM{hB%Mq{I6Lf+nvQL)nc`i zR)D1bwNu3NdutXd0RJS(XMu%e+>rpWHJkk`yKYKqwWQ$t z2~qUXfK{rzrv9`pz(m<>AnWyV)LZDX{Ck#S*1iDOt@(DGHzGuke}xO~wCV!>Ku;W4 z&qt}@v#7VQ2mZou5@F_emupqUz0m$96*aBy7wA?-L!{Q@cI!s?P6ZLN+Z}SkX)Y`n zs~CD*E3WE><*n2xFGOKR`8&ZWkPo|_)>PNy>{gu!pIVPaTc1j-?aEsss2r|ad`{lV z&~}ZgU@+NQ$-yGea9&q{LL_{Unt`0Xn<0W}HD-ZPnedKJkpYiO$c4no4AT07eKRXc z6ZEhX-Vx(90-xz%`Gi2@!aMm`NyB|bSC@@?UaT5walzBB2c2@@zBNAR(ycvT9kuXtAf$vk8 zs5qAQ9jyWp8HA5GxxlE6t)rmMr=CPwbmTWuCs0{_#>M}Xmid0C8ZesULGhpR$%o%*u{RTq<%8@A-%_y*Y?6Yaqrp!dbx zY8(0ySxtRwV1JNOA=OIWMH3*vwR!S8-bgM`wYPbK^#!-b^2^!k)!4>h#JTKvgZ(pL z!cClyJ+98o+in&`CF< z9x*^xOHzz_;ySt>$t_liU~?Xxj6Bl>j*bqKDjydO?|=XOFJ15&@Y24Mwn^PQ?)Hyh zKGMWNH>p5B({2hV)BwAdd}mIR?R4i!skh91)8qb#t)yRUpXRuj>WICn$Y1cdHI+6! zfhe=G`p6S~K60(kJ$$4K^^l&-o4tEoME?)Qp5ekt3Gxy-_$zxBQJ?x!;lIWM{Mciw zTeL$TZFnvGT?6Ibp(m8!stjn9qaFF~@4h}xHlvfMc0`&`Eq%MYjPN-@&sjY#4C^Qw z`U#{JubF~0A+YEWgoRH)VkD+%@3HOdZZX&dD1% z^{SUIS;EB9#HB z9O737h~=x)Nl%`9<*+&rtYj-OOFV7@dS{AyLu2~AE#dc=7Sqx%&9(Z#|NKt8fFiBxBDFLMqme5 z^0M}CfD}?GcgXgr&?Jwa;^R7ow6QnM`!~G>%X@8Rmz>U0pKh*B)t1^nV*q&X4f{cV zMRwy&!Wj#7#!Wqf0bK1NIX1`ZzJa5~7pQ*R zNTiM%+?H#3-02p=i|-_DV>^8joJHsd_(GC8Bj}qxs}OKz88Gn5QOHWlP|M4YRFj+1 znVR?bvo;ofcD0V#^cgBnr41-Hg6gB)KPV4^}bBxm#U|{s= z3R81)bF)U0?aIKwgV%t4@ofI!dj3>{#%RZyJW%!kjkNRyuDI1G^H~D{{%4N|?CPK* zk*iA#A9ozQoKoAq5Al8|i=J-P(I;`_Y9FncsP*U&2e0KH)I4i9o)A@SqFk}6LGgGftDBp5gWzND zkLjKoA{CQ$+-cc^=w-h{HGFR!zE-JqkJ(6CX21L%Pxfzk>=fRt6TV-$y5h+=KXIAxBE%3;#OExH zlHGRXhebs>7U|uGetnR1U+>6cPT@)Ed%XE+q49*9UxGSzRXzhRu4BC-$h-r%8ri`Lc8kiWH{x+n@(}l`-+w@a?Cj(ioLUQ@mnQgQLQMnj3u|JrO{^29Y?dEv z)X_3M#JB7aAJ{kzP^T$p)Gb|tNN!11_HMeDf)6L!=f>zs*kV$j_1Wv!1lmetxC1}r zAu^{4zi6vwUfD7l@eM!+T)1)HrDd_#8X^D>i3vEUCCV_^CaQN;gI)+9-EVi3*dS?{ zqWGv+nb@zuV?lQdM81syVU{i|d$C&VsBy4o+Y+;`eW zoIlLHzVc4E)fD!0z0xRJ% zE5G0o>vG3>1VzP#_qiBr3o|VFWCfY(j~-TD)y{->fUroB#=j!jyOSdM$>PUQuz&k* zN(X}A!FXoLLS_a2YB&BGkR5$5=&1Qjp%eVv9?U~tgD`L{1%MEqdy!pEYdx0@G&Drd zSbV5&8!(zjpYXO_D}*TMWnI^cs}BEw-R0(B>5TBdgl$h7nx+>Z*uhvj{B2nUQ2Ihh zq;2E@J}XciDBf>N<$r5uBX4%Ve`-6$C=~pzF;@i+li@8dB<%Dia?$SpXfny)Qz&{}nUlGn z8Jj|UE;4n8!)m%(5wv>~g$$DA>l%fJZ15d8;)dRLl@rpiuX ze=aXw&|%!`H9RTZL-a5shh5(VKh}j#mVXG!Z%KBT(saLQXK2;p$5Z7_)pZ@y7OFg8 zI7;8cdmU_?$AjY?n=SUZZ{nG3YgnY#wt*sg=C~{5Q-QR>48JzoQbD0Jygr}8UPxge zY+`G_944E9+uLkPljxH8WcNSd0*S>C0~kons}IsSfmJaaF8cOb^-~$p>ZIhKz2-Qm z$@C^4Yfs1o5-Cr!A4v#RW~+f$Zz|~^+yFAaK=7#@0DMUyD1V9Aw|5a10#gWV?ua^f z6vJ*X+ikjcNdLMFV#fq#b+~a82>Ol|A{70i3OmMKQ=~3*P`A}@W#yW$DXJTsymN42 zS{i)LYltzU(K)`Rg+Ff2oV2|83G|7S(wrqEsmJK$tWh}!5rTJt&-fb-^?u6xiJkhV zhvPB(uN>pu>$bg-G}qz@5e3!h zxMH#``A9jlq6iffP++zj6nDvf6&r#Lukat>@MX7036t6=j>s3}MT^AzB!Tq$pL!{; zaH@dQ?NJPq!u1<;*fxBBAUrxwU+!~#KN%QlBpuvC~&bEQbBc z#$eMY0itol&((2;Q#*)|4hrW{01%Qt>l`f*;l%tTV)IADlFV9cn&}`_ zY%hEO%=?VX;-07Z(Icr90jQ|r75o23x4}zT1Dj3;^c*@e7kJ+H=GScDoHa$^&I3%o zYSj4~@o?r6bgz3A)A}Edy@C@nydt-^HxRPA?30TzQj>r19$WSI!6h-_d(mD7u zi8{VprRoM-txFuKH>M#|xCZmv?`#)K5Njn&ml~-bzJpOnzwZbw*h z=5Z3wNR}0`2MMj{xsGCUaVufx?_CPHq7B;CQl$*r%0#c`A&&^e;t=mT$g2QE{HrA{ zdm3b`6xpetaeKQ*-j{I`($+*2XP*U8?tNiC8)ggQ>wwl9HQ1L*<}Ss__-hj3Q^Qd4 z=G!PKT1OY)M!F&EUx5`d zj|Nu9C3m@{Jbq~k);G@8z&pKdrC@?h0F1*o^a-J z45DQbd|Oj``5`Ealg|WH3h(yLQ5(EUok2|^I->^uyqZo!;#WhM3bjpVM2Wh@b`n09 z(|wo3+;bxnxMB(Uf94o-uN*Xuyc0tY%=9 z!+0>>JrPiq(YSoVzDnXWFDDJ_nY-6I2G77z*Y0qUtwf#) zX>~|X(lX#M$d0|}CzMZ1#FgCCeveY$53aP;Mc=RGom!lKYvS|@4UvMCh-WLExE(YY z7ANGo^D$rb+h$WXEDQ0OG~qYgPa{5+>2ouF*!ebDLu6b#Nw6Daqu!iI;QDbNThQ2A z0H&K2{?=k5qxi2pMz2xHt4IvK4Q&TcKJ2uG=>}6_+tF1QK&w99OuEA6O(pNT7~zj- ztmg)QA!^bnt}HXTbF@b=OsYAY#@;hbqAejaSy0?wK({vqT*5`9PA`n!u391!UK;U9 zP^jgtsoF9nEu$2Ye+813b$J{i)9#kXdzZ{p6#eBJq8zb$e}6Uzkv+<2SSjWF%RVNG zn3TCmXqEOCK#XayGJtuReqglWGi4z>{}vnb;YPqk0(R;(dh+`iBX^froB;NB=R?gQ%huKdj@?cj-!rwXAih`4BNyEpYXxPMzG3K1RO<7 z3Zjd#;p&62>`J22Qm?)X64+%6_jD+ylkqQ&jBXrOJLH~fw_?B(1h5|^X^bvb^b8li z`s`{ljL06kP9Y5Zp5hxR#rBQ_)>=w)LpNnX(#x94EmO_bA)=V@Z2vyXxS?e3 z#^C4gNvhKCe@bV&qVxeod!+6@mZq60=n5B^arF7AP~kH3Pwt5+Dd}bUwvn4+tL}5i z>Gw7&$!ly(2@DJbP#=K~P*pA9wA6v&q#6HaB1UQRSc0T_`%~i{JpZFmIu!qUt%1@H zQ(3oFHVbT0`l}I&;*Ek$mOPdLDqgV08+wm^;42a6`u|c+Iz`tzbwI3O4_)nOWk}Zx zS8uZ08qE8tTDF|}oN&T~#@SL7HY68BTCa`Z2};-T8b)-f`DMSB$c6M6u$!%%=>T%5 zwf;3f3r|BllLbN8ps22T(^Ss*9IiBWAeNKweI!KQ8}S2^ufrj)ao@jZ=pcDy?Fp*sEQ(@(Ov~-cGaBVLp#qBOcn4Gy;=htd@!g^_^9p|A;W>zocTJ^6LR&8G z_?!>$56PE68#b7MNA&UyH1MFI-B22aBtnh+$X*v)XxztmLUv0z;u+JM`u8$lP|>Z^ z#%4Am(u5k2ooZ3FNc=(~Lm~!>RgJu+?N|lWc()f{poNE+!9u_Drf3E2+qJN2hqGxX z$Zfway{htQE^pY)kE}t`@-~N{O4aH4QfOtPJgdIQ3YXTgxpFF_qgF&RzVU{yM;2~f zs|pUz&#l*a6y`9lZnc!$Z;lw=uhuYN);V6-*TApLRU%O8a0MDyy|o)VM=N?)c8~q^ zqi$?4tokdm#p24KA}{660B>Z)m4p;TB^6@3Vs}-I_Gy&7XT5NXIqm&BN&N%uhf#4B zZ41Gf-rJTEi#ey1i#rW|M}{G+U)%lhF^J5`?7o5pDmJs#cH2>}JDNsuaIk6}PPW%L zpFbOT$f(vME!*Z3@Jkf$ zidK)t+F2+8HW4}#1ytDp!0CaYbB)$~$v50Y30#^8dF}A_zX(I@UtII+*Doy&G&OpuSI^ENuxYM|csbE>lEy?zQj6v_3_9Tn$2?EWe?x#g3$Ttm}VMuEV=4 zoIq+H^lWUK9h(@(uJ*myxa7Q=V;qK~78G}h zY#jQNxd#NVpTCQEiV2Hk2*_!eq^n{}_KW5IW=SI>sz#K-%>`zdiMU*2 z`uWMBv*cDiSkm>tJuTuTqr6eH5)cfqYYuJDGw&{6lR>J{7hGZNYeT9S6(?Q)aFrIs z`GO;CF=qvTrDL!mxjsQhovVBB?hk8K=!T?l62cjZlZHck&~H)|S*dY`#-zF6r<+lY z?~kRdcdVN*p%?IXC-WLmKm1-nh^BqrJLAaqCCN-}iJx`NnyMOsi{AzD!VQKZPN0T? z<@;P66K`>mlthUNWx`M`neEq0xJ|)fE`d>t9FdAEoH6vAZ_hOgVmj-kE)HToj!_I4 zVy(2xx@p`znoGIdPv?*c3v+cQt;pyvZWz`@Y;4p;814<@%#x3~^Y@@e0Y|;kVn+J$ zsEZf+$7jmjcFD7~X087_+C=zW!qsTWCh++UAHA%U(v^E&%nkXO4JTeAeOU=kyx-q+)-Cdv_y*v;tJjxf z=aeG)@M%@~1E`Bc99uv`P}w0*Oh6e{N~7tweYW4y2>F4?LID^(eT7w2?(MtDr9#`)o?)!#^muLI+&y! zx48Oy6|YDcDr>gYJyW_IAa(QSu6RJx>9yU791nScfwN{4fHzJA0E~k%6^~~l@OyVw z%5?44#~D4^<=yklEk56M`pT~MRg?gSxHdKqAc^ZwsOKIm@W+=@w(hjkOUh3c%J+i6 zCWy@U*!Zgdhp`~rKQ#HEs@ey1l)FuFh&{eDe|{J@7Z=&+v-f~OAi$GRRP$ePMVYn5 zCCUY7ltHa=_M9YpdWMsEqn=J1AlZ3aT#Sl5XEXa{RmNuw3S`!Sauk`c!+KFjHmh2} zoD{4H-QPa4JN;2(h&XE7u|^IZK~}K4md3k0*AGVzu_Iq@#oK#`Ym`H&w+%cEwG(;V z^)eWqs|Y8DWDF?hM@uuCU^dLisX&4KW6-!OY~!b$pDB&2Q6-GYwG(GTrWw}D9V?Dx z-H}QC-2-?x?Im$9Wz6b6fTGwf9m27umm@Q+HVRgR#P-)(upQPoWL8%lsubkEgSv{@hdN{D>?TF;OTZNXYBz3TNB;veqj*WHI3H*t3+!1n|Hv{W~&cXLH_ zQY>4w7U2uBE`LaeT#mDHhVrjDJTgkeEf2r1cl3ZMLb)qgo$p9{Gihz$>7 zM!Fjjh8diK4jagBz0s&y5(i0pHy3!KE(Zqnt|YYrhVABf!W9=q!wsx$He&p$()n@H zd$n$#t`cIx;cXGHbro10X~2Z$UBP8G2#mo?1U6~BxgddyILB-)KP+P2;RRRtdEz3BLDOw3L2ZZY)o5o0|yOW3Ro{f`(b8IcrW4zU;S z*~!Iq+S6qLj;#5{>2)%ocI9X~!(U%tXRz6aY85AW-O|IY?5@bugdSj;puDK9HTG--b*@ED#$fg~O}-kk zSGpPjF7^a99PkWW>Gm(ti!Q?Q-+8C;zl>X);|>KknLHYq1rDzaS@=MKQK=k7VgoVy z3on4BHL=6o-WFzl%`Uy)l7kyE-rIU2h(R5RAt?)CUXS%mJIhf09QvE9n7W|r73q7~ zlWsrAaxFG}ML6V>u#%HIcdvu8x^cswiCu!ja2%PC$Pazv-4Xta(_;CsrBhA^m%diY$gT9g+#o#@Kj-do3B`Tf z$?B7{?~=*|8&pxiCmbbIPk##++39LzKpm|U6v~(yrg5+;mNENItz(;r8V^V(w}-4} zH&!AzK>OGQt$5uIiG#pMc9=XzlXG9^6Ey@r=npyhP-bJX_UvoNN+~QbkW1+`5z6}! z^DThTwSM5(f z@AZ1kK&7UT2`rKX7{4oKD)|f??Kn|)zn%VUsbG}UGBx!_K4D=wsb6bYNL1l&6%9T; zFo0rZw4cNLCWHvz+T!}lNpK z5C-2#INugXpoHCJ&69ZjOO>=^>#J`GZ?)gyJ8cYR<@5IJMr3r`l(cOkmG21*!x_=_QD+pAc)wN;xenThsOy1Q!xa0J?HWh=2D1bzX&G7J z^t8%QQzl`vbJug*G!SdEiyMvY%MhhDB#DOpa!XvJ0K(2^+g~H27E#q#pS_>fp3AtW z{w5(%tkK94$M^1J_HOeo)7!)B5$cz0LDF%@RX0EtM>Z)m)ail9eLWGCMXZxdd8h*7 z6ktesvY`$Z`Rfw{z7g`s73`lj&gWMm51XpAJ;Sn*ZcLCKJF*hu)czMHPSd*j!4$g00u2+uTmf4#i;{pv4qs0lw?7P{yID2i6 zsr<=;v`#B}?`mDTrgVM1U7iIw#;&S&6mP!Z%r`*M5Itkp!R75N#u4N}wfyekJ5OCg zp0t_2n67$zRGr5slV1?c<6?;W^`w!l{$!T_a)k8j!?AF$-6_>6%IPpYBHGnT+4lp6 zGPaIQj;;PXt|sUM_)@DbOK1U5oqqY!IT8M5DGVpwF*7-{&Cq@uXa!*(#V!CGo1?l# zQE0Ke;VI3ps4-7Ql50+HJ}i!a?13wQv82({88S@1=1q1-v~~wM>PB1y60WBjF5iFS zg@fs%2XREs&HYQGjfPx%gMf(@UBKPwT$xCvCtFI_> zCwjuzXdLlD{ohjd@~(bjenunvV>>H9c2FHmR={OTXZX8wi8SnbN`u|-+8V7|+=c03 z-Y#&xL$0q=Zkt3)>5EBbtd0BIXW>+X)-SeE+M_#06AIlALXtGkckt)xJFc|JI1^t8 zGCoQYZ=jbiqD0~hnDbtC8ng(yVr&W!GelAph3%-2roY^kAXLorx4C7cR1@Qt-s1+qk|$)OPN+O zFmJm|?=BeoHP1w*!v0Xs&0ygAAPmQyDeh^2c#0`y(kym zJuv~Br#N(cA~;ueI>|n=Ff%L63=#9p)$AudSpmCNMfPdQ+*9@7n5#?F_osa$r0kZ> zUZT9T?LzXg7jT;x-9P0xfM83_ePT2-&$+Bxb}X&=C{iVL&GWl&zU=Ic=DiHD1A1f{ zWBR-0<(6v}b_7IH^XFcvB?mEmr6xt7jW z-ECyjr5Sz2)`q7xQ7v*kX|8!ScdAqufz%Q*eAv+?RWeQ4V0+ufHJyyBP5`c)JD&J7 zhs%$T+FH?yAV#QAhOSyoH1@F{6V^SHEA{n+=LG`Jb6~_&>7)WJuXp^1hRffL9`p(y zFfSO8{2Qq5HajPc2j0B^#|b_NRk5N8CmUj3fb|4OkdZK*O`Od6O$~7$d@qqsMhO5n zl#~QsTfMA}T0beTJ7!<6f?djOR+oOryvi$_@`Y08nwY=3_BhB0PZNWhzwh4v8hghl z)?kYSNnc=C$Z_Yc;Y>f1GRQ-N$Gu{GsQU!>2y)}>g%@5}ch;GF-?N&;A4wz3iwAhv zpBmc!rk5GrMUNh-m+!1r^rEXe`ctFJZe?i^E8=G77#Mh4*G(L+cfC-vG^bPKK9pUL zXL~F95ZdK`ngqib)t);%`OC-c@@%&iX@-{-Cx?CpdQu9O{Lr!n#mvXCs`&xUknj zghB_M0`9;73*fA=g2|7#1jNGn%@tsiO1%aCM#EmECV}Ugu(pb#tLJ9Y2sp)tn7L+D z%l9Az^zEvRsF!JpWWCA+V1;6*yq{lsESfG3UilucN&IO#f92{U=-U!yD&5|qCrP(< zy-M^oouFC0W_x;&zQQM&p!s2n&*+-<{ZyAtK^yyGu$>=!t_$;zRO;wdVILY2bYI^G zu|aE}Lz}c4TH+R5lig36*(_gz&l-q<{qlySF?c1y!4n@N2xL)asSfei33Ok-jv#90 zlxu@hyyOrK=rTwd=vl}=X3rVCIg?$RD9z{|fRq@^d-%ME4ai}aU9rTGsD2}iJFc%t z8;8SeamOLJHS27MXSZ^GL+W>RrU@ftwx-p-t6A>WAUe*8xan?)kK0LE*}V38fA4Ef|bf9c_BK!2FWj@xEcy8;D*?|kP%_A7Vc$D0YO9OZ&nD=a*>r%SxF zAkEDpmaEC>AlV}=?{mA!@m5bd3Pa8e#m78M10D*8Js5TGO2zr!mg+!O+p#<$1A=Wk!y) znHjWQNKh1};Sn88J*a+oNu6oocH#O z@dboGvQN@fz!#f8 z0c})e=(T^|T&ow^<8>$b$0bLne#7sVkjkb28WKjOd8?4F^elS+)dF}p-5NbK@9F7l zRiQO_Gr0ajpWWOH8WxSb{=8J%)16KX_aL{(hk{9FBB+_EzW3c{d|$U;-ma*t+&hvY zo~l7xxcp6s2a>lhrH(+jy#>9xyeOfOJ$WQxq9IY&OFZ9K{dQ>IfrplZCbPM~xFDUK za?--`?*;ZYR3#Fv!s(cyXKUA9&*2uHVR+G1to6r{e4jmMUpgC-T?+Af#dRHKr!@VW zbfR1Z-&+5woetT*_6-nN8}D+QNHQi}B-VuqX1TqKKfzrZ@WmrR2;;*O$C0SyTO29J zP%po@G36ydz&&G-)YcH(W@#r*oHv|~Zz+9D#1@;K8GRe}4D{FhX4axK9kdaf`RiIDu?{TI^M@P3wH|L_Jre5v> zHtG)kjd?FxY#au!X#>D}f}^c(t>8?O6Xz$^6?+TQt0Cjq4ta6BaSrKe`* z5cY3IxZGTp*QTIMBKMmcrQx*|sCYMM1QKMMwtg%_q<{WY#>*v$g2oP&E1XRoF_ZC0$Z zBZFfNx>szy@>%uU%m&_vVjOq~wV+|#S}jx0`)m#EA04oW1o-J*)&@83dr#)qKShBU zd^MK7n#}c@Wg*Aet7#NLZ->{__VK;1`?`JeUD5}@jzpMCZI~p{a@IKN`*b%5!i2WK_-; z;o;!}sr;pE{J%1il9QpIXR0imoP!FUK0{xAxu=DkO4R;PEyX)^_6dQB^U9l;3%3Hb z%hwyIhsS!!(4Ax?CMc(lM6C5NmOrzj9JW93f@LmV5<3ZEWxywH(EKeo0arY^1h~cc z&dyG09BIiMTw8l zy^uE@JJ;Dk7O0i2l z9&D;*I1n}s8DZa=5-;H*W@RPcGZf7=7M}7=>wMp?g=mjI)>aW6B1?Jr3rh+-B>rT) zY63`Vw?FE!zLT{g3@{XVS~~ZZm3EcT%16K3 zeX;7!Tpc17{2gu2mq4`|m4EzeIa_3TStQUwSC7=)hFvW#@3ZF4lKxixoxeGVA3TnO z0f#HhzT3B>+0c?m@ggdo!X`J9{=JRUmw2Sqc>fPTan94L=vn~zxsZ?5|G`vT9shy^ z1q9P^Y~7e1RusvCJJOROy}s8m6=}*%J2ze6Ns0_O_TdH$h|*1gjjlF5V2LNx?AXo; zR_M;lA=VmFw)Q1>7FMlo0-r-vg9lE;nUmr$*=HOsTUs(D3M>?=MP`u!X$?)wrg zZLf@iw*Sw@kD(XujEq~bahELQuA$al*gXa zw3&m~Y8m&yY6tOk*W3p_uM%a@q^ln=5?ZaU|(7d+;laB9;vTDznL z_qDMmYp`N`JXvWE{i0~kN3bgY0zP;61OzF5_G%t0m9X{3JTr&7-h^@* zU7jk~EyI80H1l(G^uIEqQF?NSc{vayEG;b+CY%dwW-&RMuT}&(TJ9XznoyA8M5s$v1vyVhB{wo>2a-2>0L)mZxj%)x5e3Rg$Ft^H5D!Rf9+FB-kd-9i4#Z z!Lfso>tw3&C2jC;GC;x*tmgz*cz~zQi3TrL@&XIZkYFcRtEcIT(-B>E=VwYjvO_R~%wT~%)pt>vjdFy=^bL4Z>)6`M# zUm29qY%cy9g}OVXGtt@W8bl%of?f6+Zj`Z>q6jqF8`47ma3 zzKxs@FO-W0$XaXwGCv>>gvqb2q&+ddTn$98IDnm;FZsQn_^o3&X@8kP{=)vp#z4*N z4(z3$wvWG9F-TllpINNYQ6MR5d;QwOGY9!<+JzRnJ;H1LF$M?-vTonv<2wOWr54nl z8fYHPvlN=I+0V;+pThk($iKLE6{qk7lU|_lwH@#q&Z#4k@Xq02t+f z#h6Hhy}(`MhSpQq`sY-|aDiVQIiZ>9n89q=G9QSx1 z*|#Cj@)1wA+59qIp4FN9R`vby{_ImO&S1D(emX2t898z*t~V)NUEdaov@o-pP=dP5 z=Dn9npOjRvR|G0&A!Eb*eUMR-%;HoxBBone>CFHFm5v0C-JxLLtXK5OJhE`lJ9PWr zEpiY~G43Yr!5u%Gug@RxlJwuRPA&Btc#n7EgubUY%{&;74|G7JH)vAtgDeX6(AGw7 z^f`EB+@N|B;x4}ap8t6MHY@|f?{<`WA7f_0B^x~a;2GUV zZLPM>SeLz4kty5V{SQMa78Nb7zG|nmWaZ3!ONn5oAIHMraN>c52IpgVpivUPtJ*27 z#PYz)j71goVyR@?r_NW!4gs_qnIWuwz($F8h`;u{hRSy7(k|h6O6OLTLJYVjtc&Ws zCpHP*r`I+Bn7{yJ*JwOp)sNNO0QTy|zSkWT;Z}Pqc%jaFeAG7@=PM>?=!FCC=Q&8d zz*cPG_F+DKwf@d?9pr1j&Z&5RkfuJBFVV_DG7&N7Y=`N8zf&D&XSF}U(=`la^5U_J zx5w9jv3ox#l1=+$mv`*W0FdpSL32mK>WTYW;>eloh1ZVXs^GQAg}PSWP5M(7-6{X> z9fs59kZD^W^7ur$V_R+P+S;1AIpFjCu20rS^ipJ>iuI4ouB`xIbw44C=UzmDh-{Mi znH@_2m-PcWAegpohdf7LrSw4GbARzi1X;}s;JcjI8Xx&JFIlmKs9t$vaARf(|93PO zi2!JL1(-OJ4UDn)_(5JpMI|GJ%LKOm9ccCV_pIo(nvaOFq?|HDQLm9kt5cYD?@ay@ zhN7+_acM&Tgk6h`$RY@7HGV6%wq^*P{TMC?#hFau0haL^eH{K5olYQ&W$?^gQ#dT1q z$osyfaeKeNTDM50o^Tw(z^^h%zVl5;A(x4GL$MI|C~pFFYmz5?Snqezu)*(`$n2@+ zL5N!XpeWIqmD{5<84L6_96Mg!#hWp7w|!T*&;y7CPY@=g6Ehcv7&~<#FdDz&)AkL741Q)=of?1IU=Bc!ntU%sTu-& z1uGU@f&JZUv2mn7em3)dO{h+vG%>bNBZ&Bk_xWCIGKx-&c0?6YwtB*$Xb1RdSDE{Y z=`pK5Ee#-&a46>bsmJCuKMMLWa@ZXt`$PkVEvu0f8{6LKaXN#K1nRHZH{Tda_quKm z!PGJS+pL6Ej9q4eZ0-3hdhe?uHj}8))_Wk2A9Y++1=^5gSv5h#+Tp!|E*%dI_@7~QZ}8XEHD&-*X9@s0_AOH-d;{?I1;^>c&eb2x*=v9!z1!V;<9+TJ+(6TF3T=SJUOt9DX4Y;8JmkfrSL(9&WsB`6T7eZ*2urb7@*4&=sMbw+{w#iVZF+WSk?Y|Lx|aF< zlW>1DB_}%@z;3MxSvAE?R+$!ShirkBhn@#>bs9S;YCz%;UjLP%%!Arm2PIP=&65}t z113JAOU#K3GJ56-Bo4N0c60+2BwE2H^J8VJYWD3TWWz4B0jpk%p^eXgw1HTF*YQ2! zKSklQZ7Gp~%H*+`nVYrFaDq~=%Xzn;@&d*G+GutI+7)ZXSX_!gm49JreV`O%&F%6N^Lr~a#Z;11| zP;vm8|ohL9)8EKE&i^3q+~JRF9CGj6Iv$xA%9nvzlc zsWh}FI@NHSWaN8}#}9WaQQqd$JY}9GOroOcz@!>*TAFu#u9J?oc1E&*!%s0n7XXIn z(aJ3+{Ue6ySBIK$!)>ko{1)zLoSfJXd+v-;_XZB@dkGxC@(VVY;s&P}1d;h-X8{Q4 z?HuxOAAcLmVi?0=bQ)Q(c9z(`q5TUg<%X6n7z{pM131?BtAC?8VCp#Gz7g$|aszdr zNh>!7Y5mp&uT;I3>Iq9u%NrrU!t1vySlEd+Mh%0SGMB5f4HyR3C`F+iOTl72BG18B zK&OT*(Rmx!II%9hzx?ZD0!pecfJ%sk$uN;^bFe(fh2Wk+-#<=E zcIsqVz{tLXSa;7PM)3~pT7jnpKG>jbcs+T4gxPeqGQ=Hv2=xAyG%xxZ35$7pXrOA0 zyX4SK-QCW$W!w}^8}ui%cuqRGo60!oL3fYO<0m~am7yk<%Oo*+-%@%2yg%dS?r1&z zb(Ivqb3^gYcgefkN*$7mVht^5ISsQ35EeH|wih}qC??ly7K@|2;M}H1%t~(0Z*^}X z+@@y35zBy2j%#r_PaYefGwU}BkOKc6 z@C8fH`?Wi#?$dl>F~y6rV}Wpz;2@*cD4(}km?b95hMYAai<^cN^I=WqFPio2B;*mH zMy4`fJ5zuT`1&7bYjD@1s^~~}P)#Tf26MueFxQtEO=wM&l@6DVQ7%h^_b6Pm!#$R5 z^S;?oswiacSzOs@1^O+5fWH+vmXUS)jl^qA3o)W3EldnUd8_So!Vw`@ts7ZeFyS^n<^Z`T?GQ-awNuq>pzSXv>O@_2I>-fGk zdE3#vW43XBXbC#)KHn?)y!U(a;ovS4$$No=>8@q7=D2eQkwUva#oeL9=&hd{a!ivN z;i1Yy8vyzc15U*DVV|^y@`R9_)#g;+0(+HGv)4_3jxq@u_o>pz5VNt?SiA^6lJ~A- ze<~A(??F6l%`Lm9sF$B)IqWjWaf=!Ef0K?9_;{OKh%5T|He2Jyv`{>*4g%_?Z3`+} zthohv%CD9##SEW4wu`qQ3jplQZSO05K`4`pi&f_eZ;<&h(@9mX4u> zrC?(nNi!q5quY(ej-uNi_T=9!*Z^LeG~hY0kKo)DyB*_SqR>kl%^=?qITwLmHR zMsJTW{a*tROo)ucG8@kLU~Igy{oOJna>18$5Z*b>D60I(3TO|6%z?u1WM#rz|s&spB_GGtYHFwx9Xi(2PliynR75a6p6BM> z%fG&}IEN>+6I`h?I6kuGjvKOWLkw?PY^qyyTDo%~@QO>^icpcxa|`Ph-vMwC)&-U6 zOkN;Sdia!sG&ASx5lh19{msJCR}@O}4{yBO>VJWIm{Xq)ff>~}&ABDp5j z)YL>z_U-(1s0@KPAv+7j*)u>a^`@eHd|h7cI4C_ zK&3KDG384PK#TYI8@>c5Z>9VO3<-+-a5A8XgubXab`cN%<&yJ8vSe^K22#fUco4Qc z@q+&z@I@~G0}QoVZy5M8Z4RVKdM+*p@54pQ(=E}x#RA(KIo+|Cl-+~&5{33UX65F} z$ql+(i#ANO_}CfN{2CZMzR1dqp>oscDH#nve}z3j%~r_}EtXnHN+^}LdT8R`yx=oi6utHm2%Md6D zA#epQ=^V6piI!$mP*)(EfmRfStATy);?`xn*4w+fymB`0)kUt1<7|*|l6C%Cx!P@( zCYax-d)>VM!hMIwOX>nJ5l-Q0)!Po2bbdGy(gRQn#~*ae&MIj=r!P++g#v@`;t3!F z?74;EU#RhS7l*bqX$<|kHCPRwKs_Vm`0A>`cXHlhmpNfV>{K;(IiNo51CYkCBZA7m z-u}%0*_@C!8Sk|d_ucR`Kl~UyL_zV)p%^d)AenI8YF?JDQu^bD?Uu1tClV->B`gG4!hJE)Lukmhe@o<#TV1P2*S%Lpwp(* zE{_3#Rj(bV%_`8{#<`Dj!PXi8{3|-P+B)6-`POl`us0PVWfs$uYd4(DSL^3{Ppy8i zrMnpfWUzpE?+VrxG&5&@(L-KCVf)2c?deIk@Wu%jl-eRMJ&(*ysy~xdAL*4n%@Cf&X zr3B(Df}x!tlUuYfiZnw!{^v*xkq&yuH1f5ZqywtoV*b?v5O{Pp;Dr|g(hZHM;nQ)3 zHR#=JrB2pI(a^nP2?&0HOra$Y6lSS&b$uc_!t{%5N=1KojjFi>?x=E3lI5M~WeQhS-U5~L zn^N1-PrKB1%R`&kJ)Z#4Sv<2)op7Fq&e`&zRiB{lWO)F(J|Pc0^s$SALdaLf!*$9`{&D>2`4+H}a7@Qhje73;3ZwuXa1B)MZ5_>FMp;1hYuQYS3bN9HMY19XLyHvPR$N3S_X@>Au|a zFSkd?53WGLSLhA5@|bU1ntRQjIt7u>jaeO?=7FyCUF$lWtECA$;n=ph2a2NLy&Hm+ z$Jv+L&vV)eVA%@9_8g=g$=?VN?c-+4b009(SP5F`^5qiw&dyTqZS$@_2@h3(jIWx& z)64QPV%;n2V{eL=Y5z0D{qA!)yGuO5_qG1_AO*lB zP(GENQ|@J;1yk9yrm_c4nbg3Hn@@Qt#4{}P?_S7NLD@wbN4>ThCdChUc$vkboNjA< zsGs?VsqgLnCIti?8`0Lc)nRH4F|K`G@8K2}oW{qjymgIkhfSXD%@CoWpr8#l!lR0u zT(6?Bavb1pow=9Qr|R(auiV^EY=K(t?;E6oDo4QddNy*@rJRz9_DOKdB+E(a*D@`^(!3P&S32? zRuXkRT2HG6^ggOIr(f10oF51?3F4M0Bl$d zB8}}{Q~T4|yhWIq2ta*? zOvWs7nF^F#&kMkxZ|_r0Gl*oM*K-K?-sKJPUfmz!A6#9S0JhNo=JSo-Ov&P&?b+NRnnx#(T8baiz-Qe*);9;E0Nm|dmX zd8rzZ^{+vD1_ZOmQ2~w5z)B-J55(6zR^rxH0A~vxJEeb1xCMQnPQLxnLqU1Z74)I( zLD2n9LGxx&sha=hzgjGEC-01qVYeN@0$8$FL_~xi`QP92WK+PYf6-4IiwJrZP1@H* z-xb+pkCX3lk2Z@guzZBNKSw}0a%OY@ZPP@Fz;kuty=XhX>ic6zH64!5=QpLqB|xK` zL-!2K-bZ{iOZX~_zs**92)|4>y=KQv!BGQYIdQt0cL zN(4HeNqe#8^2_MkWsgefPgF*53Rhzj&Eoa`J?)6ylrSmvZ`|sivL0kqmisfc#hf!_Z<$OriPy!MOL`I`~qcnkH!bw6v2(w&IHBXV&mmFB-8lyJ-d#7$# zY?!nMqE59pF4n>0(zcY5fhd<`Ehr(~bP37pncjMWJ&)4>wdT-1r1wzB;i%lZ0w6&% zJX_LIhiq;Sg#k!$-Nfm-zX1?;YDu-4JM^z1DEa_2{>*a3kf+u_r_1uSOPFwtKTeIS zA6r*P<;?gWV&Vh{EVaQo`l*lBQK+u2?l}=rrTek5MCR}O@4nSgs6gYV-dMlzrx|uM z_>%vC*xGP1uCTn&wG2+{SI-9n&K8b=X_rz`z!27(578oh{D7J>sHre~C;hzwS`Ax> zP5%#j*2oMh5`(`l9C4Si~FiKzjGD{VPBxqD#KV++N9*7E&*v_1jd zho|>lifl|Hg74UPXJWnQFZQk}LYQVb+eVPLT~IkI0{rJ;G+tKb?}TM>tvfFYouvaa%h##T2+4=b{M*j zuSCA+7Qds&*gN(W7^Vz2XNygn+KS#{+H2b(CIrL#hpfGdQ$g>em+JS=-hU8OH$h&W zc~`T?zW&+t1;Fw!kOwN^tp*2hLX9FFxS-(IuMsISdS2lp9~|@hcT2X$*wuK7x&L`m zW5goXN?@Z(CDgD*{r;ad(T%)PpjUf zvZGE;PsPv>#0Ieo3^>@?OLQte^}3m;J#E~R((1yQYQ(Ey3sWL5!TrCqTsN??VSDuC zZTlQp$q9~61UHrNjlg$INJE+5hc&P$8cY`_$lQP3<{cI-7pum6*vtTipIWC0lE#6RK|!uKO`wrqA4NIiwLw-+iYPiY;^W3|6r}wGm7? z?A+nMYkbT4IloO13Jwl_u6>&!&uR5?syW6*2rRKAH57j!^lW>@Eb>5J8Is}MRlK<# zs{XksScxSR4|dYsAhO-3OO(c$StiN&?OmBY{-mx8)1&ih&ZlfTSVMg!tgO-5*K@VA z=M%Q&+^E=PqHtYIHQ>tA0a==C6zkoAIjnXHd;-O~p1;~RKK zfddzi(xN%#i4tG2dPf0lHfrB%ZHtEPgMn8U=MOi!jdf08{SnTu00pFg%Hj@_x5sBd zz1dJOS))-7@FqVS$N4USPB7`mBD#x@eA4CIP$x?&#r?+{TR}DKHk@K=e$lqEKuQ2t z&)xe~i&tnKhXNTk=d$a#LaXeXqa+U0S5Kt_fsqIyx+n1zRDz z=_#@6qGtfGp?9l1r^5^k(*SMv2I|dXyZ;8Q+K>#jzoJ#@@g>K+|L#gXPRZ(uv3(Ro z$(8CRihQ_Q!=Sej^A$Kf^IM%J#ucmM=)>{b=&CbkkeHv)=@46c@OQ4_!DM@uVC|RW zks@iFABx`uwsGdeV?u1YmJMF6L|K7!uPvtQn;I)D37YS%%1ERA$q-Do_YL^@drjWN^==$+VyI-wHz-E&Qvj#!nG@P=9L<|0_P$%fZNsNPfN}>)?azG< z{+`yFXqnV>n627m!lp1!jj;TdHE>A?S`z*9M47?%8T*oP>r^l+SvLerPIODu6Js-J zU@e1e6C9U9SgNva5=-E%>#~4n*uykC!58+~5_^nxTCp{cOex1I-*3l;a1YlodawO8 zWgFCXZNrw$a-{gf8J;fo(L*ySskQ>;mQzgyTSszW4OQ*sN7twy8=>lUExY;_0j?qb zh$6KIcmQfLThjd0+W{agB8|pWVmdWp^D?Bf=OXEHk42w6bFW0tJxr1iZloJ$RP+y- z{HKYDza@0mSJX4A(~q1?6>vAZb#cbtG3X$lQ_X{_aW6Th-b^_tE(R!5?CDYnN^o30egF#}_nJpQETvy0rMQqTRI^|Mkf36Pn06Nk9{kk`Bf)y3IJhmZ8cE1FaJ;YT);ztu-*SPbO#3;MdnHis$x|5s$Bx!j!Zc1siKIRg|n zESU-j0|Nh#7$e<=F`~VMSt(4HAA2Eg|pw zvw{-qfZ6>_p&z+$UyGP#l<(<1zkP+%ySdC^FjNcK>l*7vX>W^4-qBO?f-B6yk$5v# zcKYV1k{bVx)m+fYI^{+G(iJ`$s)~c^sY3-Sejiy|G5_$=#!C68+*jQVDi&dY8Z>qh zrv6atES-q!9p1fwMp}&FLI}VJd1W#`^FX^VJa58LHtFKXKi^8nw+~1?oJ=1p7yUAE z#|~FKIpVp3LO5n;5Af{$=~@Pp%r7?OiO$W}hnO=oef$A&ME(1vo9?I{fD|@gg>M1@ zZ&Y>NhiZg{4gU9TF-w6Z+DYwYU!AGro7CI0ZE#P~PisP(qOBv($bi{APfQ&5&(aoQ zlkl9mtvYB|8uBRaC8B>u37Yi2UgF~b-CZ;^R1>8JVu0Yc?PR@QkqGIbV`XIp2Dsfj zntv|xHk3WSI10({(3c=hfECRe^~Yn~Kiy%t1%Lz$>C1pQ*=x}g#zkWE?S+Q#zlLBq zs78RYtQqSj197!9sPX4k)W5@V%_(9|SxJG>eC$;M$y2y}++^w|sa*XyzU^mV%I=1 zUf@E{Lzn)6(_52u1n6E-joeM6L1|Z_M}|kU_WnST8RS~zKY68;)Hp}y3@=vyJBg7% z8fRDMpM}N9Yz(fFJM68T?Sx1;)ITgqmn?&<1&{}i#I>`idC4MweNxC_z~Bt^Cpf2d zP{00D)KnGgM_tVXtXd&7l=W+W~vo`I{D122cL5YHhU zFuupR=b*F_TV@S&$Lgm-p#@<^l=jQ$o4td|(~ISQg)`~+RoYPI9s=h_y|?K|K#_Y( zUb>AYLGNQ=8(X)@&9e|X%V3I<|NW@k>cL=6NOwAPkb#ub?~`MxB_2X@IwW}dS`N-X zu9{-Xxe;D?nAb!@4l`PGsq=m-?)4n9e#Vuty55k)k8^5O27f@DaeQ_-Lc!RVgC?4nr!ioO~#C5M0m@A zvRA&G9{~I(H=&UTh8FNjekcN0-1a+7OYHhI^hyCq00`y-Urpp{Gt zoe8e%r#MfV{RAY`^~Oh5GR$g^YIV#pB?ze~L4cV(Ex{`iMY|ZgF+jG*<4es}Aj_{Ruzp{|)6O zd|TXvzabx#6i#8h3NpGOXn$UXc+u+|sm8|&=Uf8~Stwyij6W@+0BT<9?J+kwka zkEiMADPZpB$&VilcSKu9Tw1~B{wzJG^g9ahseb5tzLdnZSj0`we_z#c{S$ScoezDZ zmRve^F9Y_T7V;8Ed|5mnsJxQ=W%++z8SY2vm-MjE_T}l{oCM_+1Z4Vt$mTfv0nRmV zCO)Dak5pAFt=Y+=qcJK4!w=fGeHK9c?AmG^#E=CSDvG1@+|HgJu`S#)gnCKpeh&J^ zp(k>~f*|qK^7Ov+{NYkd0Spm-H1*#UfVE>P=#V3AzR*xKr#B?&1l6sA|{wf8R zq{Pwz1$aj>Z7KSM)ovP5Ad%U~ZoZ5*H$rSoC27cW8&xi0G4#sQIQBao)jYBWdF{rS zQNleYi#Kv68ow=%x?YM&v=-L+;ivpLcun;y?fGD8-EIAZPXCb~gk;spt1x$IVSC!$ zdv)4>;v2DPn+?I(hjXp!oY#h{2Jh66xL0l7OuHJ4&R%jonfO`)1cJ-7&TFTXpz`4R zaCfcuKXknXSXEuO2D<6)?h@&e?hZjZl?LhV?vz$gy1PN7Yts^fNJ@uv=cc&}{J#G` z=iGbOqZ?%}Hfzl_<~!c;jxonf=XH3{eI7I7pJ~HEI3$7VB!N|5jwch+j?hL(MP^7~ zm4F|dB&pp2pWg;`3$`7(Tz0~`a>06xOfwqITN@n_=d8#W?f(c|g!DxK^!)h{vA;TA z1+4(}xp{ecRf_36!Z@G0|9KDia`RFA1A2kd&_L5FzoosMq^2E=fC9SYM|fCVvCx+` zV!n4wxe|5sKU;~Z%HqU0gaT>E$+hZ$X?mjt7O^fxa496vj}2O}>#ZInxXRoJ;sOpzZb!*@qXX4z0q61N8Ki(o))2+Ba!EK!6mfrw5mk;Q@ybr1sxE4!Cr$z{%HjS=LfX{4%;jA~Ev8fvfEmvZlv?83 zhn3;8-8p^nl7ge?+7s<|u^o33ots`(+v`m?!cW+E4FYPW6*}({q6*6#Wa*KH0o7;)V9{P$>w->QF>-b`$M-Ff zd`=T~8y#u@pOEFym@IBYctAqe{>Q<{d3Kx2IL|vQ=nsGYNRzuK;J!cWRBz50*oljW zx0B9ecjFT&4*(%ii2$-r9w?gZaMD-q2Rvfe8REz66x6>D4Xexe)%)25>_vMTxv6tIcN7?7n9{sv zk{Qtk7zbZ3WMr4MZhdqRrC?Xw=Q`&aXD#$Njrw)oN1+G{cdeYBc#yFn- z>X)a&fly?aiYQ3>dI5dgp?8X#4<*roDJ@ zQ##ZS{5uY&OBja-x|&TU@OUF=5%2ClhPZs}mKB!d{NwKWEIBOi<-dbQo%isPyFaQq z|5eTQCLSTb3s%gP?Y02r#ma_&UOI>}=Pft==*!4mnwktx1nVAtF^>@AWvPc9Kl$ga zhOksYe9W5?Z-`#`nz<*A(Owq~SFS6JQS{HXYhL{zgCk5N!a4jTLJj;1(Pdt801;Q7 z-la-3{;F*{G16YNAOKOO4!EjogBy#uAJ}Cn^jsT-&YqW@*I3}E#R-^ww+Tscj}C4v zPD2rYS5Mo7Vsh;F{F~wCXKPJY-CJuNmOIM1>lmZHHk6cD_7y3nFCl8$NlCSz4CDsL zW=xYEzKRrKG(>o54)f~!3*yb+vs@@Wdj6&ICKwK+CTleRQmG zZWaZh7$0?yh*nhOA_g8YL*#E7P?eg(ywY%qIN<2O8)D4lRegHtjmj639#bu*wS{){ z5993Q_Jd(Xe`kI0;EWf(L?i(Kt2Mss{jm<=&*bK5$Y03@f2@>}`bghjWo-G58DCEn zPOIkw?2lMUUEb~~H4H0HkY-52!;4Q>vMat1AE0wVQHR054A4{?5Po5!mA=cN+XP9p z&!*53QfE7EzI-xMENNKdQv$EL++LUu#;19TfX_l0(hbp2yy9|)-GU!{BIXZtx;4Hg z@E!Gzh(#N;ux6wIKZw6XVsvuiWc%DuP9Ihxf9KJEDcR1#`1CYp@A(?tn!B5w>EM2G z3Njskx68-0JG+P9K(N?22YQrEBN53(HC!z`gm5bI5rU;(vJULu5`t!(8i)>*lrhVY zvc*_8pTu>kYz-Y9L-Eyp`Js?yvUXF6cnNcUEGqWK>Ope(*d{U5#eNjH#n~2v<7P^J{FK* z+d#C850)55h_XVfml7gK28yVMh>N1lDb{OBJXgCUP`&zs4BK3aX6E;t(|r^<3bMb8 zKI{u-+J^^12w3#V+iHrDF-A!LxMW*-Apt~X&%@|^=xs+l97x%o;lhTLbEG34DzLi4 z5w=x<@c3!yr8eKBaUrP<*(~N*<4CmWXlR@>EM>|AZ%jfM60YnoWw>@#Ju93I{*GFn z0r5demu`MmZ>Z!WhFuHG!p1WQVqMrI(ka6S+We?Z($4D1zmK9+zB;QI6N zGBP^AOhcG40Po*g02BZ_v7mp3ib;G!%MagJbHS+SwPEXD17CUsT?&-oHQ-ADwslu=LV~nX}~%u^~Q5 zn(xW2l^mrCdA;h7rwFJtR|PG}?J{pr?>*i3eJ{q>Wto^=R1c!3|Kfrq_hUWz{B)a! zpF0sz6Jw45UAmeaR~Imoo=$i=L~tl>fmAg0M@{vF)QrINFSy1-3)C+*;zR7C!=d1Q zv1gBMum#0ua)buvm8$3;sHBfd2-cy!J8&u?LklzpB?vb!W9wN3Zx5vm{axyY)s>BT zY{}%}!8%~;`4V8W`4fffg?>{_Tc!7M_m}V^SAFhxdvp0u6v<3+(YSmsf){O|n9l6n znnWKET`d4+9JLZ5DrH{S_f8Q~YU2V21mnq>TWPhOZBrWAK1CK?MX8-5K94ctMR8LB z_caUEf%bKP&j*2xSAB?{p3muW5`#Ls{X&xscQmo#brel*xe)G?=fYA==qppwqwwKb zFnh8l)j;Oge8h*?f5{Jg%wQs&DX@rY#v0#@us>Z|TDneB^{E5!({a6mV^swVYiUKA znEyL2^B<|vr3xZw1sgs2vpIWRV?IszeR&e&t(1Gpl7bf^%%2f*cUeK*K3T>OyyKex zrJlvZchcdOBrp_g#r5;1Wq#H%*FWF32sELH zZ$4oL_@hJwCl|qVC`fBj7@f$8r?U|-ES@O?byzhMX8(9uE|qH>X!22MczQl9I|lA4 z5&pR-UAm(5-F(ELu`$9wE&-gE)&P^;%;K9h6g zp5pboX-AYi36j*vMXn0EO$txOlLs1H@ezFbCUsr{mV^<|ePkxX0*aCtyaxym+4#X< z|Bhhfce-Hl6)7pdKx$aqwBT-IqNe(70p`{-k%IUP#6@z1#e;C5x$ZX>TzX_9Ec+6) zt(?z?VTJGMk`D2~?4DUvE$}Q0aDV4Hl$c%muxmD9c%b2z-(s^FFA%t-!8oHRLNH>| zF1!YF+Of%(ULkoJ(nhW_s4utrO`YvYUt+`!gzh)xgwE4R>mIM0(H#G*i@4i0oVFBs z&qp)5IpeR$m0(6Us|aDR*+mB8Bc-u}ir)NT*>vyhvy}?cwwl(VtxFUcS{mNLRhL_c zGWVK}TkF_?PkwDrEPAp1u5U{6{w?IW6v~xf0#VOn(Jeu3?doJ*+qRg96<4b*)bBUb zPwO#6i%^AlZuR5mfF|w95t;)vkJ`Mr_(}v3}z~SH61x$TWQ$O$--uI$o`wcnDe6ove`A|$? zH9EXZ9I4lod)lg$@rFX=K^2lJpgH{Sg?Ow_cr3xCCZUiKqv}I=5H)WgUf6-S379{b88tjeRQyOA z5=nBV@L*aHYIZgrE)01{BW3v^rlo}G|JK?=Sr&@PM zn=VZkgTivRmom(LCIndzIi!_~Sq65x>aZPrf-}_}fCSb5zW0h7e_V`*adE+49S9HI zi^&VDee)UHuEDvBK`|?#de`TyWa$Vo=h89C$qB zzMlnnj?p2%;PN0z+Qs=P59wC(!;LDwmC(;+iYak0LgafMb?MMD{4=T*NwvISmDkH2 zMI95a*?ZwHU~{o|S>mZqrauZSJkErCzh5%bN4DtP~efTrTdo)HdRDqNE_4^^2@9yPFIM+Zv@Cz1-!%68@;b)SuY2>o;3 zr&z`q&^nc-)8?1awHvxB6?8O~t8V}z{Jud5*fT?v8yUcPb-&A`2KZ9q zhMuyq{@VqAl{~WOfdZq&)t2%GA0zX)vH2uyo%Z_4t;?XVjU#%X7EN__FGtdbENf)7 zXV1*_6OoGDVw6;l!3n6~W@@P0)lbnlp}s_KAtRgqgQ+DaHHjjLb%T^8C6%jzKzWxu z_90S&1`8ybMwj<60+aJ%LHaK+kJkeq1Ss5~rd=TvkQIoBO{d0aNd}B44MaK5$GKC6 z+#9J$ZL{8a4hLJFxx)?w2R_@``c>}ln~WuC=+de^YKgee3CLXK@a?TgB?73?MdIk` zFsVrhrSHZQ3DFV5{c-;5F>M+VfI#ENmC?!LA(V`mG!Prkab0tyssyo!b&q? z4}2Z-@iUjj{e}Nr9`vp+X4AmBxYf>Qf`QuI%oL3dd>@xXv4}8~11wbvOpH-Nn!JZt zs1+%$gxM}kN9x_>j8)dazlP(xu?LLcj@pn%_@sl^itTBI%IAOmz!nme114XH&WFgG zH2U(Wg+GKN=_2TdRrqq+bm$!r^z%3w#2z#~Y*_M&7YV~MF^Eu98uTqFU-R+lmoa{j zBOt+fJChfvuo)(xn&e7h$s>6{{e3uFnI#+qZ!++0`Vx{#C^aV<4_*;vSxws(9y5k&3}YRi|SX+~29LT7o23 zREdpsVFlovu|4!*la+{w&tpg=kpOx)H+;+d_S@y$Ej~7^(+hH3%`jvFl>qd)9lM$@ zM(}3-8gIGD$Hl(3vBRK8TbGTs^teG)_Y{&8LC$nqn_C7m{LCtg2#j_3U4EK9`bitZ zuaR{`G(1}Q5G{CLiHLhG#)D2BSV)OO<)5#Dbty-{^5@2~L$<{c5_DrL(X*`o55zow zfk_0ch}VG}=&4;bH+pE*Q!o?&-n7E_53ztr#|)I#%%w->1RVbju=7h4RqE>|t1jD- zj7G#}Q##3arbcpbzkUL66bi}_Q`Mx;QYulT{VDG*Q7!;o*pAO=s7@DM_Gg}*}hiCm%XHbJP)P=l=3o$yaN4dZLWItsa>nT2Ch3uW-h@KoV zS?CK_9ILfZoeWf(74@Ti)4tc)UfVpedJ?cgt)B-7q^YT@p%FSVGE&}9*Q%?kb3$#K z6^E($Zyfx5#ZMRgmP@e*P#miH$GTUoy9-XaGc2Cf5a2Cn2}B+4J`(6rTu16Wkul?O zb|GPS1qZztui-;SFII-9ejK6##CTi0@qw=UXA&EZwRtgZ!1gOZy4l7Vi%={+G5v(1@zS*k#*=HwxFvJj! zz!*)zcwc;6V(&!Fv~=j=(>NHotkCXWgP-WUu6S|1mZ5idUOBPt8fNiXEKg3Gi}Cll ze|_;cH~`N>)RbE%VA9Pmn*D-%u#*I~^E!{Jde@m`XqHxQ3l~0fy3|}u_PJcwOwx~# zW$n8>HpWfo0-Qu6GswNH3J3TERU_(2T`cJMO2Sx@>{-0tp{Fsmq*T|$1J+Y?&pUL+ z0vk*-HAFk}nyOtB@Bg?)&9HVwWcqJK^)q--N1+yNzSXGcTM}<{`42wHA&Mc2g}26a zl-K3M;F%SclvPOi`3b+%eV5}Sln@?@3GM4FIgr1%edwOoPz6m5o%M=d;eUj$`qdhWY# zS*B`{yF1tFmoNNKjK$PnoNub>D7cGbK_7}I8qb=5q)*5h!x|$XY}juQiyz|tHD=Xm ziqf7Q7licPvni5OLTG;?2huWWK(8z1=!j@WhPt~Pg?@8?&9e>9#t4C9StNHkXdS8V zoP5$!$BV<$cN0nN`Wo@k`{I{{b|6hs_dwc!Twi3)wG)UmgH>X+?b1;O$2+ol;pzB; zwNSj=_}qkA>$)dz^MPdj+MZ2ZUi}v733!Aw<=WO92psCn;QQ3)hmU8GU2ebs3f5TQ z;ecT~>O75wem3QHrw8~ck0q}yV%`!SW3}sd`-2^1tg*Z$&uNr@SRn9a9PDC+=?UzF zj5jacOsuNY01tTNK!sT3zd;%BSupV`u%RlH#w$3+QzO+K)XDR)X>$VK>c6dMoV;%9 zIJ5)0TIMz9lItH-QXoMk`(jJV%YR5~f#(yPrxIEeek5+9G#)>rfC6tLjW@olBoumq zk(o*6ID0_I;mySrJ6?rLo_gZ`hKv*T7gqdX!^{2CCRG;`QQRH)zy!FU0AJi(dKIdm zL#@cUb>J%aumcOI*hx>8$SIJZJI}|4?LL+Oo5=@1Pjc#^;ai(G5rN7Sp91-N5`olT zKc%KwR%Bo_BEW0_Jv#h|g~+_j&{&Do|GaedYHTJdMC0wBuO-l7{3o+sRs0KuSIpDq zhuXI-Jju(ZWR=zft$k=s#!_EP{g>Zz;VRp)NxoHw)RRPv19K&b+pTAVqgx*t4HM(X zsJO9GMyZJ1BDqjwIkg-f6nCXk%xL6E^L?mzt$2AD>$~>)5#V70unPD$W8eXnM1i-e zhA*2P-m3FXlU1D+j|ASHT{_=+{zjB~tEqnPAD|8OlujP{@?GTUS%6tCv?9i5)r)Lg z@muEGb8FUU_kVPd*-w#o zBmZ+QJiatNW*M{sJ?LQ<1Tp$zbmprNmdVa}WVB@z-zUw|=-|Es@ou9UU z4@TaI(*CP%=rGctE>_5k>f-hp0?MP6Zcs+Iiv?l!iacY zsc3uIulS&9FTe9`U048;eeHThGaRGV=nxc$nJ6)8A9k6p>(SVT!Buog5LOaM{g3T) zQFv#QTl6ebWFSTpr*3634Jx=B-8Nbn{l5C$G`t04;;6=2-jRM!d#j z>&|oeNc_0vL!e?`;u-L&26A6LYh#;SZv3uBsgA07}r=#6Sag9`T;Wvl3Nl; z4N~-!To$&c+qK!Nu^B)Yx)BxaQhwZv@VqD_=(%?;gpyZ>H95eKAxjHOC-~8~CE`J` z<{}HumlmJ7V5eAy!15zD*sao2=8?i2V3U za7LpOkj6b7wa~R3SkTnWW_W-+a8`2w_30-vJ#OG? zUq^_20s;Y%ORg!;Q}0<^Uxn8-1<1thh#djNRi2vZqA(lQGR>!$JZFD$Hk~qV{oa*mKvTGbjn05k%EC zmd_WUP}7!D%(_8WH&yC@bNnzOdg}5S6dFoJJ0!1gl0HBYVLk3R9EGRz?OaC3j;Exo zSqLd_2^(52zHT*q2PYxzQ;cNskYmL#lE(o*{jWf<8GZnws&N!`jvS1)51C2_26iA; zGP*D$ky@Qk^cGSiJP4?od-7eXz1Igmv_+C&s1@zT_wEYhn-7!za;cQbcu7+b@{Qw3s#<_^<-o; z%3ul;v5fi{P(<%cuIYP!dwGRQ(9IRC{a{n>nyt{8@C$$#AeFt#5HH!Kt^<xV5&L*1Hjfbvk9=^+tk6- zV?u1m;{~N2In7EvT=(~LOCcuX8M{1mpjk|Pr zb#oUR%3687seJjCtuuf$UZj&~I;2``rz8v-gR+gEBs<`k>h2FgC!$Lj)*oNQCU#I{ z7Q5q3)8V1L&_iAJ>cPcc4onT>ad=?110@^zt1Hw?2kby7&{hxF=QK(a4^yqX6s9{r zzrGZSE;^cnD}d0%WW+)q6E3(X&qzh))#jozLPmJ+31p^cLIYj#GiKVZFhb~66Wglr zmQDrZdu^Dcp^zFzWW8%%aAF2RNgMhb7#Q`c=bNQpBQ3M+@u4H(@bLUp>JPwtwWtu> znSVXZ7I90k#-g+Y$m7juH%()#l>H}~?e*(&K#hvG6AGbN;#zQB=4%aCTuzA#@Va!A zf@`ym0xwQ{J-#ozCd|Soo2(V#xsqphYkscpnJO?Ca~#_NL*hBMhu>p6qxY7%3hj(*QBI(3vr9 zhjWin_AQWfAD$#EZ%9gIVS3?zx5=;|C`|G}wF4n1+XFJm{O847t;v+ZWPNL}N@l>R zdj4^H;dPUTHxC!>DgMXj?5oSZyP$pBiA;rIC%K}cwm~3EM=LT8lffEV*)yyB?+cev zX10Y>CFSweAtSEV1I+E$FaJ_{xX}3x30(!0(JbNEuV2+PG_~^ToAJo(>>S-aV1AK= zk5Ddm>>0fl78)26=b4dktA}9+<%-E0P0TywRu&SefudB{Ux-p*`0W_;<>htjyX%xd z*Syv6T!2T_55}6#b}efn+%pV7J9>1%DH|Hjm5?}SrqzMQ6jpw#jDIeB{2Mi2A^T2j zsoQUG?6x}@nn0q9n~Dkz#$qg^D{U*Q4+cXxG{rYOP~Ed6O3Wk%2Bip3%$+qDO(3qV zk=$FB26qun`hqn9t736OE!jL41yM{jXP5kYm3NMbD3>lN2uawBz93IusN_{}&<(@C zh$Q9hyG{g1XaJMi2a7&l2rQi5F7oM&kSW|Ci^J?ltex?z zlk{SvP)9TH-6Z`JN&&$F&3jX|KZ8+?>syVny}K-CeCo?YU!5$r=vEyd%3vc=g4nCg z=m8aqV9@%m79CLjYZ^0{@VLCd0e_TfE2f}*6&DNBRmM_SBmw>b{Okv`f!&a=2TRu5 zj;pQJ8Q?^Z_>1z#{ks?YxAA)?eOu`3v6A&rRihcNn@_I#?}Qe(xuaK?pX}*AX3>7& z6Rkpx|NV^(AY;_7QOsulAkp|gY}V4~>-+(*|MyP))>~Ii6O+E-*=#?Of8AR(7dKB{ zSsST^a%OK=2!i9+D_D62`JZ!>&=%SRuJI%Z*fA1^^8y+6mYGW6DL4ipl(Zu3oQ%;eO1@(QuIso?JTt%j?OjhcW| zH1N_6!^c&SqrZ|#V2QcDa+QUCq2XYsc1dcPIw*FJ@}Cq*a4U;f-`YV!f1<-$d=-|S^2QH^z!;e69ki|td{ zBt@G+OtI($^DpqfwE*-HbYf%WY~h76tE>DWC*TV4qL6AB2HO6p$7Zt^9nD7c4>grs zf2g`an5OC{`!G1FfbO8t324SpXd?O^P3U9$6=30suZj>n=%;)>N5K16%e_vHR=tflOmM#VPzSAf?)hPK2gP z!aRz+zxeVsfpx@a8ZcNLwFDs9TW~ui3e?igP-F!YxNEN>R1+ZFFSsy7Gu8l#oMAgv z^;mnvvwYz~ijMF^#oYF$bL;Cbq7JZIm^f-r%^WbB5SQzpyAb?`mIE1IM<+hgCk79& zv4B`Fd^|$K3u5&5OURPOLO>^6;JDt}&JFS0`r+p3u@0}HJ(H8)PNoI{>@Nx&26B{S zZ);>b+lJ2}!TbsJ9i^+CvF&YMc#K!FTU z66R}lXms~}k)f@vlUOM}Ah)1LE#L9z+;)Lim;^|d-Ob6onAQIkeAKBGW5`Ug0pS7a zny-3<*N-#%dXD!LEdcH>&*jk!qq8CX_QZWbgdYa*+P!X)*peNA3sWzobw#kL+q`Xv zmITxySR2W|afE^FndN#O{moIs3)2F~9=2@ypfEh{hnC}w-2Jfuh2?Hn6o?NHIz&kT zRUk@si9aN2^DuDAdMi(YRH8C3EVeni7GPC^czi#f8YoYINdh%Dhy6?4uV}!@ia9mnV@${70kAqn5}a##SIwyd z0tc-J4?OMM{Zc=f`m0(KHTbOgw;z@}4TH%n(qVK~rOT+~WnvoG1Sjg7b;aFI@f(?3+p+q;t#F#^my!5zbezz9zK;q$hX@EL9 zjN-Ry{37%?9E?0glI8zUbO}WYLI(|?Q}loAiJ(M7!uz`A8HCbx+Vp2Hex2jJQPT^Q zhi*wkv5(mHjR?0M2mKYlUAna?RpUJ);AORte}iS-i_IuRvkSM1#dCClpWre7f;JP(C*gp2Evcz zi|GzDc|sj0%r7_kS4SBhM2kTQ*~DRVhs@x7CYjZGn0lRn0(1w8N=di!i6guISq;7H z>`)*f0EkT3MHsImuU0k{Btr%D1)gj<88TzEesW_VOpq+^sN*=_>v}gIOhuTEw>QJn zkYU|>*2)Bc}UA8TPJ*T zyyau?P-F^Mrjd4@V9*nR%_qU(E6%>B=b@31kO#X!h5%1y$v~A03!myl&^q@4ebr9W zrUW)H>tZNyqk-$x;S+#UhaZ5nur4Mv?J3_nRpojF&6ywY&4*67W%{%5v71^_$2~Yc z1@e7otz|Wh-{8pC=dw=)m>K&qqWTtAUpLvAz!z=N>NTZ2UXBY)xSd;n~G4$*OO{jt1D+dXJyw7?u-L_dXpUV!{R zP#b8;o1gDAp~$Q6(sdDi#%vEnGDc6DOO&mBG72m3rx>TDN^%G)OKol-qr_H1QBhb* zmpgR7*?|+YG12hm6YWOvOhRsJXASyL!(N5~&I$&)S@KK&_J2B<}LN;f^AD?JPV&e2#k0XDf=9@9THV2G3l0Bmt+>$c*Dd!Ui zG7^}N;(Vo?Y!l7uH+Ef}Ixa|{LdnX37;3r9%z0f^@`kn{#5W@Son z`MG{gPE!zoVAbi#um*cFKxhR8mLc~3=I#~b0z3e_5DRh7L>>n<3o*^F{9Fb)(O|JW3e1i;> z*q-ltSsgmBp9Szo8vQVybuPog5OKj&Ugpi!rhuK}+UP#p;&^fSrNIbT7pFAiw&to& z_pVi#z(5wrasn$*UdX&<=ldPhoxz8@*-JxL>oI^t4T@|iZSwLJuqO{V>3O@DKwuD( z$x24XN~X^WgI*pC8v*wgiH9%P(fD@RkRR&{$d)0<&`uy4z>VYbfF#X6-c5`y;IDYG z!a!~mPZF<3e#_Jc_hN(=C>@O;Ksox9$NXJ6x<6$kMZ^ysv5>VfuJf=2JhQb0XPXWL zgz&byT@7b?oL{QvLU_rupv#NSy?spUOgMO$@RtqK;(_x+Htc2%m!j$}^h>tA79045 zkGGd_tYQ?UzbQ&*ECzSIMn_eS?v6aS1ZJAJJgQ{p6F=Y1I}=~oo33oN#`JWyKgR-v*xY*XE2SLz3yWN> ztPn=p412O}c4%_wL$sINE4%Kd+D^2W!e=5f@x&i8Mv_3bLZ@xlqvk?4!^^pMR|eok zBt^{?9#G>X+iPn$$}osS_pRHq@F!0u0tv9aYVK)@=kFYIBnQiC%s@>jRQ+ytRM&6c z)@!rxVSoIHy-Ke31=h-kCzjFISP^HaN$d&)<139v5GEw3d1Ih#!C12K+hXcFz80&+ z49o*rD`Q@*h9I1r&eiKQxgr5eVtd}wVm+VM+KmW`bSVP`K#@Q1J@mX}{4M7(O7#EL=T9CG_~5@-PB+4>B73 zL_5^}JqSt9J#H6`hE$C3KR%ixOpQLebmIV7;5-g&P>p@-o5v3B)f;H;-*tg@ndNDJz8e7kn za}IW=4@XIZrngp}ZS*(@j29}T_GIh(i34qK1I;fe5hEX+?;a zdMtVn_o^xKj z4h{D?fxwV)D+G)txpqF7c(qj&+vGn=3Md;=0IU*nav|`t=!5dx$s@v~dItS4TW};0 zBOPJwQK01DqNsCQbc0$<tbcRPwFQTNW@(5}%_q_AmA|^m)a`CN8u-+`cg=z~_W8%aEU=!tLkAQ>N{UdMvQ^cyiCK za!zfIPBg+0NDZ*)+gJEmVz2GDjVL}5(T_~5tmyv|+o>tHKKIgtV)h1aGIWatU{BKj zD;bELx@Aef8@Tqu=XHL{H>-*k`3P$3~l z%XzxUdpX!FubghHxROcCoQ#L=fpI{gtvGqjsMa=c)FOjZ?37~&`3gH|W$3PmS6;sY ze@&rQRuOjlZAg3GUp5JnK``9_!>>fYs|Vl`MNAxo()%Mq?M#T+_<83c!<8Kj^kNX7vqKL{-LM`)B^Kwz%4 zy1KZnErXp@7*b7a8W~2lu)_R4m*X4_dLRdLKOXPJP`&`5riHZVrEyq~)E)de36Y^?{>Qg5K z8Z8eG-do7w>PH8W5lO=v?B$!enYXPswCG36$`(FMtnzCogfPSeQc^crDlxJ=era?NB9BdOG*x6P1Y|s(|QFwuNPc3(DJmnwUne=z3xdX}(1y(er2!O}9lLbhd_Zgh3tYa?#Fgv<-foCKow9 zHqTldPuNo%jXKK`_3}lq!T5HZO`!ws{pDGu@TswsZs+R4!EOzqdg{;nhh@*^sIo8Q z9T$7augq-4m8>y|;;cY^Zj!0NR2@Be?3+#ETYfA*-Zxx^PZ=JbUOzJWR5L^WUY>FyH6Xry!z#N zWMyytr(S#dbUzBOt<4;*UNhqLg{vu=P9l0Z=QQbX5NFCN#e$$bp$+?JLCAca6Sf7a zP9jp>kE7ULl8_V0&UbIj4N`?IdimdJ4-A)U<47|=3k7+d36Kf@?%$z>h;*-ipjM7Q z=?!)j6rd)`_DVo!*y&8!>>U)khxXxAlxEy06>v?ssIDq3_F3_Nq)Dy+!j2f(hM*^) z;*Yy?c(}RJA?*6i4V0?*!B;d`Zi$_)foaFIN~HeN9ga@VHC~@a+Zpyt&7@j8Lp)tW z@3_k{;aPe(p6~Bi=wNqD*~P_HsJCq?wc3$PSvtN!i<%>gXeB+MDc>0RS9~Vl#*;pc z2U=1;0rUG=xdKv%pBv5N*=m^Y``_n!$u1)pypzY{N9`OHl3Wz?D#K;MKkjA_2pl1W zi7xu1{DKP$Jw0sNnP*2HbTs}g*YrmQd`>$4PW5$Fi5PzCZU%z0X%hljzn8$Y0qs%M zeplFsZSU2TZ1~k~+H)?*&MH{ft=2e`-ea|AHtIB2-|gaR^V;rp6-hBh-X z=}hQCMmW8E-sO2e*+|rnC+h=eRUYkoEDkC_XEU@Iv)h7=zs-W5?)=|FrVu#K<@TU4 zTU8V#-fZCgMIGiKfn8>M+i}0~oS*=Qs`F$R{LuEq@9ClG%3Hp&z2rgwo;d*KJ{;EWnKNA5IQ@{uJNB@+p)BxGN-~v zVeemo+Jf4Oi(od_@_bk(%BcEDC~0)oIhSk1*){Ro&^z&QaIF7*cXJ(=;IH{Lxj&gO zTPOEC4Ii5eEWZ21c<_N~Id6^GotGc$oQC$ke_vO_8hjs2AB7ma50|?c!p=^Zhy)e? z3aZ@SRo_W4n}6nb$I5=$*j19-){Uc%K67ckmRQN1`$@Y+c7X*qJ-{ z5d>TxqPX0^S-2@+JVIpWue)rx`OA&jr|K_GJ09PS9h}jfHhPSiji1*xv+l&47mGg5WlQ=r8ql5yFxhlfI^s?8)|M4dEZc~$!o@wY&Ve7kB$6dF$$nAQjD{Y=$ zGK`p?Y;Y^NcPxg!>fmx4gnE?3Flq0T(oSp|`oqCBjPKUeZrfXrSKrEXy{}GD5UzU_ z>r%L0W=*`yfcScC03Xz=B;a%AaVt1E`GecgHXyx)z4ClG@O;0B^<>7`9X31^?e;IjIMVk%jeZ|(QR+BR!&`o*E3LQ(=B0lcj_==p z0u6H})s-`W>aFQYPmFoG7=b$|gK z&~Y1++9Kys<`Yr^!mkk3m^gje@KP{wKR!W?>*1Tr<(7=NDgz!N2u|MN%L)bTKa7YA zpnem-&?CEW8r=_gaXnJ6)o{!KJ-KMb@8c@vpYvwZ(UdW4>B zWcSWTJubk{U)1obk6hrC@7sl*@U@IEQvTrPJBiD=HZeE2AuV=Kb{HIS7xyZ2LxJpaK$tPS;)38C9NN2%?&4KiGo9B zMpoh-nge&!&#YE?~m$gG+ zJG5H6K^e%tIPy2U$fYWwhY$;3`<~Vw+yNUXT%8GS9_KPKp1neCD-;}DC)vBYQHYS$ zBW!&##J2jVDC93dLo0Prkbet27s=#pIM%|I4f(w4ONzb!ANq{1sTebSn)str~+8-HvjHjd=c z^L)#XxF{lhtlMONtTADWNcRbMHE7;!+xqAx`vf6XnVeb6?UzDJou2Yal3a-&EjFrT zvSu{~lzC>%HiWmgW1qna0IX&s2@VKzYPYaLk@NM)0(>x?S{y}1_3E;}SKthK!{)ay zoa31>R}saK(<3H~X9rljH){I&i{w;0pgHrN-OpHGt=`Xgfmf5uaO0uG0a&y%5(=l{up#CzJJLn9F|kX#sbiy%uVXOsW*H zS30%H1okkGN0%ZUsw>I!qE35qi|onoM)5`NI|Z-4f8Dto<>vGpNLoO*buKAQr{kGA z>D?4CSXh*LMSPt}_GD}Cjd19c-UA!<{Xc9y1z1(f^GHjIbVw-O-62S)gf!A1-JODf zbazQNcq!>pE)CM%B@LJE|H1e4`QHDx-^V@Y2KXJ`0tPeu!xg=;FUkQqOM zEILr9=^irJ{MpDO)69fI@fir)@g9V5HUmNgq>4l9@(zPbEHX7M>!chkj>bol6$M!6)3Mr*$Xuf?-wjLhpE#ygL3vb!G} z8V^hhocImii5MZZ!R=z5_CduOXE4R#zr9-K1Y>1fQmDzOZEN=t+LxTMgUl5$N$$PF zW;Ya;=8-9n$}cgK)d@%-Zj&{ql>kc>T2SeVwIRx@;d9wB(|v_|e{mvsceLe|rmOf3 zAWKL_K&3`0{+Q$5I)`QQ zg(};pGDCEPF-(f-=a$@K;G7)`S4S^YV6X^2l(*#1yRKfD;`U}p)_=*M9I2L=^c%Gbg5w%owRYjUaS9a^*EXnSL8 zQ$#?#;l&RpwtANyEJ~CWmUfRR#mV-*Yfbg$f?(`fg2Bt0Vomo!^VYdZ=9`7gF0P46 zcLg@FBeq2*HA{=`Ef$W{6yDgIK8Nee$<6aBBXN8e`lRkgT-g=KF|cd&O1syMlh}F{ zS1S_oEuR;-B^wnpI^H<$%NXN4xg(DDBW{*P(TqDPcI0)+NSkcy?O*!I)+Na(54qQ3sGU(NU9Y>sKrQ z3zPyDkGq^GKZ^L?5={O9I(o~&f#Llo%Zw`&VrdpBiWKyqSW*krWy@pM)lXqqAoVan zh9HF?J#tv7mjGgQ?(+-8d{6Q*co3n#rXe$}fm5yXbL+S#jf0!=M*Mt{>8K7D2oqSR zt3T(L`kvBdwx8A-hJT&P8dBYMuw>>z2djrU!4|<*zcED9GB{$%&1WQ~O@-&==1dCe zw*BP6C4)k_?l?wjj^Cw&2hPs}-Da%%crHR5@Bu``H>Ql_ zIA#P8-W%^}3~?>iI8r@moHt7~1f?wWr9@vxj=_~{O{@U5^fl4s#o=apKzY29@GFy; znSMLl(*VOzIz8K8o|Eoh2kXE2(vVBn(}d*V@8~v;JI*lDM@flgMnThvX**8? z`_E?31n-aMJ?}Ofli4W;<8kAvEGM`(vWnl5`@B(vbPiY?D zZ_Lpbh4sno1*~Slvu@S9B?Oz#z)RLmg?<#9;SWl;EECgnoHTC|>n(Zvx}qR|x%pke znV#Adv|3^_Q!Tl!PXS%$HRCTdYgM{7V1T@0Wotx+O2}>0!mO z_*P3!4>dGD()g}gX@R9aP6IO}=`}$CIq?&8hJ^wcNj{GkfZ;QxG1&tUH^4~6b+l~C zaVaWz4yIMc!TH6UEq6-epv}F<`J}m|CNvRnSYUbqsi3aWk@##r ze8tfj8957d2~7{P{oc3g$9mGaL>8=M^IoMaDiL&gGj$@A;lXTfvX8JS>OSNCpX_y~_gZE)-?}iRR`7Z700dYzW%qB){AOROAP(LbP@7sh*{NcN_>V zj7HX{R8{lI_hG`}x%k{1uFl~zQO4eZqV7xOTL0KCa1nK|@)J#IBxqib7w$0_^HLHz z9!%*-5(z}+KO_&=2v7Mh#cx5Ir7W`eT5Tr~k^Fe<*Kdhl;HdY8h(KF>3`$tY&Edlz zPM0NVjI5<9wBE|fuL&|@XXT@PP_Vnd@A&weW1)JMIleu%$hAznT}?CwbmxD!=o=QR znQFFepiILSb`uEjJF&tR6YyQEgPT21uUkKP>_{7gH-Z#Dpc>#g7<|kUd?4nm$xbHWMj7 zFv|4JEv^stJmXLy)@`jgpWo2e6>q7DEQG$t=xOBFM#oQ0?duKSgk82`D0XM+{c8Y+ z6_0}6LUqx{v`;p>7&dM2@P-WHR1U1N@z|Yp+aY;?l^1#3T;UZzGp}_xKk#h@MD!+( zIOQwsBbI~U6g14)dseX6$zTgS365V)0V4D{Ra2m(;OoDA17YgX$E8AJy;rZw>KTp4 zen^X2R_y6{SV@%2^w4Yy017hq++6IAQec^AuiYn5Dopr%J)_tftd&5KBKC++dD?mM zdt&y&KopWekBI6s+uS!@HV@$KY3c2iwys}K_|hbN>IY6d#6t`7F~uqQ&k=cy9ulBh z@|@@K0RQ=%0|5FMn8=FxzE+=2vluP4C$%bu&0oK*h!Qhz8S%$Hj*~^O(ToUUq+wMM zmH+AyHuS+VV#1U2;E3^gH0!rlh%l);A)U<%Q5(RoF>h!Si2hSL#C43r5zgz6KHipL%1fN|hf0vN;P|i?Z&(O*RU){&oVJdsdUP9lfeJbQYCWJ9 zLKS~f?mfpU!bw~2;}VVHhlE6bHu8JfOu<|FD~-}Vr8m!WUOAk4o7XmnSP1$_of0E^ z^BTX*es9<=^Y)SKb9?jf@NmF!Jygi+i0E&svia5nePKBpvBFt-t#tk_gU@Z!V;@$5 zH%`5Ac*{*;jbDCGF6B`K+yyw9!-I1b9699l#;p?%v6Ku2+7eIiD|h)jens`Toe}u? zm_EkU%D#%W8K_Ov=sxWcS7yQHdTJ=`r73lFZqlt!llTS!VxB9bnHyf`3yC`r(ZT7u zY&>LBxs8qUg}zFIwSX>UBXpSa)t1X z$bYf`{|y8P_+)FeemRiv^V!Kfj|o?)Nxt=K?0-QKBU*8{|5~Hez~tBh0HD#Dv{=M; zAm>c+*^@EL&U5GYk8EK01u;E0SdyRgtY$5FNxA*V>gx7d6Di-|gFV|@7`VUnU)-#z zVKQWZO>iV+^-DM^b&WhiJ4p9y6B~?Y;YNsd&KiX*#7go!=aN<%lj!QOJ;)+w%hKjfTHdulxfYsZ<^ZO0GFu z7&^7`Z#-N}jt&H>n8{JacA-`3KXaoz@Xf!Q``vj!TfaFURZx19JMYh)o>;7yI){ckF&Ai3g znd)fEbX!?2;iVNT#d_u{zT*mWi`&RF$puONKAQb}V<2_t!(&Vb6`eaa@RP^@ZHKJ@ z?eoECH-)cZ$!u=-2!d@HI*qmqRUX%9+KXtbj`-}wCwZ-zH;#)NOYLr7{bZPy=UwJI zE9P8uRr@gUX+dqa!)r>r#>c^(2IMn@(+%4i1n7HU(clvvwN@~*#a=ecRGVMurviKj zBRav4nAq_c;i>NEeiz- z@0y=xEGp@t9%%6U^Hn@c1|s4E0s=fCY?;fq=Zlf3FikAvMC3WzYLptAJj+Orz0>n2zBplRox}Wg)h_JZmII(2j?^0>F&kxj%1d9ffx7fS}(-X5@!#f}4 zMoxlUKW_1d2sCAM=nU!cMfk~NvAyh3(=SKtP{odW4LZc=v^6>%Dao$mVpGRT|F_ zkI$Ou!2R4q^5hJXUg48|brsmJ_l)>pWKa6uF6yP#faG}MBWtPqVXk*=m$=$(65cys z>Nf%j@z|U#twXW!p|d!`Xu?=5%;6>%-3jHMJ$|cmWcb6J{9{bA@Kbq9^dQ-L_z89X zh&J~hRuska@=dlxMfftol!NVXpw(8xN~QE}Ev3Ju>#vmr6x<+A0Se;{@~Bq4^-3w? zcZd{}F%mKFdYe`=^CxqExQFzl@i-hVRGE(#kIJqmdz|1u$1KbY=$^L6sI7`-o(`zN ziA{e;g@F%e(x28-Ab8Hxay<|u+HG1}&o}Vdg*kMaQT%sM{YD=!T4Ad#&T5q^X(Gw@p4ouh|d>Ia-}= zbU=9XX1uz#)?V+xnnZ?|od2xDXnv<*G2BO=O$G>Vptv0HmR1_D z^-yXIH~yDiXSW=HyOOq=m-tpm2sv7~x}ZGWl#3|0rv5SE=@TQKNhwkBTC@0g{tHm# z@yv|cbd&ds1rKQB&ySXxsjzvVEwDov?Gp?@c*1xwCsJw0>M&qG3e58{)#{c=IBYitTxLyBo06B)2%5N?ew2FhYK}V$;<kk-_NSj?) z$6Y`XYScH^lXqc(yJ|qPIb3mzfWTSW{$+pDmi0R-^{ys(-N;8=4$Xarq25{vF&UoyL!JsL7rPYbYZR!Xy4XEp7aJ#l`lt(Z2cCV(tZ2FnReNR;YK zJ=5`sDKxAd>XFpDigq=t=fothDj`bR)9jwD4Wjl^K#{rsG`IbgP$sa)&`ga5LK=7} zS@)V8@0Cu`|JOW*x5BP9#smVY$WAG$enM&0PIO^8{i{c$!sblyM-*BMl=mRlRc6X( zc$1S8Y2P=(YMq|D~Iz0UNU7w_|P>P!b3#U|K9Sp)63 zQROhw>Tj}0DQHjkJ%Xo}onRHw!SyGw4HGd$NDexGCp!9v#?zAFka3opO@RZQF!F|; z-#StoUjN06vt6!lOTXEQtWqF?t;sO303 zNaJ{gHtd-Dc^JZ~fa1nC6O}!C_)>(Ak|%ZAYHWqiH|+-BpBJEAurJBFe|}7;UdrLQ zH0d3FE_4WG*cIOA-V6}z*LarKN>6Nu`-^gKuy?0@a4Q5YisoA|Vt3orM_?k1q7e?^ z{oB;i-gI}h13=M^zVz~OYQch74xlbCto8C>Ud+uWLgsIQglzo2 zN9iHrPosrhmiZRi#elM+EI5%}%b*BHSE4O`HOZiXa2zn+3QOoSu|9g%sopL%+xrUd zr2Ie=B^rrdo)p4}k+Ihb77lE6t29fL$E%X~hihxxeJA$#p6Zf7+}>)Rw7t^gYx5oX z?{fX*5gk{Do@EwBc%@?e($ij&Yw7Z;}R zQ&jSjT1-5J1h%$EhsimuED6jeS&jI*&GG8RiPZERU7<%uE4#RqF$_LK>Q87*=(Qk8nJa zgP8d5_piTK*aLEWXBQ>j}AP-U~dz@@}!~K9zE?J3r!ZV zLHoj3+OJ{uYQ3ge;&L54KlMTj6zqJ6W{LvNeI<+vZ-aW^v*axZnMH?Ywp;l|qz2Sy zXKljne8ni#ns(;0DE&k|9|fse9wD0mwZJ34SB#hc0V znZO8e$;0_q-bDvNu|bL$_}V}@pMOO9&pZ6Uhx1`&hTRs)obdQk0|f+)U?}M`A>9jc7*O= zW^1iG#UgUgKfssb^VBz)%I}qS>lGCie#*{<_T8~=2$qVaayUJme2)5 z?s00Xzr-?y%e>LnNO@J1Fva@wzN{ zad|lJeOsNbT}QP=L-18F1sOx8Dx=5}l^4{RfsN0PVUoB*nM0k&o0|~K^P zlr;-S+5R9H9=-=CDq;Wp7<^Lk$CiNWRjE#i@k;uG52?!9o*^6lXCPtIyko)|z zZ;hUWyP+Wp;5GdHP+-%wv@eD>Dw*fY^gk%Wz z{SN$_KY;Xbi|;j9p4l1s5WJGpl##g*o z`ub#F7VP-2F{ykV_|JZzyVM=I`Q^UaGw_q3v2$FIS?W&{4QBZwOejdTU^2>My>W) zuKtdUsFehZB9fv1Tv`I5KVZ*ncRG%(pjUKth8!LlC>h7=eRT}Ee7p&E^S&kh8Uwi3 z#S5D`vwR$G}c)x)5!&(O6NlNTQ-=|W_ z%!M~$?LlI7BRx;BP{7DPSp^YWEwj-=liQsAqD^J?m((0BT{82E7hy1z-R=TgePW@H zN!c?B^Fj{W=$4+(b$(ez>hkS5-hso%sE!W~BW2Kej5g-7FYoGKHQQE0m!=AE(y;5!EmiX4}=a87A#6gG(8W+4p}R3(e=T{HbhcChG?doTXwi` z=v(=A`s1JBH$9IjAih{aa69)n=m0Xz-Y>24-}jFu$%d|?;-Q1r>$)A*M|rTKLl4D_ zRR-MOz?V{?@GEXA-b4?4Lza=0(-LJb zXZ0dpI7c=?M4*pRlmQHs7u^kBsGe6IJCe`TB@FJxXIyN^cCEW|-9cc(ur54@U1gck z#Je(^pGYFQ-Y1)91d?_+t;FioMNnFPC7Us?Jv^8Af|*&9M*sB4^zR~5tcl3iIdT6oFx4>SHE&8PYsU6o$z72JV@VY)j<(A{$HnAH=pMLEY z2?%GXmUl!wq1Ke!@DY}j)6*~e{ZRexxRgUbqNLcZ_Th825c%p}hcB-6T9iNH5A=?< z%+OEDT0L4=ZF>J1N|!YQgqd$U;FpYr`^{cwE{ZvJ!*(=2^l^$c+ySfp{wvJV&GfI> zaZ6y?ukmrOfW#KZ`1C=w&4XuZ?$eG&$ROr6c$33dZOvUghz2Z!t)F5D7hGPjQPTY^ zjVlVjn9BmE&F8{;bYZ2Qm|c()Ud&MOgrWg4?duf1PvF`k!$WmHD9>#FPi8_B5>K#1 zN~2V^zMYtAwH)AH=~hr03?xR?zYd3>+i(Stn{F`ViSUH4`PFxrbh=!=H zv5%n+Tn-PDTb<~E-4Wi=gH-a>c8?&64yvaYD(K_0Tu;Y2FjTM1lHq>E0*oJ(u?SQ< z)32BJF_BiASN{5dMbJ)s1iQ>=Gg5&Kr%O<}&31dibMw-s2j3>DWk)+dk!D- zq8lP6TY`6drmOximNl%7w$Jat>Xc1BJh*ZdOUSxEKAGLCdMeO?pi>7I``q7bWqq{7 z^OM2g*rmeJ3O}Nm3*cJr@N<-00!>ZaVbdaNFAxLpMRC{@peZKgb9L>s;J-d$gPqL; zJ9A*OU66PjNs3 zh=W`u8nkD;>`RVEg`u6}ks$9YFUKyhF-Ro(hSjteujMA%xQ*}fh%MBuhE{l`duJ+v zz|ROh3l38=Y%9@ZSm<2Di2TUNUc0g;;F^9&;V;Ck&8ZvWDdXASRX-L@WLWV+=Wja} zx@JMBEv1sK*7Jul+>M&hgGbcj0PBUrDAjHFPkoM3Z;Bg>3$^Q9cO^tQ3_*fUbSQw8 ziq^MYKhwP13ZCToylrN1t=sO%{$%B|KFZ>OOcW+U%y;2eqU4jFx>{*wh0O?I?XJGQ z>itXFA%)EuQ!R;Zw_-#7SjR<;jOzlS1)GKD4-D+@hA$6LpU>^7sN%^4SD~r^_-gBX z`~T}6@uf9$j-zt?_czA{d!~v}+mh&Yg13SVhQPXvTXF2K+nN*xXtjdsEtj-KC&fGrWlL5hDN zg_R$x6WZjB{KhMirp%2AH1qA$A3SxzbqM|>+(jNA@hu)h`|p@_PVAH7h&^E^ydx0eI#y!h0)^!e@JYD>Z+he z4;GJ-UD8AwZL0W?b3`-7l!^qnSpl5o4!s96de>!bgcVd+$e`$R{7ovC1qblsn;9Mv zUxU!mxpjn#1-$&X!>+f`x=cVKzd-r-HTuRD2sTDi-lH#aSGlDZ^*t_-TY2R&-+fm8 zG`~OX)s#KrtYTk#v1Y^=SIq97d=QTt1!WK7y3+UYkgdWX(XQ_SzNT-#r9!FkKISrk z=rtAoWt>Z@0#gf`jbFFK36W~FN0U{W@M^pj#q4_o3Um`&`;Q&nymI|L{$ zsDm>>c(_>=c z_*tI_10%Z0q-=d7)kd(2PzC+o_jL3ihe|b}6X_35_j6G|Ufq)(78e&kD%e4W*41?* z5nzFP-}eItoj$YK10$FZ$5%#Q`9znQ%c2$N6Q zU6!pV2a9}K`t&TX7V>nv!BVnXqS^L6q`zV13_I~!6>Bx*vTAF;o_KO}aFB!UUC9hg z4`UcAGbe85Gkg>r8POz5Dknz-{Zd2&IC9Ft09QqM=w4$Zz-`jaJU+GXHPO2v!_*r@ zp!_A2c|7B6Y*X{JB8 z{l}4~=;cn$KHxxoch!(!U-SzJ__T87@xhoEkyR~_x9(p@{uf8`BV7Vuxv^D{nV+9; z(zb;ZYeirFQ!o^8(f1exJiqMJd6Cw+NI^B^etO-8)>ttY2d zN&IdQvjRGK&XUZ4-)_5ZeCmjx{!;3V1{cPa2`wArtJxO>?|dEM>ZL!-^U^A0944)`h&t~$xENM79yN(}J|3rR-v{0giQPNJ{gJqnSedjDz#uq<- z?6*>`nylbRc@vMKuKir3?Y-2GYa5brlAGI|8JD%X=b6fD!~4|cBF2PdQxe~*e1WXV|)MB<(FxcK)lfg4&F2raK2EsP)Wr7SR%!qEuWOVORT`fE8U%BXag~PE zT%BSSu%lS>3{&ONuP0DYZH`?0gW2`+qycNWY&!LFE@cJiYpn zgZs>MnB7s9t43ge8~N`JcmZt6I-DbNeH&YJgf_zm_k%Xu4NhNrCkK>La*>P&XR91q zSd(K}2m72z6djFHD-nEXxxUj}D!t^f^Tm7dfMDt*n!3UZW;8>nBzeCyzmUy)y*XIu zUjqn>TqZr-*w_F_5B1roT-kppPtD4zjM)2PIW)2g&(bjM7yiTAu^qN+jy6h8c62>N zzAQE>GN_fRJT+eT? zVbiM9A1Eik$F(^(K&dr%nys>b|9f@Yk`2mEPi@T@hdOob zec9ST5UK!E(8ZY$#8C!|P%G>g#}jYzZ>FUkhm1U$E@}>mXvw>nVywUMrN2<36KS>6 z|KJM~8y||bZQ3`}r&lw4OxqOx#=;@2ASr76zJ5{?wSDkLBz zl(6FRSo&s8`>2Ujo)C<3Ve_n6!q%^>G z;{%Dfpa>0lTIeGvl>*x{Z2`!QzzrK=%cy@S7J=3pAucVqNZYUBwtd6T_{3`n4pW>R z*cZwjw;JjVsQ$g4e-2tD5d{B!2>;@BNu*cgKS0HhF&W=FI+ZyUx^dAR)rs^}H9LMv zv49oRd*{QEM5ByJ*Xu-M?jgZ(V58`G6-6&cUS)vCZA<(B%s4TSxhA8U^Mr`lbZNg- z%%&$gl(Otm)4s8MNF_(_pk{7Ly^N8f_Hyqpu(hd7PE8dC5xYyCo}T8^rn1>ePLkZe z5BnGE)Jrk9v>f}2F60R?`C9~h(_gd19abmYDRv8QaM+{ux{3~WKO7z^Y%vCT#>Fcr z1$<(Qw0|69MCl+O{Z!2VnY|SsHpzT`;i~UitkR36)dv_CO|xyENGQw|`tNF0>73qjxCDQ@ zaB!2qq2my%!lx{FI`Z+pBEdkN>aCfWFy&^NflO}1*IuHz;{IhWqsvETYpA4;VY?6? z;I85&SISqRl}%XDs@l^rE={mO>x2)NDJ_`Rj1;hPjl&j=f(A9-E1p&&k=DBI?{_Y( zBW`x9O%bZP112mV4SbVW#7L-CYw`;#%vS6i99zQ@ByYUDZVUG|PWMJn0ZkI&*K^=H zIyu#)u{%y{U5EDbzrH=)mK~K0{<%;5;O&bV;4$44LRfRJEOU)RH+Mi4-a2&FJ}cIZe%QaZy82oFHdIaX? z<|BY=kUKLo11y7``I0wXTs?S6{|KK40h6Ck`5+THI5+^@Eq+m(%$O6Q{QEm7gCb>d zS(RzHtR z3Yk(D4~aJzPt$wtfh0~Z0Bmvk)IU|rVV9!QRAY_}H5BufnO zoVOaZbg&ii#8xk+(L^z}#d}Cv!1F#`v;NNdGGLO%ERBj}yc?nCTBY3s&;Yn6VP3vL z67D>%K8FZ0WVGfGP=p_2s za;K7$+16_h&Dss;Jg2I-HRMiuAvw$b+Ue=8F7FN5$HXr>k2#1O@kWiz}g_D$&N`6st_tx+NU|iFS)6&+q4ogElzRD zkOEp_6*xMCXV9@r&*n+A_*&e@ZYpk-*9ZUC=%Jvv4F}VB+z;CkPH&EfB6)?K?1mWK z5{DP+&*Lh%e{}+`zO<}B?X!pFs#R-=@08YQJZ~d2XlBzVuuk_kjo^hUmD^K$yKNlT zRpemB@khywaj1Vc(A7e5f){^R80@&$k$g4I2bg&G$mYu*-khDo{&6>fcnZ+Q-E@vsmPNFMci7pVOCB2103DSCfX|`wjHn)d- zu1BTq&$nJ`HQrs2c$eP>MfR;Ps>{@Jkv+oRtk>Abx2R%(|18Zx3%}%F8aZ(y`(TH$ zlkHjAZ(MSdD1TOOf1V7-`e@f%Q;2I<6K>J$L@q--3fx1|Wgu1ndNDi!?AZ&(Zbt0ogc zzpT{<n6`UM26l22u+EhW{Pxp5n7*$~+GnM@6{Y07cAmD&X(weuksskx*S z$EvjIMdf;Vq=))1S}C7+(%Qu{KK%ag7Q4988R~R@drsHT-Bw7)_jVLJU5H8fPn{fU z+_ZF+zI@wNPR+4JG5>Fa-1nF{HoJ6?>9{cqYgW-bY>&0hkH7D%?~(HyC1mVNUF z1wg4}vP4$B^LZoFu)z2WmTib8NXhOr%5)C$NO_z7M*3+vAp=H8_WnAR8HSb8fn0_o zMSY^0bF9kebG70-`%MZm*6J12*0r7=u|}lNC}Km?ve^p?3*`0>Q$sXex}9pI1&j1_ zsHy$~wes@16{LBu^LgClPXyJFG4z^T4~gmRKjmQ|ry+^y5z=qM^EN@^I91A*-^ezA zoF|hX9$`v{I+=t7@*2-eyrEu;a~Im*=@^R-PTOENa_UPzH=hT0VKLN63l_&KG_N%q zbxvI|udqamMES{*af{jIQa_7IpQ-3?0aTs4h*D-pYYa@CC$xc2Y=4s-a1+)D1f`gL z4MfE?!>)#`^=bD1+Y$`dnc)siH!gbo*Gtr_0kUPDwW@-H-F`;2f?%yEqv%*9f8L9B zgsbM(iwN(g<2KmR$IA0Fc?0e%cTQLFix)Z!+RbmxzFJa96~7LCeW^6#8r5S^APep} zt){s(u(0A;r`CM$$m4T#@7&5x-Y`Q?E4`I~y?nk}C7B8XQ#3f`>JC7&$hTj-OO zclrr?RSEx?$x99mpj*?q`{}rv#Lu~eN;6CxB~QkeasJg!R(G0vB=C(4`^7%Am+L2a zMMkEgBv?TrQVOeh{g1sOFcs{8qA$B!QOaVR_$H8maRl^ z=Z3>fHhfKutG4wg_Mw=abi7W-8;%G0m_}&dtq0@QeA;ZT9Q#wJe;uw`s-A^P$l1Ny zq0dOU)qpu~xEDUZ#naW2E3Ck5Vm6OlsLaIiK#;>|p? zy0jvHbZ@=4drO$_54cA5HF(tSXN7J9TOf40Z)QA`krn{gMyXQt3?<-0G!VNat~WfO zZFC7;i9k1Mv8~m>yJNnI0^b+D;(2g={nLCOI{~1M)b}(0?nK3DA$*X*s`^_G0=m7{ zc^LfZ&ZMqqTIbO~%Fr)&mn`$9EGh@6@|10DCnY{b8E^18XSh~OB~5o}ot{HJwX2v; z*C_;&BU44)SuilpD+-!?EPIOw&o zmWCDJ*HPpjg4SHV8@*>QC6Ck@1vxhL#)K8r===}ERbC9irc z$Cmz1TLZlP&kUiUio2X9bqbzzh;?a{^0r7B{Bn);k{S`L?QBw0E4}6|U+yu5i2;H; z+I!Zp*DoVLdcR@;u1^P3g(k!DryDHhof=HGpgD%#;dOBsHq^OavU)8$WDYODNSwSS zt9V~~YoA35N9BO|49?pdN6elq9@UAKw^qwUK1)9$CO-f&4Ii%6Az18J;`k?n16-u4 zWtw>aj3a0AxrLpoG_M4ye{s6M<}q$MUi_wEJwZ#{>gz8A#D!L*XI1NGh+y?u8mt5d zCF1vE(JNtfg)~HN?`5`>+T4`14wv6bQ0bK=p_y4lBqm4PMb*iV)Tdw?#aJtrBb8DJYMj$NFjU%EK*Du z;ibTE`yVId+vc*T3iwBUt^b*$TA7+=!XN?BGLvHn1_2>}JlB*Wk#!Th>))=O%-%&T53>|6u( zYUQ=2Y|q5qsm2hYx#Ayd*GihyHSH=-)EfRoJCrOFaN5p4hJ5&J50}_+bIs}1?0L1t z@aEXU=hCq8KT)6(NoZXs93UcW(|UUbH_PodZ@cR;Q-8>|{jRR^S697;BsPy)#?}=i zr(H9p?(@EprhXtpopT@9PDeNoE~O`V4I%(3YdqPrF~#ZxB`{beF1@>xA)C|rYK}FQ92ClR&tvYQdJN}_$XAtqb2?V{ZDB4ZaW+g zaP8!$S`*ZSBNwTX+zbBZJ!FE7&P8|QiPp-a9eL8Lylw|n&H?%t$W#vUiu9dSXFuW# z?uA?LgzgA$SAFiS1itJoeVg#5F3b-ISfU&bW*W0m50TW+jDV0gXOeC2^1qv^%sg9~S;X9AzTGfR{tFb#)vI#e5} z&R@L*(14MA}l7-IrapInnHh}n(CU+1H5;P43f=Vc@xh< zc2e`iO5!=06hEt1M#B3>-n2YDTF0aNw+``|1;`&Ao2y7wC{6}UZRkHf5ewj{GNN#! z^In5qDm8fn=oG)X`2u;UI%G{Y$~)9&qw!?Vy%GpVShAV%{!m@p1|vJl<*{gPqoO|O{Rz#I@-<-eg2DZ{kNUY z%+`XFF+QZrx5-6Q6+&)mEsiGkcJvhfkY@;3saV>juO~~Zo%09Jc9vIU<7u!GL;kI9 zsEh$;apK8?7XZx&xt51d_>{$IoPqJbHWP5JLpnzEp!s|OZdNqw6X9%2&R%G1Va80r zZ@emNyz*+EDAg(9LT|}CJA+ZmQn1G)vf_K*$0x~(OG6tF-UxWK+8OI3&TDEsQqNkO zB;~5KaxMMidL(gzeT~Av*^*QW)qTbm#){&AzCVrdhE`Hgva*{d#BXf8xIZhiPvmvo zw)~}~|Jt1GDRvQhE8c(bqiB*3uwJ?kwvRDYaN|HCKS}Mc58rJ)lLlaW8(ZW%5GTnv z#dzjcX6BXh%Q=n5B?qvnlZ1HlMUXbt*2N6*BHiRvv9s{}kV^`&?{_LPf=hi1}&8Qw}p>o@{S_gZ` z|B-ba&~Ww5TlAI?og}*GUGy$ky+>BB5k!gJMT_XY*RTkJ=-m>%ccK$S?{%^KZ}Pt1 z_a*tCv-UVva@@Hy&ph+Y-1$}9WRH!b5$Zt{_2V!dwR`vmNFO3AFJ-a-lHG5Aqj+b8 zx4)IL^=wPYUYIXfLcjn+;aGA4-<;j0bG)Dxl0L~Hlw~Dpr6b)3*->+|L zc*R>TF&+0@!8F3>Y^wkCDoT5MGRxqpuU8gV%$g)4w}7H5<$T7v3>q@d@olz%8f;n%*|k6x6OI)!M_4CpZo*2}BGbt{}en3kNv^^au&BhV^M zuq%?*s8bw60csM}O=EgR=KkvTCG<;nCG2)zam34+;rswt2#iPf1dWiwO-UY$N$;F7 zh=JyTY0O{i$76El;AEsF+c7iZSlP($x#5&2jMfxIHgj+x76 zM{yOgMy0(*Lk+L*BK4}O9B~2#=Gyvst0g6!?_cTooK5PuOll>t*7=v}`qWR&SIIYu zH7T~7e9`-8_#>SK#Pw)sGc#F=I?x1kVvpd)@ZN9E9^2Q+rFs(oN4Pv0EAl+SkT7u( z^F2NF^2b2J0Ij1n=B*ycvE{1rDQtc2U$2bN^LUE!SGZ{nyivs0tZc{EOcE~j@&9j! z2)L|P9( zSw2aR6Y8?zQ2j~U(07$p+B+lk1Rkm>jQBM$m?0^$^03@u=u^dG3(aq@;Z&M%_eKI2 zyBIFg0!W$u)KyJ7W?#uw`q$5bD32nO@;9`(|GGx!_w=7U4xA5{+puc-^N|{0n{l%> zYZzx17D@jfU#|BX2_;DYEv>%=ay#&u>jnDHJKVZ9xinqyWUj{Y`jOpcMuw2{^71|B zjD1yKyR75-bboe~cWGb>^nqx>b~2 z7p*2;#MXxbX>y2tw5dCy>zp0e^*x;YcMvzEH>P}pC7od-m(W$O0fN;~nJBqg+} z{IfX^>)ute0iM6F*j{dxB~mo6Hc|Lvo1z9O^RG(D=y*%mTj%<`rEDYX+OOvJvU|4H zBFf|X%8ZI3GM#$E?8Qx^Fz9%#OxcPG)K;JlGRNeKgHT$;`p3&x;6f;y>z#`iz2MH^ zH6G8Q$3X97t8cxZx$&NPjnm3wco*@(Bvu-q<-siy=96H^CxR^7*q|`hd#!m6YLI9m zGZA`%+C9}zX>?+aev*2*V{%wpf1?xYM*4o^foSvTn1Z0gS`W(HByIDr+v+lt#6vR7 zVjA=-EdPC*Tp8;EdxibV6UkGOlqpV3M^p@F62}Iemor=(+L&{ny_R2z9?6eoJ2>x9 zGM?pmiv|G$;GF!u8AV>{LoOm1a7_Z`}H4sNf?CKnb;?%+#su=GwDdfeF0?uWbV=vKP} zW+$>e0zNg!;YWN#9>g2^H5`V?s$DeF^fI&}fej~@68Ybb%sv)GROWv3JX8jR=l)POYK?|Xe1G!-z&2MB;4P8B70k4!wH~5+nvOQn!37k zfCoKoZm8e0Y_7h1yZ*iF-?0DpU#LFGVHg9*RRODR&E~gqQ{p$;x|^e^Q+C#KvFwb* zeE-mt>?QyS8X6lXMi)!ZHRzqUJLEEK4@Qi9p_oBU5R>fU2<_KAeYQJ`rn5I!&YprX&2|5KM*)bfZ*dJmg3T;V2TzjG`d)C zO)}HM$M{+58cxq}Hb+)yuF{}ay3O@xTJ>IKRuwU{j7NoQ&9uFuskny1aq-QIDpqD^ z?ZYo0n>oZP4yDZV2#96Q^l^MYib4H&I+IR-#;D})f8pUeZTm#v#_p`}tX8=U*FLVr zVVDVAs&TM)Cr)p0puV{m52LKFgg;G(ahQmyMA@Q*m#wUJr7OnnSZh03LErQa0_EiQ z)*^#Ht!$+JVf7`B=;bnyUZ>WDoKHsWIRETH>Z%b~u69Lu+`=}TZ!V9pYKqyN2)n_0 z=Yb9nf0acX&(6-zUtdJ-U2PSMjqYbOp02b>ZEtPAFn$dZRU#OWU+GHz{2sHAOUj*b zP@#>P0d$OCS%GV23`)U2U`n6WRYWYU!llguSxR6UBqm;+xCOt%3DyhNJSx}kt74^y z3VM;j=ToC~ccpS0bl!X&`CYG!E5^)H=Vs-Dw}-OPX?JG2*PG{Dj_MqAa-3TYPt#(; zo*upT#v|@?udN*Jj){jzETXw*F)5Dk^fvF5YOhlGNcrB-cb~2d)vlol0X%q|R*amX zSoLbtgq{wLxnSdfq>uTGo8WsYrgktE)t@mQ*F~qKYU8awm-zSe2aG}639#%UP~Clrwj|>@g?`=?7Kl2C-d-f(=s1jh zv(U~*!>;*=n-N)>E!{n&z^m${r*#JxVib!)2cx8r#srWnL+{xs%t2r&Ka(DJzWzHt z>|=V%-GT)$#t(S_T^-Rv}T!4XoId0f7{MNy`my9^EIc zc><2u0&#TiGe$}CM!{aDSX9ee;eX~dMJ6?Ztu{1@iIZWmvN(DbgD?8tw^dV*VTm>R z=XC42SAU1>cYg9~{;*#$+O73r`yWonaf=z`-ykG(HdLzbVLbj6ewmO|ZE<1Ch%8_c zYEsZ6&>IRH{PBhia;9LDzn%(D+zFzF8ZuX^mPSj6hn04_z4B?wTRZ!nn?clUbiB=-qX8 zn;#W?&+s-6m_NwZN3Wv==f5~(o?;fAXIgTVoSI|`3%$3Dm!xCVgyI-`QE~HbzSR=U zrMVT$f%zw|0XBhgk^ZbDJb)d9gkOV#@9`1{R#%-U?OE3s|ECoH2f;L>$|EaZ57h32 zj*CsV)Vu!b*mSYEu~Yag$SwM>*y>wr$Ml>%6rZQzF>Hl;IjAaW26SXR$9b*dT%;2O6_}-X>{Yhz}OeA zDriqba0%4eVXD~f8?8)q`kr92_@wxl_=sFgVl8*$I=k??56POlLOw-$V79^ZE;9HI z{nWOYw1~&6*QzxeDBx0AD!H}qFNY+{g_K5d-Lt7BqrHlv541ri38koiC&xHtUtg$! z$5vjL@^^s+`ykO|N6(a^-z$|*qHs9e1Gb*TE;^LsQz-hnKKEy5!+tB0!g{w) zmz=ncO)l;B+OXHlWhu1UgvK?Uiu%mf+09yQE-Ihw&&LUt#yHDY?iepMEtv=h2!yon zFF+kceMlKIeEiS%+zoYkMGA!Wn-uOxL=ZBT;cZvM@P1A&GrcI)(zb*8@Q#$8ZrWOY z(f{GS6~C1~FvtgVRr4T}N-JqMiYR~M`qsh0wBxWyK}$=E+FVAdVbK#TF=jjLnBRHG z_;_pUJ6@Yv$l~In+8m%rObto@97)iO!u1ErC1qEqPtEZ7S(S{jk4V?fyRXv(XN5wk zmKTWwYzrJO*JzJtGfiiGm!ose;jt>+?5%KNlarY zs2G$qg0hcr?r9&@$z!2Bv9{Lg#xYcz))r&k>N^6vCG@O2TtRPd%Bs#1h#{rCh0z+j zw2sPhu|$t%1hR%WQ&i~NsYZtU(=+bpyA0)f`VM*|MlWU@_s6;jB<) zdSoj9QzZCAZJAmGEz=gNf#zl1YzEI>%@zy#>?V6OG$c?kp}s377$IeA;L!}2KCvZI+6&~n`-Q7l*D!*UROBy&^VKiRXFF=Qt$8NCKfcJ?ZQyOmJCrr_jx zMuTE+G=-k~P(hDItOl(r&n**bS_PbADw;Fw~Ob8EV)n<)fVPaA&S-jFXEPc{S z&%=d2FVpm_P*0i!>Cc3#I{6-{RY*uk)t9Q6yu@V6ZnVpO>6j|dWNUg9cBDUSpKXLL5m4WR>Igg1mmriI(>&Op zEjbWAgJgRDuyoE4Wu>>2(N`*Ov(EveZ|wf)b?g#&)XST3V&WG%5s~BpmjljYz2?YK_PKrhzrR%t(HSs@(3W}x< zJ0`+_)1v^}M0P4F{@#rq*A~s12Bw=P7Z*jX8W&URXIs{i66$8TwBBzm!!l$~UD@}e z&oW}~yC}f!rKseo_EAxXzn;bHJhgH^k&o9ffsJjXAKQwfJW?GxQ@|`b64Kg8(_DR& zaCX*7$=~S^x~}Q%mlyO=qT07k#Re^kNlrbZ_Xl~38s7tNv7d$O=A#jfVYq7j6%qXC zfcy%nZB2gHsHEuyWsrtxVs|XFGFiB(sc$TBt*nxHNbp z3F^0;9eB9wqsR$X%dv)B2ZA1|D8?@64P^?aYYVOiQo7%j+oZ+Lc`yPlO6Zj%NgV_V z&E0M+MNF6)`SwYx*luipZ_c@)Szltl%G62Xg-2PGV+v%Mmh}47w@~T928T8!4|r<- zvtsvrJPIfKxng+_W%=IhbQQvSld@y2%UTMAaJ0X?HK9w8v%2h6X$||WIbm`#=5Mf( zU+5(YXgj_>;j1j<7U?KmoiXPIHr`OJsp--U-x>|wnkL2_0ml0-{g_A<%Xua)oGWSL z2`IgQgcsWMd8mI9Mfyyl)S$>RJfS2?bDX3Juu&?Tux^ z_CE=E^GTN1UWce@Y;FFXmE0;mqJfTL>RQ#og6rAs{z8`5N3G4hJ)zU#+rumcZ+b$y z04`!PuDr#y05M0YdsrW{E+43Aa(a>#dnQzFLd_3H=>GAC2$o2-ZL!lq!TPV5>37?;)E*Sfp=&QIBuB&twO;7)4Mm8- z3>Hti9$j8TIXl~~@BEK9a|83hMG4~JDJp_;x`|ZFv9xmkeKmYP^=Q_@QCz6JUOnYP z%a{M}C$W&d!leU8;7~dH-EZYsHM*Y^?eCsZoCso-qB^!lg)gz(-4AT zJ0*T(F&JTMqeRx3QwfacM28lmR)k=Jt0faRG*h4He%3qx9{cQ#fvKQ;V={kiuMrH8wM5VPSns(^E@PM#1Q+9YX zJ&0D)zlTHjXxF(BudWW9u8e>G)B~kCT4La}CQ=IH@>u_|@7?~vVK?+H%kTMl&X6Qh zh$>MuwGn2WQ;kftAYJHxW&tXDmC8H_OGZZ}J~*ae4?sUXhk_ug>blZ?ZT&A z66l9hu1y(H@KZz6H(p-3%#9|22qii)#k|VZ$4s}2hS%u69E-1pn>Ea2DRN&5%Wt#A zs%POMQDHwFh=G)R#kK#Rp<`+F)m{j3IF~n=@^e&|D<}N%5jZqw*)i+-v25hydZWh9 zKI99-3yg-D9zm`AlKs1@ld?m!tSjO9JNLenfR4P4o-k3WFbGTRSB@QCn^G@>l9Kp) z0+8fv@*W++<0B@RQ^KrSz*GmrswsYWR79LPDOJ>|RGVb|^K69=7=5wd2GN;kj2rhDnGel#yFw|MT8zBykp zRj@cGCXFg#;U`H-Wx~aR)1!ZycKhmDW?P`Hymjx4Zf060icq9$F|NX*PP4(3d zOV^C!9{r|UM$lC2zzwx0^cvguxKQY_Z^M>G?3ClC z0*FcqaRB8ZHFk>u#z$Mm`vJFo3)O6MQ(&9XNzY zAYwvLGVZup)zpeSz3N4>ai~d{XoL}MpP=nU;di&yf9ypBh zv7pnY|6U?iIDfhheVwjt!3-^5BE2I6!oh*2#uMAJdgK92h;T4^umi4k=?inQ++ z^6kmck1=Bk@jx701r#j4IuK(^a=K!d+c;dLxTT7GA~2BQIWOh{L-wNr-Ff~6#ASSn{o~oR(vO~Na<+}v?kub9ncJ;D$7k8d-O)^`X_!0kOuswbFkBw-c2!Ro7FW(nmX^=NS)fI*j1DA1 zM15z+$J{nZ6~l!}wVX>j^HQcISKe_0eN~7)IX%u zoxH9>4kYuOaYORJW>x?dOo^2X2JFllreqc_UMLbMghY=`Vcr>(&vwVi_aQdGL7C=e z8<;%tP6m7nH%zt-uvg@sYeK^ode=OHQ9S&Hj&yPxr{lixjZZJE=g(k5o5XZr&>FVk z_Vbz{fj+X3dnWUnOuRB=F1f=h!Vf=yvq#B3>e#(`ZId>-bQ{Ch7S$ADTB#sx0LMN7 z#uI|cKYDJejeS*aj{cvGhi6wlMin|Y&ZJ%NENXde7oOob_lidOO=s6S++d%+5ep+DB3Rzd9) zgO=%S^m;989&-HY6$&SEMY4^P^jQA!iSGunW$oNeobPEA1Aa&JfNoRtnuKOUG%g~i zOdnT_dJYTKb981H%;*y{f}gMq6S#&|Tb7>&p$R9RO4W`BmS=cND0&k^F}J+UTQ(|_ zV0hPY;kYep(2lPn)_-?w*fO*mWAULNGe{#Cq(C2%0XA_BQ9T9G_N^eBabjmejp=Z` zF3GfXRH*Jh?NgwNm0UwX3*Y+&-sX{N{S8QCtBiq6SH0S*`9E-ttr{%Rvp6~(S26se zPj6SgF`H#l$W^19VAc8Q!dq1vV%5U_nfDXRpI+qi8 z=V^w3LPsCuVWF_;4`CbEzd%GP-n>^I0E$t+!iCSh@M)jHi{E`dQh7c0|KEq)vdgrpM!*=>)te9_)A?%$1;7$Jvi zjD3jmJ*(Mshh8YC8WQfM>hUAYlx8umUUxz;U`Rl}VgN&bs!wU0)#rL+k@Hf8ET4(~ z@}hQOxEbn7Z@j`k^WCu{Xu}9bU}^clBP=in$vo?2Vh4{`mq*>WdEz@RY&@tGQ;0N$ z;7MSG{RO@eAie+Q-Mp;;wSZq=0M5;4UGdYoKXUy)j;Ag^53~V=VQX>3Z>9%RcW2;l ziHd}#3b|~EE3x`-hA4bvf)8dC%-thZ3(1HI{aUvW4mJHouscS>`7_m0K5g-7#zxw!FX#{+ zbOb|iW=MEif1l`c!6&n6cymJ8>~vSs_ozq^*_x5T;kXLaA-M0oLx(CBgmkvPn}qYo z%3S`03zxmw&aB%}ikMJ;19??(y7rTyR-^Ahj_K2O&WsXj*mvB*7T1rUhpv~GDtB7P z^B<{k-F~q>z5@XnFKD?k_e&G=aZccxqA};j$AgpZ7hI2K{s)*Kfv$Fb^lS zoaSliTfDui7F%~FYG9EB<630Vv1M>^tFuSHKy2j(k*eYZj)r^5CiI=2P%Zz$<__9~ zCWkAR7TiNzMDPGQvbxa2lW>__ASEJYYd9tE4BnU0M>_Reml)Zp!7-VyLS&pNPiKUf zIh3E`&EITmpYYwCvmefgU28lL@r?F~=|T9ueA;O-iFvJO`HU$6Q|!hMheM37zY-1S za0HISQTqi%9TSIcp=eYA&(yjnN!f)Uos$(BcGvebMxC0F&O8Nu9V{EkG5-U(519(N ztE=06JZ)(}#p`CZX$Q^MUdn1Q(!g_%wygR5=D;t3@n~K$%8J}_I$~k+N@%nt>+WXc z@eKD8Ez2-2!#$*}THtV`->gJiQq1nXr67FNflvHqTu6k&*(#&xHx44#Pyva*+}4Kn ztwxFYw7I}PcLAr2hr1)SI+H%m*!gm?h0iklm}+MTM{*IuQI{ty!77eY;UVMvS;i(u z!lp>s)Fbdbl2fKz#SpJ`%68t_fOEiQa%<&5SXxb{t&J0h!?WHZk{Np zz;aF`$Ec>Rn&`br6dxam$AI*)6*8@qBQpEL=HSw2A9?{$DM3Zj8q*Iy>LG2SnRryl z(;-#zODBo7_N#+@Cq1kK)ZIPHJVaSN9gQ4ACHtET6$7CIE4n@1q`S~}gvF|1Q=A>f{b@6_M z7ltRCKkg&^{=uB4d`Ox1p0)7LZ4+;%qn_@ zh_<0qHH4HXl!#OhACZ0}#V7&2G3RlO97!e5dnO|9X%+uu4?|~=Xi`3bXWbn{ zi`J-< z?XkE$RbdQ!o@wKxrTso056EWJ0VDi!#dz;YRNJ)gd^08n(|Ywv8Q5sdNj_T{9859af0QeW@sLE>46nwj$C~UWL7loYeS)N* z#gy32_sn)SVp~SLHlHZbbN;$REisaUmL=VYZe8R)Ju@b9S9dpTChIy)&w22fUb83P zw1Kb4nTL0-!Zhhu`wA>esk{vw%(mL`z&|;i4q6fq$60EYS?T_td_yEJ{_<)XI`s1y zrQBd0ps}^3J#>!t<_pA<=9tG@ZDGW`vUHJUdEPCFG2B$HE0M(*lGR zAjVO~##5<#VeMR=;=O$tTbM6OChK2aRELL$t0J0{?VCK(|3*le_q>cDgvv1pl$5Pr zXuos4ID9kz7-x4z3Y-Yxib47CmOrI4Ww>z9BOTq3`@vu=n+dR>_U0_>&K=q3@dc3QMkztWZF)*qo!wVe>bW~VgB;>2*^ z89HM@PM0Z&Zq5lhh`@e8P4&fbTI=S9{g#?$yj3E;xv-8Yq$?xU-})k?DO-5kPrtI=-r?q{LZo8fuj%PgkZo7)-Tn!DdZ(tq~rB z`*qn`BwC%ipL_d^EWs-1xk>%Yr>7er#)s$-A8M973DvB|-Ta4=l!1p|l@i~l9exg+ z-6MFZo4DUKmRH0_c9Uxe*J7H)#Mxg^fGQGTms*r^ZAy6=prFU>P3Fp5TX<|J`#8};9!rh7Kd!4ZTJOE(1S59%~Yb3d=x#5wKoU>$f@A>OGFa107 zsv0gQ#rdB+Pw57*Bt+qehT;a-TNtHG{5nIENo#hGNV*!8Q*w!R-G)vavsM1RD-E73^+(bW8q$cZ zhcfwdRX<-cDX*i(t!h5KC>joSMFSOsmRnw?iBpFCDyMSP>_)6=XGZs;)pIf@x6Jxk zf~5s5LwK@4PqNdpAEEj!H<&aZ1W%Zhftm0ENM(6n%12MtN5Tm(ivRjNl z6;>OY;Y^X;pJUQCebGlFlN2lUKb&_o6OgC(NmlgB>QhB7qAKjGxO({KH*>0d03u^b zE&bsPNC+L}>0ZJG<&J^n8LNtl2Sz3i{xMzXgFgVA0@8v2aeb=zA#pXutvq&&a6bms z$fswdHfNM{6~YCX)5#G9l;X9!u_hQ;A>!{uRWl8;OT{U!nX|GNKb3DRdh)y6@WXAB zOJw?=B8PFW2Z9!(tl`8p5Dw)4q`t2a-&T_<`~0 zD?tl=E}JHZ7=8Xe_0_L>7=ryKc9P_p@ftGTSLW;8n|c=Sd3o8-Oo^Z$OKXY$m#wUA z0doi+wjvR~(Rd$@R(7S9X>9;i*7_~1X!YIqp?9}oh8Dmw_+sC1d>Xz|4Xv@(M%%@< zQ`x1SrFv`nr3FL!c)A%G;ymX#L|i<^fcSf7;%_X>;sju35kH0=cI9`c%nA%ntP%X= ze?&v_Y@&vj7bsF~!&hqIZ%M+_CA<$C!I^5-6Q5obBRFXgU&X{eN07Y7LT3$#J-3~?r6K4| zgi36m|8>i)^X(eW9q!jJ7GU?xybWkIA@Vz9b0$Vp)X9g7=QRMYIh*Db6|5LtFR2gC z6dls0Sd?`+Rg-k}6Yn+RjjK-Ti;dS}cxoUa&=96+ZJ2mnPYY)=z9l)TFThaX#tn{w z4|sdrk7TrTi%jU*RB4XA9hz>s2?FBM2I;SAQ3-%1sp7}UR}YoL=d1oUGO&Bf_@|+< zY8XR=od#w3Z4v5t#Vb>}MP?}^z0vS-9Yn8Dx@VuDb$EfRA4}rSpHads+H4kx1ptdv=8jo>t1_c5>8+)2UT2a zr#x)sNG7k5rFKI{eWzf(*|1Z#L43QvgtC0~$kyoY);pkmf#b}Rj>B{Og56>&3y+bm zFIj`POAdefq*Ba>xvbIh;(davz~0r6MB-DZ^!X_PFiaYaiEd4R*ivB-40m9X?`x7N z-#H_Q<5T5z{X7V7!iML$|F{t87-$b;ad{OoW51nQ{otMo9d6GF*?5@;Qlp*wc)#H% zTDdXa|CWeV%B2~fPPpx$r#M|u*eRpvUC&X!YRoT?us&D`ruebwdC+W>mVj`$3S7wl z&;w$#tGjeX1f1wNj4}s_K02Hf>pP0k{^{^xdC3})22x}xv>835v>5LtGPB*6brneF z$K(xO(cq=Ve0%I=v-{ZC%pz^dDJ^D;7k}@q4h?Hj0uvQBQp0d1&1a^~Yea+7>w6~Q zYhY#S(a(IOHc?{-=L{OXlA^;7dO7$>n-ID&lXnk*%AFwF3%tI`)mN-lRE-Juk*J-c zq5WVCEXXk!*?R+KL{>ydV#{)cFXJ3<>l#$vzlwV7q@%**Z*>H8_Z(zWRJ;Ufkg+S zqThgcwxtEWXLk}|=e6o@gXd?rcSYHajW8|K@6Z>r!`NL)rKKAWub1Gp`A{I0dygUR zV|ChsJc64d1ihRnWH0;;4}Ii1PrfWk8o7m+Rr*oyPYw?7!fJUNTtpw4iZv@KsG%~y zTX>A{Fb0)s8Q<$_T}b?ggm4c73*L0ZY+WbD3WvIWRCNkT|D+U!(*A6n;vIv4jm^!;}7`GtpAZ zw$x+Gr3wIGHl}SgVUK*b&Te`gm)e`Vv$FY5Il!QfH{U2TZWYq>FvUR-Y<1KLr1At{ z3w1>y=1(e6(EW{5r1Nxw2T-T24Dxge@rLjb?i?gr*e|b*aS=t)KMsHxV?clpR~zKT zY6A?MwQ=BL<9%CS$jC;}%GrK{c054a8ts}1-vyv${^;!{-@tP9$)wNpiY39b-6coqAuDMjEod}yJ9g&k zW4Ll)<)Yd;SeJD@Rn~fgwTq;Apys2M?Ortl$FoftZD4W9KUQ>7E2c=klK6`*?3H(u zuQD6L`cUR*m**Nqdsfb^rwSOhsJqArZ*S2I6z=K|R(t6)&3>%KK^E~;@j@W+lpNSP zllfH@TPFTi?=S<&%=R!R%gGXY$*ME%>%`f}(94iMdSvS5lum+5HP6|^@rgf!T+?^z z!XW1aZi~L+bm>;D6NCVy!$O?fg*_MWK0EhP8U+h|0>npRJAOniVB!Q%@+eke+}vq$ zvJqx+w{6%a1~1sX!+|QW0P9+t+bQpR<;~4-HLH9Gl#hsc6(CbmF*^CV-l1GUj1|A{ z`>|bBJctUn0+X>=yzVQ~WSHn_qquLhlkfQzxcDsLJ=}7DvP>WLugTGWnfzkk$A9VW zJCd0!ITg8Y`f-P-@)I$6bN7&ugZqfB<3{8)tj}UT(gJb5a+BsKf$L_lvW&0f1NR$_ zR$2lHxO2nx%T~%3ubOYleAfpb>6QG)cgKQCe2liy_~(80t_XhDw4G2qcFVgj$C6r{ zVqW;ky0%2M=K_@u^RVpF^{dp6{dZ0`mPF?wpnA7holJC2gf{H3!Pj55K+L3HB0#TE zO}O!7s3W$3C$U)pb{no({gc{~S*jIJp{~p^L+|ivZu>D%#H=OSgYiCa###u3Jg;1Y zh|K0M?Zl{?P-PW7N&-hJIE`~zmItzpC?pC&();RAE=_2?P5Lmr+3YqAmyVdrS)RBSNL8h ze!)FByHxS;m6+9Ih+jcP_9vy0B^X&>h_&2gOuvJeHQfODQ=uc;qaGSa^!>;Z3zsD^(sWEnoohque9oOMxHDQV?89=WJ-l!0}^vZub^n7PXS-P=>U} z^H88B8yV`6as2vH#=EF@^OVF?V>MhwnPZH^7&4QiQ-UW+`I#%>JjZW|7=FZrr;gac zfqoC?7yj4ILgLZgA&Ha8rit-*K=U^xDX>$*&29Vs``bqy4(3;WuFY{2Zqq_4cX#`Z zEv@DF^vPLid7Br!cIa+Q80ORuH?`*UJWs5DQAo5!_zN9f4ur?cmyvc4yUL#W=18!3 zij#@L4DuZV%?o@aMpN@^uLlV<%4jEN+3$SVa)aPFj@xr|!%y7flg&Hc>`ArC1=u?s zW9BxNt~9tdB~2y&Q^Hn}|GZ)ExacxPx!N->eA1S#RI+m1jvr}83S)+GuYIJA^24PG zL7!PqfhosUd8~w&-9xP$OhhTHL{K<^q_hWWpux`P-;#?tgl-9jPdJt?2`KA@;jsTF zsA8vDHB>~Z`w;B^#Irq{r55j>nmEMiqti@l?zmV-TloRFwgHm#J%6Y4hwt^ep^Xdiqh$NV7-$Bg9_IaqGqR>AImcQY0_HrWSbJ9X;;!N^7%Wi zhYi>+6HXp}Ne&y2Ow)oBpnH1<%lW?E+~#2WHmMy#_WL#F=zu&>D@$S>@y1ClX_DQ? zDLo6`s*9eHwOVn|!zhs$cZ|wdCix-h;?^MF&ga=iakR*UFAnAVuxrHfri|ZPZdZwwL=V6*lav9)$iGW}UM?)q zz8B>iUG4(-M3jd8X``8AaIc^v1kVJNJ`^mf{Vk{z``!m}>}aV^l2ZePRoqOg&x*#K zb>diMT*J9|MY}q_bx;}!bvUBEGyKlm^7{299gCegm?}^rLYU$_P1~U;f(&87Hh6sz z?<7NziZvz_u>oa(7#L-Fr;13tUt#!3@v|zE%1bc zqMZ|?cDfY4lFTE*cgBXEFSakp0^gOH4Rzy^6t3?sjzVlBLw?$}1PjO-O11|rt6tlS z^mW%m?Dm&!WwC>gY4c4;7#^Y8sb#@XhXh`^I!Tem5G?w=Mlpjm>mY`XU`wcre(_mrFGxBql zCL2I+pX$;z@a4`>T`3e;?lBcU>yh%>5Q_SGj99pd+fQyxf|`lGlNj?k3_U;>69X~O zcK$MoOGE*YwBKsh#}T0&QRFqr1yPa?s#x@!tGGRm4+IznSMHA}|)m z9M6)mX#V3QJDs@pmT`?2qX9RScW(66!FT?BD|Yz(4>*gXO_Y5vQTO|<+o?(h;v2Yh z%>{Rg0nx+r7Qcaj#OqV{VZaXeQ;VMC^q1!t(!utd#^f-WWnY8&HZ4=<|22t$MHu$W ztwo5fXn^5b{;oY=cxQC3HGbQ0CIY7aefphm7Rzp*f#{&{0>ky`+xCJF^yd$WqvD)5 zJ`^fYi=)R|vc^WARRlc`#gOz*MyH_zGfOnmT1(he$a%`9mG=_i$K~>*DFJl7+R7Uj z!RLJv{$_Kc@$!bgfe|jEvNF1#N3MjmQ#hB*u};Ly74^v(U0)Zq!kKxWG`fNS%SPb3 z7jCyhIlP7iU7<2CC~k!LWm?C9BMBRC5XdT0gO{Fd7!LYnxvdI7(3oATfVFF$dxvnG zuoP}e89W(!m-<1Rti_MqfP>Bo=1)paC%40x;kX|pZo;8;oIR|Jf%mWivv7$%-6OG2 z!|-XEC-Y(c8Jo_3A~qxd4aZ?4!&RN26J<_-L+d|32mIQ`wYYicdvC96geT1ChwYVUH&cutxeElL1)==vM+kB!SAB+pCWkzKPp{G~jd ze(g}VMKZHSNCh(Dpj8IN)yVbb5e2;USHb-AvZf*c41D?wI=>#~d2y8BNlqzrgI><9 zfG+-_fIbGhH6_bGu(iG&dLJhMyC8~iQurG*>^i{?8mKYHt{(9{l9w;UtTw zt)l4AU#bm!>DHNVu<}?d9Vct_GHF&gM(v5Ye@AxZ;X3#BWFHnj<4?Fb4tz%}Ede-f zbJyJBjm+ZF)Pei2S`N6vu?9}S0U^pmtVedYm&{&!=Vj^{0^*6%lH|jrEZ1M{KI?|W zLL3ED#Jm>eqL4aR@YK;VJ>TCQa2p!?3Jj*%waorc*{x#xIj?xvG54piT~kdX8)*;t zB;28X+vw z@Y-(62{NE-Qk1YQ&<%>m3(&NDw zBp%QLjwgOF6Ac(9VQVGer0I_Dpnh%1^GAJNziPy<|A@GD+plodZvCi`La*R=xd7;F z0K=HTMyTt@%?1bldzmS2SW&=G5X4zMKh|J0cMdoR-8BWAzH+#0{9x$uTI;|)qAM&G z;{Fa{u0`?!ox-tC&pxdsY_yjK8?wmp*+DDxUK1*`oY+c63V};K(*Fq$SdY zuV3Z9-l+Z3P%Sl5!P`eL*+@Gl(qEol(wBE%(fdG9>yH{{UBKgXbGx*X#Fu+1qrurb zG?o?^4TI;X6f7ARHg*h*VaskrR@~LYh23xDKB$&x6;4`(KkNQvMtCgjYm9ygW+VC5 z9LjQ_aQ~(Sa!&l347~#v15DZF<}m|^n2cKq0l0^-b@#}D$Hw)IUV;c-7WIy}2)3yI z&Po^{0%>@Vi4YicG0PCBV8K(mmjq#DecodV*&KREoW=b=>0JK>(DHKpL%Od3*;vY z?!bGqa+Gkt<@B6lb^gmuHr28T(q0(@m;3)<$*d1Rn|VLZkqh_SUBm2-FWXGb%!7r+ zF^f~NHDarJA;ue`m)SfLqbubWk;lwXUkb64_N9KbMYq8&B8LA0QaV1p@@D{eW=8q= z{{(kydX>zznmOCt@h!bC3zfNc%P|=ThJcsaSeS#=A^tfmo5bGAtXbbLZ;r-mbFpMo z_6A}lO{$*BSL@_~?bLgjJ4i5)CDAwZZ;JxzhR1jFklo9qFE8p7@g;vYQFuQXVYZ7g z4_=+7Yz^4IKF4)W4 zZ;6z3f%lL}f0G{zqQe7Rv3B!UV5P3~%s+fE@OXK7K;nnz2@9b@APa{e7w|B?_KxOp zALWfulRcQYvFzl=NXyv(kR_4C9KoD24##b#D&qd}c#O0jr^!1*Z{7Ae;5oxio~hb< zUWDMDsm~AovAhk=&kIv~C+@Eq+vk9bkZGR}lAAsLp1s751)`&6zW`9(T#wurmQLwC5SOIVddZ6`X(bJ^Y?o==+b>be|Blf=nyhu_m8$PLZhumWI4!D3 zw9>1k-D$+tRJ_MGQF*cYcHXX&_xf_AB>>FYhoqDKEy{fL^5h>bY5#XyY;EQ2oH*jS z&dtisu2(h}8cTjLF;0CZgdw+`^Zdd8Op$-EXR#n4?Uh*fi*iKLh#FAPBVPr)s+I;6 zBzuAw{k!+*$ne<7i-1m!hp{gynQtBTgaaQ_Inu?7tX3Tn?LJE_-y+FPP|1_Y(ZCLyG4OjPFu@AC$NI=nWG_bX{$4eunal5?!V3C zbl3XEM*VKh47^dFRSP>y+=uIE# z4cwr>bA=nz2B7Y`r}p>Ik40MKk*QW$?Ggv&{nMot!T5q!cLYyGyn`|P%Xu0_G}M6F z?2*Haa@+gz-yc>SB^yG%FW&EYggCH{{lbcY$^9_Isi1=7=XiFRd* z9K}}Sa_zEN4uMBAYg4L&tWIHAC9X#56>Z~2Z(mhMNI%Hc9qBg`Xf8=~M?%TaHg&FV z9sQ)|JT7t+Mv0{-IJcTt@UZyRuq$_d%F|b;5o>z=FG^pRYd@;|X>`{QG?@A>)!w8J zT3gmm7aCR1h+NlBP)i#dx+CMUrccvevgPZJXzma>T|O9LI{_clgR@M{W$lo4f$FN$ z^ZI+m(~I?!pN%8_G%|x6ErTzyszWQ`85`gyqp7u5Lya(Y#OtL>?HFM4#K%Ev0|P%$vn#)jjDQUk zq3c-xM?#qH=z!0>J;~>APw(!>Luh+YTnhX|T4kUNW;eEZnq|a?GYCF%2}H=pF56!f z>obt?Kp{9q14AihtsvZv@QyEIG*ee``*;50`b9Jc$87s_;jKS!GMljtNf3QE64GRi zzi{>Z=p$^DcD7gFX5MnUIr%B}XMO!4NiUez-xExB{Ww_qbXe@qtw5=%b!F>k`tU*zWO6 z(jgagD)E}O+z?{dlRlAiaqdBWU>?|1+j#V{w!zfj{#2hF|euOZR@0VMTlO z%BgyB>4jqZZM?ka_LSfm)d!P(Kf#vku6_l|AD(kk>E|t$aV`rY?Txnc?N+5^v@Ko9 zQ`F)$eWF*U&`VWr&#mlSk++`qkwtSl%vy`-{0awPpT=R!T_(7>Na=RTe(&97npeIP zFRNA@r7+duv$Un1W@6(QwD-X(WY5SLos_c{h@M>`dGp*PLM(hGFpyG|rAg4H2JM4a zNPDA_-e@IO?={Em>6u;M)+H`?)i^~vmF^|nxNq67$ewf0pU)O~d@35*c$>(x6jA?H zdF^|2@veYtk$6y&GtSavD)PZjR9^%(IuZPbh0X2`Qx3&9XNKOn#K);30_6qJJ1nuc zFILtS$mcq>oSu$tV&<0@FhpU^*}oBtd7NkGnYrl8%<`JC&e$G-UGtkS22pUCr41#| zQwPx~3*n!$1if2xlCJiXoEZzG-F7Jq>NLMkGGoqHV-D)2^1uw0GMsgmoF_Pto{60O z@a*5S+5WufEqkZ4UCD^C*_L6Z_j7Z>)LQ}Er= z4ktyw-@--+z5IcDlX8L~)Wu%>ig2BJ4%O#sZF8!@gR8|=)foDVZ#$ZF zbSW0t7rB`b$c&%KR2h%>&ST+W(G@}+uZb6~SjCnP@W%_+DsSqJzw+rcHj(BJp(zSg zxxLpkxkt!d&m8RHC^vuWyEJ)cKlr%nUe3ddXe&-b{&Re-9V#xuefkaBOhPXV^Mh?P9v3EdTuRQ_a!^` z?k8W|OC0Q}(co&z`B4tztD9Y&2D6GbsQ;X#Cp5d+^CJ|YZNu<*hrFIE;oqbG{=A6N zPJWK8ByxzjdSfn7uf^x3(@j_Q=ymt7Rk>%*z$xNx=pUs&5CKzna9Q{ ztcv@Kkmp_uA`QiB9{g~ISbDk?T5Q4a09*(~o1d=*LJd_Q&xY~r+c`n#3b|6TWwKOt zS5ZH-ubvVbkFiccG@;AnNG|eWX0biJXc|H&+3r*625EIOf^h6m_*+cw{nAXVxjalB z+*pZHuf*eFKHtt_MN8u?r7{~T>fI>S@)eEc@os6s5!YV`iM;C7Kj52Fw82?))L?6) zEHaghWxfkIHZQxrtGA)`K6B@2Ib5Y`8qfR!ZCbH7vVx9btT${OC$+j_2s$o1CvjMG z5tr(|lPBg^tY|poz2xz{O+kY0+&exjRod?szcJwd?p8$SSg*dXVt?z8JFJh}5rjcr zwiPHuQm8hb;`FrRK{&a6|FX2_T5$Kz9|XNVEwcgCElt$@I@T2YkUDb%1Tp8^w78k= zFrHtyc3Swba#iwbI)WvMZ|O%=*7icSV_u}b?N;xVPg%jL7>lrfNz49(bL0;l)Vl0v z&`meTgZd)Hu32QIryJkzq48%A#ef!6hT^Ay2qOMxXM6vW~hwbI)(Xu&Pw`<0H-xUy##i$gefaxlSdtSdaR;x zF)N|EUk=m3)%7lBakD77g4x(A{!fOS5%iMH$w_g_@(fKE}uz zHJ6IdNAn)S$y^W6IF(2`wU4I$dm*E)b=vXf!HwqQ4k8CQKEeCmD4MP7Pgmm&K8NXu zTs`b;4Si=CC3(Bfi0y4N#rJ$BnDRrA`bI`bqxgkfTJzCIOLbW_)uxn))+R$SvA4fO zcrJ<>1uSg>P|o#)aA03c##G|kGvTmL-IhXDt-3@q-NO)7zs?k{M4zjOS^R#+&(-b) zy=I7y$0M&N znZ#A1D(nwk-yJ;gDbarC<7Uaxa_Tv0Pf#e*+8-XBG3kesIp!A?!}Y1$>8XT_mx*MV zRVZ#-?{I1WN2?3o^j4np&cj^Z&nqq3iOaBctwA*tgrc_@y!&GhP2f+Ru>AiEHkj(C zf*q$^E%6c#2tjB|y#4mA#)VZzv!d(cVSlZYcT_2=+B)c<8~nk0cH}Zn_U_ zX`j3^{C3KSGHkFkPk?OQXubdaeLx#S-7AV&WoDWl__hbMPlz5F({|>%E>2#flG0YW zYQO%B%%c@hviZ$eY?9!gh>xyvA*PuJr!LIM=q&_Zl64&GRj`Svfq!M1ZMm@{`!rJC1P`W4d; z{(M^FJpAOU{Psr7f79ikXUg8A3y}=h9_u5bP7p z>zGy!v_RQ!^jK8gs!e@VJS143C%2bWy}l7*6@HP3eSe>d``-g!`AOgvomgY&KTzg( zq=+L5ruqv0Kr#-dVZsljM~ErXrNzTb7$`TGAwthXni+%eq@x~p9lx$AMU*=2v^M%#u7#N){ zjzTSJi=8n|)t=B^?^Fu3=tG0EBm-~rM+u(Xvzx73dF#TU??g)xt!SA)+T4daQGytdxV-suqEZY9~a zrx`?d9#&0~LobKq4{o{5BnuNN>ArGOim%=izinN{ofd#L@xx+N}_?tNj*{96aY74IRx&4`(%+(Gwj*? zMn=8GoDYnC*WY9Wlss!X+x6Jmqjx5TB+oH(_$R_MVyPmGWnx(A4ch$|wnIM39&A#X zhw%})iV8*flJG0f*w5}Vv6zv#G94?uZ5ibRPHjX)kc9fDxd6=5^_l`BaIaIS8@@;; zsP)BRhF)F&y*%?UOKz;FcRHiSXw%QN8NDb$vWCkSe@wHz|`GZ@^7nAoLh-~H#QBd4v6 zFkz@)g41=%OS`EcaTuI#VQ`Dqfligdrf|6I`q3Pp5ls|_tY@&a-y=2QH-{fSS| zAD@m3bq7=|!UAm<>L~!wLXSgghd*p6{a)}nzc?GXc=1CcW}^Nhpqs8qAc$QAO3&+t z=?XvyudEsE(vk2K2xe*wrXM<(0suuWe~yU|3I|#sBPC;;xFC8!#J&umLgAIwkN}9P z^7O@d0=&daz!h8O^KD!`Gx^Z?qaIPpUQ7iOe)0h&9ItN-or!F-jBor5Gu8E4ETVU@Nj}=0>V}Z~vqN3HXw!g>Jl*YC6!bnVaAS-EHV)ooY;8&~E$w{$u z@PI@wcs!ims$;aIlh?k1?lNc?7*y6yfBJzbhw8Z5pEJm>I=#ry5~uewtY z@)))s&M~{qNyDA|^RTxahg;}%J!P~^jr@ax&OTyfn*w`%Y$}9 zng*Ro_9Yzt8`O>05H^rgsmq~$lmfVAL5MOh4T|(MGjMm>-h9X=_-40^e?2b4(QcCe zwaB4bYP>dUDm-7@i_a9P$};K2F|5Dn-4_M!GpZt$3i^XioOFM2vHa%gPj${WVOr2p zT^9Qd9KMc%_R2G;6Vk%XVn4Jk*?OGaM5mDT;2<+Cc_2)z#;oD?%E9&rCuU46xHiWlL-}s9D zUX?0>b<-cF&%|t=Klm3l{$$fiqKTI4Q9lD0Cnu*(W7ULjBxNlvhev+FBRU~H!6<~m znlR#C3Fb@*o_kMuNT2fD>wfG28GTNOln=?AM8Od`Ak#AsLzZI)pd}qj=u#d2y|XU* z`sl(kUswU$DPWUjB)T!Uxf9RkzhXl+sUXA zVZt#8A@fe4*bRqWKxeOzUP!Xgm`KyCExUScz=^b0qtrX$N0~?nbk}Y#9q5|T5SC7%Ja!7ZmhiPKDV_AO2(8H+{eLnweUdqo| zIvVhx*qibD51*bEKzn{pBy}ZGD%E9-H1o>8RzST1rVeeesF6gq$ve)ucXw#b=@ z`#b2;5BW9H-<68ZYwf;x_6WSo-31sDn|XUx%O{T#$}MhCi-Y4kOLZVny9VE^?8oe# z$7_wc4Rv_Yp39g`=YDTN`#shBM|miG`@r_Oy5vuR4d>OhzeVStXO;TMlFH5f zed=1>SH-=-XEQM?LKt)@$Wbe8RSK&^B1fiF+pLZ6)Uc-X&Qg#(uEm>^6!3QX1iPaz?A*o8-#t7wkCI5wGa9aSn?Rf7^RvMc=vPbNDi z#8(v)Vg`!lXq7!S8k`0%mfvGYtxgTDOWKsmc*8r(Q5X~v@po?6_gj zpjGaH9Owox!SpCI`beOwIOIjfR-r{dY%gU&byNQe_~S<+>cpY5+))jWC%bpfR~1Ys zzP6iDzs0W~XQ+I;(Mc5aR-f?|GgU*jU-GPY&=XROR{72e1Ph_8DoJgu*Lv=EWh zf?jEE@w{(|EJ1``1BY%aYP2nu(aNpsRL_?{*e`1p_hcsXv;@oLu*Lfrf7b5V;QL;= zHP)s&57d$U2t!9D`1B=0cj<~gqIqwzaYD4p03o8`Bg3cKkfih<@4|_BbB4LAC#zwt z?5%L((q3kZ;CSkj-$}=l3#$zF!vE2cj@l3MD2UvgjBRdjlh^7>W86b%yH`?4lk;n- z&CepaFIf;&?JjP6%!eqW+_M3qk{-B&Jv0UQ^jiKS+W|R@%J=R8IE|yHi1XNG4s0}p zTOc^)sFylFjYM|Cka>&>r|^AI;|BE?EssYk-j9HTB5$yeFvl6eUWo6)9i4x<(7ORY z+C{0}*uf+|BR6eGqDi}b-kGToD9!Vm+-3BL##+)==_=#yV8Mh8+w`*KS1UH$o!!#6 z++2%YpGCrfOpcmy7SL_81IOtQv`B8a}?H0DpQrvI5aJ zwFcZ4CT!6Rw4Gn0P%jMyHEv+4S6p{w-StOloyHteD)o#PqN=C;;Yw|y#F?B0El7jy z(fYgXwV4Yc3Zn5CBEv*)nwrc=IQB_<7H*sw*mY;$jp$cGG}x^jL=$n_T*S-Z8GKB5 zm$e*Uoc_QcbS|s0LIm`=J#ikf=9~df5eP;ffPkl`ApK35v$j0|G&*VAtyD>@HeG4o ze(157$N>R`qmBA*a{bX<+)=p6^QH-2e}4C6*Gm3Seh&grm89}s*Hg(SBEGCbvV%z> z$@xI%Wm%0G&WGt}A4sIm?f9L8TxhNHRH#48FycylBM8j1#Fc1T zSq`4Ljx7lEp`LK@&mOqAoi|Ah<-!ns~a4jVT?}na-XUL z2-eW6h21VtZ)V-yS;RaQQHW~Q_-T5TA6)On7k%RjvRi%L-f^x!9euaoFDk(K$XoN$ zwdV9ec`-*Qir&wVtn9@+Rqcc9${G6$IfXH*K965OnL0i*iQl@~Obvhz>Nf>ZA{10i zoXie0X3UUwN3v)i%;9`_EdOn8WEH4#&@BaqrHqi8#Ojh?hQinxQ&ip2`l7zQwLy4t z>(SG&1rGd=+phw`?3CNSJvoOJEaov?j`z}@=PpSg|3J9wm z@wQI~UKk0^)fZxgb)D=x2o!XO+(C2W8RmREeDHmaw|Aj)OM_qEFozcuKIRFx2e zWa#j!W$o^d_uTQm8eY?^<>328ApFmoAUfe!3{a~8Tnwi@e| zWV4KR;9u>vPEv>e$+>}T42n}$a;Nhf!mseGz5bv=X}hfs1rW2~Nb)YKh#pw#x$>57 zmzfu0g6>?Hk9Ed>O;dL51<5lU+LQ>olrTduA&?dFhetmkq3VmmEL{pJEX0k2bS-?Qlr<{QG@G5bP=$R==CUlBuhdRR(dLG+V`Oy1%3+@^^ zj-bgm6AkOJe4JhiH>K!IxJA*MGeS!n740dJ(+0GlUpZ=)t~erF?Q9FZfsSj{D1A`W zIMOC~ysdkBGlsFToI2ucu<_arVSt4xmiKUOe9qPGEx%CbFS%$V;bF~~%TM9thbuUx zX=>1BW{m4mEo*3Nw2NXxV!;*=+Yc`FL@F#G+h^Uc6PZpt=-kG7Mkddfh{-SQ_dhW# z7V)PeMsMAE9C4J2ls}Yg8^nW9DXf*RJ%;xxr&!h^xStFUX;U_K! zi;UynQ+}S9g4-5AtqGU8cU!(B&{mtV-?4D(j`Aqzs0Ca6^d+L1w>4JF_54$4DhqL) zSbboLEHoM?J)*Mp)?v#3><@}qMq1Cff*YR8&%ltb!g7vBUHWfu{&`l@ex_>{s|x?~ zn?3m>Oh`UyPX*g*u}DP_EBN=~g78H>VO%{u`0g)_8+j|ub4h0K8JV8&T>8;lmB2*+DzCh{+ZHO!HJT|<`BB8jr({-ps zRl1AMD?i`;-0F0x*B7pip)OvG5`Idjw4aew^2f9FN@W7_;Xs!u$(6-KMkvQb#f=hz zRQOlD!%G+}PtyEz`P=|m7}(Rc8x}-ynnQhj${XSDQ6{fIICiOeKrvaax6ZayxJ80B}Hf|FwuWXDIn7_W{ zx6$$k(;y8mWCAyxyY$I&8~ra5>dmV9tRY2v`r+c&7s&!XPd=}DhtUHSRsS8%&Bi+V zOAV^>h|sId?GFCTT?w89j_sc#yAg)tlM}y{x=+R4lQ-h7FR!XXe9tk>4qM4D!4eXK zp$_3By+Y`&0Cc@l*VTF-)!S!;ndg#6s#b72*>`OPw1|ivYY!uI{m-xZF8m+#V-npsT6B=eEAy zEp>T4c8hqsU80)R=*cE%WJ3wltgl(71wI~o2@ zArev)j0zyu_q6YLOXM~c9=TgflRE)Jt~H}6A_r3&R;UL(w}193ZZLNz$un$&mv%&N zdV{mcP^V~75t&fV zkDgvuV)-2YZDB1QqCqA3%lx4w%n_lRgUW{nC=kY?W=iH67u7^r%R;-kqmiJ3^ z-+8c$W#>GZY@h?1RfUkg(-RR$sk+UcEV?&UdDOutQ0ju&hPaP8%kAl}W|%q$8@-ui zu6*x~ghDU&;8(9!1a+JiihlBbVD=DQkuz49h3;=3UM^&WTqw-PT{Zitlee5)>4E_s zi{{*Fa!tT~@m>#1PFylxgO5d7?xr~%(r?1W5*t@vFsZzO0ShHULhFc6nW;FHXF0i* zP>6vB_r(>e-kh*MIhAI#nYd$35vPe3K1?l!Cgq>0l{E~!YW6@~a5JFxt}drWvN}4K z7f6;7NbXG;{^ccB{9Y*9-*&d5>#g{pv)#-&{~~`X3bXR~64k58@Yv^Ytv8kG$|f$Q z0s3zHhSww8&70AU7@q%hVkUchdGiC21^=g#IL$gxpl~!Dz@P1q`Y1{1of%5@TFY8s zjj55UxJ3r}Zm0qY5tX5X3>ZZJD0I5~P59zcyx z4|q=ImZU6BcK3|GP%d^ujwEQopB)PPJ9Sb(X(4#}`^tG&woDXCrt^=9zz*doboG^C z)NGC9uR2unbh~X-7E5gjQua2 zE!oefdhWqPFRv2YhRAX?d%DKYOViIF2P&g#R4&)O(wfe{Fw~6Y7IQa-3SO(n*SeqM zzPuf?oIUSP#^YpwqEM)RjfeCW0>9qgg_}k`~&UxcTcJUYyL~QG@*ue9o*S2l9 zHc=_*a8e^fGdbsv{#)2K-t*&3`@hX}qgGy@ZjC?qQhD&&2o^SO$9+V~%s0K#^Iz|$ z%iqrky`K`6BR(Gu#NQpt>F^9q9J*xG7cbEtKL3c$glQ7|jbOXIq+R!?cm;K=G2$=J z>9?-j3Xvw-eW`B7N2Fbq_CVpHAQAK(mSt!NZopNLiFI`N_LkB+lbUJ{L0yGbuKP0$ z3N}TrTknnY<|KA=gs#i`Z5*rptdGtzsa8#|qIf3NHV8sIK^q>u{G<;x8)Uqx5;x$u zh^I77Da3^zCGgN;le#|-^XWrMrr$-YkkqEr#HZB+7vWGRs4zKg*p7_<`buc_GWqH(lc6W9cVHp3VO$M7npa@awqHkk`=Hi^ zVzGqUx`!ME-z3?mLT`b%6V!Q!@r@G4XlG|^yxTd| zdoxSzGPnP|Tj!nNR!jbQ4$BsM%v}?KB=0FnT3?ZejNLrHUi;exZ%RN<3Uw6~&`Hq6 z94|a4Z(uCP)8(xT5_8H=r3tDw1dawDtc$Lvj-&WLSd{;ix6u>FYA$sbm!qfur%dM< z1+55ZR+?ft@6U_c2&+z%7u*ohlR^}^BS2)51wS6av`48pyp!(BZ=$o2AUJ2eXZPcx zXjEj|-ar5Ng|MT5vmvCR-0?L7c*2vDjv2_u#<0&Du&00x2F%uB4a!Il*9VfW+t{0* zl=HB+0RIPF5iZz(W)r8w$~C)y%vdWJ*LHv3!4B%R-gLDRQ?`45!Z9$~ew$;-sEKy= zEB}%RO7zC&u4*7WkXU4K3~GG%UU?OpAMns*AuXzie7i>(_VF>%zDU%+B`2W=_YWo& zqDepoXW&aNVL6j+nYY(lO4YX9>I2t0`%S-wOWdQ|ljnkW@&@EMc2ikVO_Vyb8LWR; zUPqa{pE982P63o-&WgojWlKltFIb(Zee6Ep)uX+Yu zO-Agh2Ma7R>+IOcJPV7&u7V%coi7#NEBwskb2GU6bAEqs6+us-M_-4p^byjZkSY*p zkgJ06=zp)WrA?hze8Gn^AgP8U{&@)vnEIzy&5AQ90J&B1`pmT*_Ck8EaPF*O$)TkLpkN{~UC3E;}T5H*BgxbzI}- z$$0~R|IokBmfUj?qvP2zv;u7axiWK9ojpyWiUkDR65Bu z`-tL^;{i(S6MD)g1JBwCAI6#D11(zgzUWWEGJ>lRkh2jqs(o!WyOs-SE5W~A6K>qm zPGXU+52NfJMIhWq0fCJL4rFI+keG`YZ6Gl%$c){Vo9#n_?UK|+R3vH{EPdXyusoWS z+6`jdBYr`Tq}Lq|CO$>A_t;v%Niu+3#b5z^efok%e%46#Zz_(31DOi;P$K}Vds_@? z8>*$|FgEbA3i+*u7kXlV2lf1`W7;~=PA!pEZh&*tt!=ulyBpL~erm%hKXej~0+Kv* zs$1RNP9@t~&!iZhH(ug=ah>RzF2U3AqNgqUSbeexHJZC!Vs*y;sB@aUuv(zZtID0m zzIe88+m$Z<^PPF22*YcE37DsXp}G#^?E-MQNN&%D^lEhE+G00&-%{T-E9SF|FBzt_fg+I}Y+Tfpc?LYAOT6hOGH%ZK@OjuT?dh;R6zKvL|xro8{ea z`|HO z<3e^}ehd2z{{s>qREwXiFnY~>J>RPdnRSJrNVckT07?4m(Xd2#DNn9a-S^y4VKh+mRcj^4@y7|w)aL-=2j<}mF2820ix)hU$m#(03GeiW8P|mmybIm z^WRgMR#kI^W|o#lE>25Y?<)bx6*icBP^}M4cQrx?&E;=`SW-!0D)luIt%jG-7S@~1 zD0PrVX4*dZ;kt-VM$pFfP@%zlBsMp<(mRoMe%a(M>0^5hBdwxiNR7e6?66#h`I9uf zVAdAz^Pbm1%zv)1Fyig@#D6*uRL~|$^`ot4Y9eQP@X`5d7b5VYuil+S_aNDBjWeWC%2`VC>8Sd!kbTE)QQ>B8FQ;o-3#{+wBfxLvWqQJ$J^oOM?lXd0g3M~64uu`fVH z66+4}C3~!lL1!HJZPP+Z8KWcD^|yDWo+a#Wb@==hI2(QkjhEJJnt z?Fl7NMD50VD=25rPcqQe)yVfW$B`A7yq3CaGm45qltjzfUO0dQMbgCh-_5gO!lC%G zq2QNXRUx0Et37hu4L8-P#v$2LnpT#Bb;$|QG%T`zy#VK}!Ef4cw)+mBqb~L&e9DxC zgX9!=4y8X|!qM*B3^Ucad2Tm!Wa_F$n(VLM{!dLCFaw8W!%o|)v#$FOv*72t;bm~d zJ4tQi1Hv~pjij9!Q5J<^pFLS;BuZi=!F26Wk`(>DC;DG-<~rwo@;Bjt@tRfwEfYSF z8!G4}6W7Xp6vhxCKNzn*}ULXHo>4fDM(2ylz48{z58tU^mJ#Os*OyQsDu{2KX}tf-!GPgdeHW&}z6 z*}F7JgdkutSGxQ(VAS`aErEnPDjb_{7FD1OTd?n-L@>Rak=Nh&yess}FZiv_<)m=F zXRh0G9RI$KuJ*#CM0*~ye~m7A!J4#d&#pn@-gxk~#(VF(dgCNT&(g&siapH6`U|!7GcT=w4zPp*L+Fa0$ z#Y!Rm(jkjdZL!-}$$&f`lmhRYu5>?EfhLVH*w;l`sGOkzC7|HRY8r);q)Z#J@8k-Y zti`O|-&u3u1UJ=k?2}>A0eW|J=D=*!O2iQV<;CVMag;9|AsAmvWZ=GPE;c`{%^4kg z2OOUuXu1>G1I)&>++Q>Pe)NUU3Y_8o)H4XK!kX^6;CYuj%-vM%eNNlP-G9n3;xM<7 zZ-t|l6*s*!W}?&dxqS6ZspXzD-8TECtC01cT%D!QGmk8Zgs&oA6a&`2 zH5$dmxOORN!2D6acRVu`aPPD67S+^`XbzpqHucP+MBbJDTDp6Mf3D=S2&@VXrSeD5 z^du5CjXDzqi~bjpzciAZU$JQz9>1olg}8IReoXD&=npVn9^*5ZA_AYE2(gR+o-{}S z0n(n=4!DOp6d(h1C$lY?dDOu$DTW>m*SD>G(Fi3b5K${Gn-Tp@FEV`_-|jM$GnSDa zS5C%`#u*a!rA-;jm6rqbK~&?aa{*kPnl(r>OjI*X2{JsC-FEIIk_FkzUP)w9)6Wqe zg`KAtN~jR_IdFY(=P7gNiSS~jznasUA_(+rTx#$l4OoumtHp%};Sr58kqc)3_05E` zAtx6m%Z>Vi=_hbeMlbt4v{I%=ii;t+R`?4pya5FozhA2n#0g>mWphi^vfm4|zWTPh zVcRXoLQ&)K1A}pG3G4x{;sr6HZO{PSnzoygi{w-*SUrnw(VFSa^qLQhTu}6%*?YerehT4NfM4K?Aq2B{z?Ut_$YPA;qfz_kJ&S z{TG*^^nW5$*gn+rgBIsM2YiRyL;MR}J(1+S)<%*Yi8beR%cUaqufBIDnEimDe z8dEu8xP*~tU|}xT!3>pvm%u~43{WOS(u*c8%xR&d^WxOe$|7N98+@ep85g%K5D9|_ z2=G|sOx!_s%$RbreXHE&C;U16lZd?=ZOReL0+?Xdz9L|BuG`K|lPpgc7m>v=AJXDV zjZ6^mZq2Z7TFX2o*q6*VoBSIuW!%Z|q9uwg%4=#dy!la^@281^*B;E(6c+5Xh>L{O z9%0JB=YeYZ1hEPNfS<>mOeKG^y~sU#PzaD~AjBh{6Zc@K{3nC&(ZRg6Tv4MyZlbQv1~u@6`ER7pt#mMlI#l?SFefL(Q4PZe7J2WE#qC z&8Z!nu_f?g?!jzJ>MGfV%!C&QqM_Jn<+ygVh{kf#PY7uOeRqGBQIcD*M9Mz&*P#so zy5&00S3kg_c@VJ7NhsevS$qI&$Zjmr&&2|y`26hXB5pdb%56d5@Dc2cQEH4O$JGHd z25%2&z^{X5TN%u8v1h~1-5qVwnjKw^3cR?UJP_T-j|ITJCIG+y`2rY{VcFD-{X|p~ z6HdcPR>Ggvn1W3>{coN7O!hAYFjClv*#;-PLXYJY+t9%NgzJ25Fj7~~s@M|rDrt;) z32`;hsDe-UkvO*TBVm>=mbbiFT)o|LAXhwtMG(>R<>LTm48ku3Y`%goPkJ3oB-++U z8~RvR)yvDK!jXo=s*riB#>vgmHqDF2MqlO|z03kx%@Yggor1SZbb`itl-lQ%BiFb4 z?}~8k)QL3biQ0nqG?9w_ur!D0|6tPZo>jixe%W+3ZM9NkPg7RCMivO`Y#2dj!+$Kh z1``5dolW@pQd=LK6P8PREX9wD?J(ND78*d!a1D2kY$Q}w#@{XnkpoR)37e^D?DcOdTxj2`pXq~wfc%wVaKkgnSOBm30PtH%{G)J#UCcGBL zpIy~(JPUEC#u0#1C)($s@89WzN~FO*hPUyE{92jA5q`yzeGjGNpjslmKp&49jC1js zpxEcxP2KAKq>l19ja1d{=XOZU1#J04OrjKCwmb+k1vh0oYV*wX#q@};{Ds_uEAM?V zUw>!v)iO!>Wf*i82!@&4=%!H{e?sp-l<&6Kwv`C0$D`BYH!uqc z>@l7QnDBo|6f~GXa2Ps4TULDf3KLN=C9m*Z-mpEzhZ?lOn%7fA`1Oc@&e9d20+vJ~ zi%F9hO>4H1^%*^oH4Eg3mLKaN?)RCc-eE+KEosSofCF?)WrP^GkmoeE>$GqDG}(jg zgfJK0;Z)Ff=DPoxGm;c?VaXV;gH%eijzp@(`4j@Uksj<<#39J0$Z2-?=P<>nlUC44 zCYs2`@et|kwz*x21v+X%&JEHe?_7?q80Gi2-_LtLIz?5%{20PG{6PK@j~vXsO^)S zL=`}!!~7KTEooEIr->R2*uWO(SXO#CQecP&B~7mrLtQ0&soxcBapaM`RNlunA(D8U zX!1D<9kq>!k5$u-0%)p#WIRN~iVIdUPb~8zemMAV_q^UbT;OPYk4cHEax( z$0OaQY&R)LS+|{rjhT<(>MTR3WE1{cVFR}Y=cB0_BNWs;ja^_u`FQ*?sIUNwfzM61 zTHIO@SNslYaj!7XU4&UON5%w$n;X&7JD!+Yuol6kBqj1`rRO+%NYs5w+RnF`x&glc zKNmxhu8`eebJb0w$vH!ESpED31Sx$c2Fl zyv~fi^m3d*XjvrEHtiAvtiir!$68(Axts!p00_w(XU(hXV}5Z?TM_e|vZv6D3Q9|s z%!_$Km-LvP^a&6fbVu1w9$bdOZO0)!RmF`#P&QuM#XXShb>B!AIGklCXkb9UbQYff zxGwY}RWb$rUHNM#(nlg;D72!1$hmM>88BPvpY*}(_NAxq!~Y|?nO`Oc!Bq8B`LG5&dvg-G0!bxNfcLCFJoV zGXpOdOfWY;xNN~|n!neXA#07C`b;8g&gAj0C_gn2Xi7(kJ^#^Y^r>K0^9N;K6D9(6rOpA{>y+%AGJJ3usSzugZOl z#bJ_9I}^<&Mh?4jh%X1A6SQb(67M=C+M-wIvcJM0iyc`-xO>F9H`pSz%$i(|I}|Vm zS~FBK9?-9V!?+txUg1Y~n1KRlUq6bZg8Y`bTiZS?yWU$g9Y+4QwOJV*YXrMe(aP)>S z6u$TPA44_i0X*mYN>u#BNfAjy7DW@^-&PYoMJ(~|QHEYf-i%*1Vav%u5y?*|#cB&% z%omYB`fU6q(3G|DDSRj%G;mHscAQua`zpypDV=#i0g2%iXu!$tF}=PVBjyH9Vw%4p zR_IUW6FXbbKKQDirXFjj)5^ZG{1gl9D(U<=nNuL5w;yHz2>SNxIseA4u$iGuJ$3K? zBYSNWMT_GkgO<_l-i~b?WH)&Ue_C?oAavacJhcF@w+W>3=dtZYjT=rigp@B&h>q?? z=DlRJ94ODy@8-3a)`sV}12AI{A49&rmz5xtefIuk9^;EFg;$BY>eJN^2IE}Vii>qA zx4$&&$xXOhU-Z3?u4~LQ(GDGeLqw*Ris7L}#+6#7QQAuWmGNtqqqWfEJo>yLpW$um zq~Nuf7ka>+#`#1spkbe{8i^%;B*gwkx|!A4DSJJy3llxhCAS`>bVJJ{_~S}P`XS`u z`ZE??a46syb7Ww*#zQVuv%_NKVPQKa?FysjUXSQxY6kQ1a)N~)hxa`+HgX{d0_4j% zB9VsFcZH{KrAt~9$Zb5>#BY{dxYP!A&AFdC$4RvPp5q!%x}9`e+;$Qx9>(w2yJ;u# z>%6ox^F8CisZ_#QQi8c@GjU}qufZrUw&s4~M zIZ!C?U(xO#=I&(hOAKRUmf4Y1kHm{(rC~(kjAVmys7kI`JwKM`L-FvVdV&7>3&*rn z@!scN!QB&d^RDO@@DDjxD+F^mJIFA;psMPjBkXf^yRBXKkoad<n=1No6cw=xpSJ zw{3BtGQx~}8PI-B)7fnhd?eZRB!X+b?ZiV~_Zhdv_va};;)PTbm>v>66cF}FJPzMT zw)(1~P!wn{J4)1VS|OzpSbY}vm_J&7-i5{5SiHnTY+=n)cZ=C|)@7oV+v+uZg+byA zwH(3(l0Hn%IO=Ti86{fwn8*q#K1&o|7E&b`de_LM(1W{94yTI_ax00o$Lrq-jfmV3 zZVYFb7&u3{7YEC~a&7Yvps@`i}o3F-Iz&g(f4tFI;0vVRQv zXPK~j_-y7zmyB}V)1$g@e*661U)K5OIToRK`-(MqVF=o$T~nY=m)h$l!)@`x`Xv+p z!1ILs4<9lYPj)O6N7D0VnI$1&2ZRnt9gOto_m>%4=-yl%wXK~7%90zQzA2+Xp3e#D zU1{p{XazR~x0?7+I_%iFhy_{Aq41h&SyQeGz(vgXhz6EZv3l<8oBc*^M>7F2uQW%D z4OxX}ma6`YS?}5Kg78!b@q#s^Z@yHQx=$tPBH8L&XIK%=n3F(x2lbu5um)vo8}$bX zUaok9{dt%sAtZg+oH3MH@0nt;DiQh2Lwu=ySDwQn?HpoRJrJs)zl7tx;R0RGjXpXG z=lE{P$JJw0Ok3uBAv%7f$-C9TPKWY!KsBq|K$lX#cxiweS`eQme2yvZxGXqpwJ-#B zVToQ(X4cut%&=4t5W=(nZXFw6fPj4~6(6R)ZmvCAnB#328=@uGYPmYS?|Hs01LgNw zVHdl)CTu<1M5A(D???;^S6)^sfd+kdq2lP@apy$r!_RXdACoI|LH1v zbA}ALT*FhgDV@`owv&&Ire|`dXUVt!F!8I-{&sdmO1`WOv}s zUpaq|7bl@zEKstjB2!CMC$hxQVbp)^>71sKr)S{lohH%pSS&MNnK5Q?Z5nQJ!qD2~ z#=YhN^lCX^Tkou4x^j8x(@Kw%VaJ#9)lLzFDY*Yf*IPhE^=NOPl!T;$NOvjS4Jrtd zgP_tS-7%6wN-7=Fp-6~ygD|9YiFD1-L-#Pm0Ppzo-uqwg-uGB%&SKVLW`OgZy}$kK z>N&QE-cWv|^!%e+!n0RQJ5S|6%c#Sw82O-i0kiphLlY6&Feq!tc=)Vs(VjH_r(1+zjHJ~Fws*fCB~9ukyGjV_do zE)94vcv%H-xSUrVG-ftC)6I3@Mmh3_1x5X_f_>$$o%8(;SL03wQSg5Gn-N2=VZ^JR zb}wi^=z;Gweud`i3j}G)&%lcTYB6a-KUwqX7|Yv;pbAbpV@v5z)y#pXDEPqD0p0AG z75@}@AvbT~fJPxVaPV3`<}KtNUJp#Y5qs?{^xFA&{Gd7Pc2%Ll1!8E0IAy?U6))%A zu`BwwxsWcl_?KY&FY_E3`NC@?OR|eKPUcxgc|aSgqzm5j;ft4}PKlz}2n4h}7d%%C z`g7ar7N$Q23BJyGTP@S?=$~S*-A%1bb_d7&2^mi4(@5f7_s?0T1qv3r%p=?(Y5b(v z2RvPRA;dhvr1)KAbZjcmR_|lR7ttNBx5o4d5!F2HPm0QVUj*4_Ye?C-rt7C`bcI4;Dw(yW3yxz9NCp>dKTnL@M=M?44k_ay$DMR= zze}r;QJ$qNPJLex^w?^a!;vIaN+8^~rdvEmzMr^P({+(p+^J>7xDaM5Br842csm;+ zbG(Eta|CB7kdarjWd8UpTF`qgcuXP!wI`ENfU<{N8C8qCi0hbxLOFIO18%KT@S5i? zffaTZDYvZE2yZFLv%yaTs@u7LR$IdH&#A6cMaeW06tunff0ZG77VG=nrD zuwRTshJKB5OjWn_*(_=egSgNxBwixyd2^%WST-!y_+`{9TIpZr

1>$3`kD@{RlVPCzCFU;lmjpEF5qjm_wv z;cuS9S3I$#ZBc*eKwMF}m>nB2O&M-Yo&FzF(%>2kK0&0FYt+o>{nS^M%f%zSFv{Wj zn9`M$`u-C?X|l=1%y%a}b{Vw$RINfO6h&p>`k`z2#a3uq!+<)ECWe;76xCy*x*{}L zf>VQ!)#iyw%4PDKxxDmR6#SLdcPN~4M6gPr!_gweU7I5k>th&8lVhxU7IR}MV_dI= z04?dvzPY^fncJ9C_B5Bb3X`uH*0FicTcdo6)Xk_Xs^J)+H0pf7JH#C;KAn)up$G-c zY35JJpG{u;ZHF>8qge$ll}~>En3;Z;+u|n~-+DMKjGj%+VVAiORkvVR)tM=Ms+eMO z^DdS&SIRGqS<+8@>lbe$`qu`J4Xc62?(U=aCrL9R-Qv=L@HH}5sS5fXm28mgvBcy} z=6UPE4;S*sFyq!kqy>86_BvBt=7OuPpIpn3iHN9JoNbuG0{uPHlRsOvT*!}8!!+zvTx)_4OlnYeNcGa%*+(aV^^Z&yZitPWp}e!beXOu zgzmg{S?G8Z<;eJNGnR9h%CCOX6L|6bCc>pTArPJ2aGWuQ))e2mkAgZ!a^5s}oq%pO zsoE}6ImHSzr&l$|G4RYWx|f(r^LO>zZW{JyYcX68miv$H$ld-HG4-}f;nW-kyBF3! z@)+z`m(7QfpSj|_Uu5;-p7HPtO#1=7=la(*Lgr^{Y?|+4$jhB-#*#w8fD8IBCslo= zuBqwy03*QuaIZz`wA{)5Q{RT$$e4Nt;7A6LLc*V@0SZW!ON#)A$Hq1|?blKnXYMF@ zDCSG5d&+`m)v@FyVFF&{n+qC|HG<*4!qa|{od@Ngth%zPbiQ@Crz1F#A-chRvLN7% zjd39X`taL*X*>WQ3uLVNb@KDn_m@s@nzUNm)0>3pawSL37bJ=`R5U)u@cO6A<#Dmx zWyPX3N?5LM*}JxCtI%m!7vE{zw7+q9Jx+ik+2-o_Egjs^*) z3#lWv1ju!nefQ#_xXBjZs~m}ue&vA7TCq5d464;CDkDUt!9dd@sZDH2d5BT zmk7`?t*K1+wTs-((biirnA=XfrnrMX1=Y=-^1(`-#hsh6qSmHmvoYU6q!9-gLyo6R zRJZNJfqQPi8CD=73FQ3J!E@xT?CcgtpH;w0Yv%bF#AU`+wwGf7UDQT{&@q+o{a_as zFt}0DK-aB~5{Gs#!_K$eWT)E=N*Wygh9@s7I5;_d))JIoBu>f?N{XI)n$Wj;{Wq#Y z6E4rP7L zc=d?lF2%|7j~6U%GbFcSJ?|dmL*Mj)D=pg&ssr6AUS&04P%LK<{ zW4Z7%g|wE)NXIr24K9AZ;{i4Pqahv8(K@hXB+O#eZGT82ija`43@26UFu<<#?rc{U ziV880xi|;`6QaI@1nQ{OojfHM-t}IbT{h@^=co6xuHmUDRui10cJ#0YKddBFH*Rb{ zZE{mzm&s>vVXA#-O33dLqFKI&YYIEiWXKYfKpbY19Wvop;$qD&LSEgIoEiEZ#f_bP zuVc<R2U0%-9r$f=Mo8;O^ev;Jct^Z|M~3S zWd*UtWmDU^8o;)c-dF$c*a!GCMsnrhi~f|@F6#wjC}+@DAW4Q|K+qSfsTivk=$jWx zb%k{ks=qEw)5|jZA*R7z93Q`g9Y;X)l!^?O`6(3-9uw+5jsI}Gbz9Hsv{`h=Y8AkB zrO$_bB0#dk`6|Lri9eFJ=0uXBk|>1kl-5~x@ia*&iw)h6a03l4*o{bLwMh(5Bhrh9 z1azE0uwS+!-s=Ua=U+koA4eJd(^5@+!hRLuP+~dsD>5tY`J|o||L{35E}Iy$ zWls~C&7rp=g5jEB2{eC}uSamtsavcY^`z{Gs!NB=+ozIb{W?RY2sita%d0b4{@?8jqD;mPvBQW|H-V`@Y zM?KS|^wAOfKaT7St(b1=_icz@?)0uW>H0ZLJlYMAH(GY;F`a4q5A>Q_Z#5#$C*u~o z<XYE(jSGP_k6~Sc}wzvM~OwFTh=dIIaR~Nd@`Dk=*YkRMJVB$M$Y`n;K zCDSLic5z0Az64?sXP;Sy75@!c(H{qCmy{-SJ_lza|2@FY@?l0!&W3RA#ZU%HKWhtu z%^%xp^C#4jY;lROoHq2JQ3<)Ylp!Z1|D%-rT)}xb@KDc@H!&mGh)=o4vd;>vXdb$i zKg4^7mp>vHMK$540-1X0X+>>8^puR}c9=G92hApDURBp;X>~tHwWiZGAg!a5sVmGp zkIA6ig8zlTDz_8hE^B{N0`JT>>s1q@KcJG%M8fqzZB0m0$Sr)S8bdM86xF(8eN*-g zJf5@M07yF z2*i8_H9Z&IC+a-vt^r3fgmrhE=~@yp!(CRwgJ~ruyuQ)M=cHYT>T-pH} z^8#~w+m2szj7F0$ zH~$e3moI1c&S`FXA*u?H#y(l}p(jd^2Rg1fZ-Bi~_#wt*0d03u;J1$50nirBnqyPa z9+$EA&+B26u?r5_j4`5A6Al*6l@;sGl@V~tirKuI(Flt3gTj*UemV!iPV!un=%v zBE_N(fciGRZZ|TLyS}!oqB)$C_dMz+TUxsoAP{^_1 z!1iLHBF*c$L0(5ZaSdR4s0T=RL2ArPOjk^j{XZI%blTqFM;uQJrpR|{SyM!HQ$>k->QvbA2cA%ycq1ubkVFya zDcuius2K1T+jPU$QRJ)S=x)}yqXbf7SMZn0qXDmb2Xx~#V434o)1|n81JwCk;1%6^ zm`^E6(Jd4+3$-MTo%xRBInR7rR*O%$tve#0iYlZIZ)dG>{o`!1W^Ac|3NO-7u^$zu;%}zesND_q1L*RKO10 zSTTRo5<|p#$Z#;H=GJ?)b62uCk&g(6@7NF106^mleTdPgq_3pP>V1%^@EP@fo$OFE z=;~boJ=V?kX-SI=Qs}}j2e6oYsbAxH&B~x`Y}f7(mPSZT$~ymuOG}d;ETk^QDE=$| zz6FnXkF9g^jiY>by-ZGK#1a<8Vg`e~ zi^ol?$7+iVvR}NHRtEG}1enO_YIn9ia=#bcV?qqi<#OYSHLZCWhn;aA2*SwI2C*Cp zhKuqai3nKcVU)zMvFun1{`!8ONAp?6?mMtzeb&D;rM31KSqLDc%b_z}y1n{shmqIr zic0VlIB#h4j7P!bhK3a~AJX_62c`s`!!j>EMVRh2?Ot@_#{5hmXuf@GB|P71n4Po7 z3shFq3cZRan^MDGI(KIxTRBNxQj*jsfvgNzS`kPZ5G z`SSDQXdB-JlE0?U;pP9pE@6LYWW-bS*QMo=XDpD2m~|j}0{FQ~JyXjnQ zuFNh&=yi5p#ey>2kI}oYTM|eUI3}~-%_A=BvOa+&{h&b5k4SIqoctqc4G9=#t}m=e zT5k&{8(JCEy7mNzF%jW+dHRj6V+T^NC;m0Dw7a{UzQiYrd{?X=|hc;&t<>M;i-7e(gh-Cy>smj<;KHr zuN{`IyH_=4lOUZF&xlQn;|mF_KRGN~A7TvCSUb}hwqmGZJI;(q@?u!X)?3c$SmJ*T zGU8J!PiEB}xNpVsxK*{_!v}e40k6yXCMSoNaX(u+US!{R;kxjv>q_Tl2_`+2QdgWBHV{zBo&I(r5$7YnjT)HQXsn2-zo|PHjAKJs53n zJL%_?6mPqX`3_`3rVn@8X#hfaf>!j2GN^U)pN(g|PR|+0ngnb8V{paB&}bRuIEL5% z3p`PtMVpru6#*{5YOOsPuXAi~c9njH)fl|YU+N`)0!34~Q6TO0hX}R0=Y(xw5fIEe zro_kliGk>PXEeE1wSOHCJlQf)Xw%IO#QrjoD%?XhgTZ*|c?jNigDqo&q9_5Y$1#|s zXHhKjm}otMiib!jnbCj*B1XI0)}*hU`dd8{AaiB4-Rf51V8Xp?F(A?Qs*E1y{7j)( zizRg!kUfHl`HF4EpEZdyqnnHTcNz-!dZ+*(zkQWYM)^nR8jKT6qtE9bSC$({A`l7{ z`$@yjGf+UefspjyW{V44=k~j(;y>Ee0lA<3B-pN#vP*o1KraIebc-Yq^UH9U)97_A zUx&y;!Qta>i=Xu;ss!y3W*UlAy*LGtwpDoxQ<7gOD{IWq&w}g$?=p_!wK;85nHj$hnGHGnQR) z^SAySMX!Mb{FghAF|ZiUPBAbIdqdQYei1x7 zUQ?IztR3&<;^NB$O(nmc9pwnjc|A&Cns zGZorh$z4ILG4Q`Y_!Qc3bIE_@jL4xifBO~PINSJ0<>M@UF0bG{Vvs-y%y>fd^3 zkRyx6Y{4?Ost^o9dXMKN0IY9Bph=+r94)b0v#LH>=-RVf%9=U&wv_oJ%gW(f{PV<; zFdi@Z-+nQ(Q}i4GF>e6^h8rT9l1w4P#>U2H{-p^c3eZ^fzVW&K$;MHvV1=ohH^CNx zWZY%4_3!+g34rm~fA`v-h=@o?LO_vOH>mwr{`1M{N;_iOU%+nX zpb3kV&L859Qm`h^v~9`=ciMK^aguP7ul^5>(32H@VYep_Z>ag9=PXn00i!J@pHNh} zSg}7LEu{D>AuUf8r#7IR8cFL*(s;6n%3Q^V z=VyZdicTX-S0>bBaxc0p(7(rY&(BF0hI?V2mc~dwI4wyTHx7EX#tH_xas^qnB2zGL zPK*0SJNwdTH^_OEWE|3nkNv%|vf$X#!NDtvOg!&V%8&JI!A zfG2InYOnpq`Jiw>N1aboNKSeL(58k&H~QAyDUR>loyGbSJaijCo&#XY!OFVkh|s7w zsuZOprz)+(k^5|yAwdU&+|Lz&XBADA3N}j&s$1h)5H(5kzHq}qEQn6~aQ;=lL>>N5 z{VEZzI9|DU*uM_86xMgYpet}JrVnr)dOiIm)4#H~V__P9)kN2Lai~qzwxWYa-Z|Rt z;6y;#v@os;O=WQ*cq!zcymG%l{ll|Ywl2z^qg71O{2KRje703$*isaK7IA6x5p{yFIX2@xu`HgBAYx-^v^w$oy`-sz{P zd6x?~#*ilHWI{X#D52reHSOiTsb{PYG5>_!7Xos7B$5%%MO5i2Us~HoX+X2kQF?A% zJ|Nk!4Z*pWFzJE2J?5iGg8y&Oyfgp4u;y~p244cGSin)2*QwDBY?`Rtp~+NU6b??m zGLf#WP-xddT=Z<+fnCq-H*7&%7+EUAC$_K|XN_F;fxeb>2|$(~qO4QOmmbYAX7kAT z9KpYN0Cn=8uG%{;pU3?JmGjR3n4$asllH&2rCFf8ygByO0cInZ-Btk3eO{@-OFoN} zJ)!T?j>qseE@t~xk{t)7f%@wrJzG94FAsy-z6>4?fl%`oRN-lSU9r9-9{Z1^{phdv zrJfU6OHz%}L{;I^>irh6s(MrS+HS10u9A1~{0J=b$tSkzoUEWSw@*otgRT0WXJ#%6 z2I0Gr_^$FvRr|~K_gCY0!COSaz~P+HT}yONF&$73?tVS{Vaopc^!vQ~r{U%VfkTHB zSN&IiGIp@MwUhT)8ybtv)yq`sAKIUIaSHyWbLlSUu(*_FGFgg3H3ZcE3J?`%Zc2zr)&;v#BbN^W+Okw-592^@jc5uX3u-;+Njx!VD zaeQwp<78un-BQ`G8qYgUkbwfm&9bv5=h6V-pW_QV^&N?v2i%#p{pZ`%sd=|+9FFH>t>s3kerlU6?8Mh9c zh+>i7y!J6KyuJ@7r}DpQTGjfpBLwItX2t;2emlIlaIEX@PoD#z_>apY!TSG!S}-2N zXCuA}DY*JFWscl2bJl)MyljtQyJu&-cb$55?l%^g!UW1?MX+TCecR1;T zFx5Q4EiBagtJ?Nv-j5vY?&hpfDg`raza_UXoE{#JhaX2pS$zkKnxxA<1@je1j0fc8FlB{}^UY?pY-!JNI;V9Z?vwIA*w;vtSm!tEKMDrr^w_#xX(`y3B5#uEso* z>hg7Xrf6}hX7;Lj=TfRha;{@SjrmM2OsP(#=67CQ+HW55;v5$(s8*5h7ft`dr*p3P zG0AUOyE&U{DzrgaUE(ELrlBHXN{~!PPyBQ3uo&wBQyEu^+()jr*C-dI?&g7qZRhMa zTcbC04>j9VYYcj5NCDlYKCYfy%!(7oZ|fGNm{lg|O+=+efg5W6#EdU)B6WC;*i3qQ z7ejsI?G@IptD*!&g8VB>vv=`T3K3K^G#s&SS0p$-=AC(ztr5Hrl1O6C9KJsrIZ-rW zOn+dXhS748Rv3)K-m_on+1kQcxrd2G673u-eIO`TFe{`;wW4(ZRpj#;=M_Hzw;d9q zr$GUUMQt}8S$Gx_X4symeHC=G3X1vSFiAhEUvPLYX~2>*%xii%+c~i>Mf+d8>P1|@ z4ajuK!bSQS$L@_ouDY${@7(1fBWRHoy|ixOoO*xnVqoy`2JNNyux*YmUn#?r+Eo8_ z?}Oz{`NOjvAmNl*&Obk|%ni-KR;(W|g-Xo>VANt>F?8NSaQ7nWD_`$`yUbFW#j)U&X?v;`fDyL#a)b@)X&ZO7%bcIvLCGq-iZ_veOv|z zTfW+viD{vZVro6sb6@hzL+ciipxwvG7l}lN!=&f?^(|H5L1vO+;;F++;}lVxcZpu> zcCdLQ8c@?{yddJZV~95{G@n6>;7x1iKafrmP7`Qf~y^ zbrc|q9qt5IG@*%0cQr#pysTTc(Lmu0expl-SKW7F8e!4xaZws!k8PdTz}aA2^!EjB z`6M8qsC)#Wp6Y!@or`oA^}ADD0=tB+E4oAm(>7M7cpdO2DG`z<$KZ3e4yw4iR7*d8 z!;9O1iZFLyxO1CV{)et63I|>{s<(S4hUv1M@5LFgLP&$NI+C$Emm_U?6aq?L-1cE~ zv9i)J$VCg{I`B@_R!mMAtf;G($8%Tl%}-Wj%t;wBZkHO2fF(Pe`~t>y&gO$_Oa!G{ zk3KV+{rEkXHx+rhv23A(K5Ta0EFOx0d)w-U2L;|{k|6z9d%EB)m7+2KB!UwBLG(I* zXX^a@UH+VZ=#)%)Z+?l;1HL?3n|6^h{)-VFxna8+xRnfm&(H6Fq9rh66z0yoJYf{_ zN1w`N1tPTGBlmBc+Cabf`$qqRb#ZAr-*uV6FU8sY2w4sR#q@YC@?bDq`3JlAp!-HE zRUUC(W(I=~oZ~)2x!?rhqAx@H6@D?ADPym6q%D}mwg$^x;^9_K-Je#JcCoL-UBZkqzWb;U- zdyrI@TrY7*ud#`#O*{!t{K_Ua{<~osu`st`4tR4<+Ro0lmWc@%{Gn z1AK`z0OeKH)392mA+4v)w@MFd_6&k1{(fHGZ}GzTO7ug{;}W&3Ud~uYy4?n~s7Oaa zgp6HU?}OgMr?un5_h#KMDgRzMOL{rfTR^c78@g0_c3o36f}+E^`BO$yA%lKgJWuNN z#K^Aj_evE1=wa)8L^GdG9}arr%6TL3HY&Bg(#kzPS;&0UbV`KW|20o@mra}o61|Rw zd+(SB+>Dy&xvfs@AC5IJY&8va^%mBD{#(*e4WG0Zjb)IXGwz*WW$e^nO#GX3{0|>z z!P9}7AUg0EEdv4qCNDOsr;pZllrLrKGkKI`hib>fYc z%kq1%{u;*Rh84`a4!jP+JBCffM%?Tgbmi%ZQ{*&Y;_Vt@`x@eHVP1pD$SK7nTr=8P_YX;`llE$vb5{Nmi?&J)K&UkuDtMvog>^FfEHaGW|EYF zKR~*2WkqMf>A3-L-e^i>aGYao``Jw?1K)Pxt66%!;GrPtkJeEZNGNB; zZR8*3G#J5LMU?iW3-#9`|XdH4=<_xNE~YFKTu0mB%s zZF6yOG{)gzYSp%12@m`ag90!XYf*hc7uL#BkPx71;lHMQH&j8;nyDQbJlfFJbp6JX z)(guVdgobOzkz!HTRiOdW0AH1ar*Yeyz=LhK>32VAJoOvsKRwiPbN$2%A|yitIFQY zH#o?)ZXf$0^meRa&U1nK{@#ZptJ$2zoFa(r3BFgwS-d*grCPbgV_7c0zKf{X6W9qa zYW;%J5fy1>Ev+4qpF4!vnXF6JR(LCCu!$Ic$l<58YNWzo2F_!$tSx1b&j?FT1^cATRiI z#rNu)p8(@gg`7KrvhD>*hN|#ZQ}nYC)@8xn=)Pt$ts}q^*dA?opX3s;9)LG4UyobN&+#|{ zWMZf1_{JVkI8+R%%7rT1pAwuP84%iuY|I{-PnT$cRGob7=+zUTys$ljwNpXxLg6`X4=yz| z{d(V~2N8-?=W%kMB6Vrq!;p4qOxTp?v-YoPjvQ)LdT(7_Bgd*<_K?I0y4uF0Z84?k zmhgh!ci04(b$2`7dS1Yd-(>N({6rKY?R(m6Y@?5o$YoQnmc3wq3XUxa4cPEBpzF3A&_(Zey1N8xzHKTE_$9_^=jLTDpe;lG^o56P4k2e^N{|lX`(~e@m zerc}p@$r(8)QqJWap!Ydwx^z%1{~EFEnA@~UeDV1o^axzwPF`s!?ho= zia{pH4ojxmD57CbkSYAN);G4^4Ojlq6R&`#w{51vbPGNP$j~0Ykh!qO>qo$RRjWS~ z8th@PPFbF_V(_T7H$dIpbx0j_vSf?5Y91PfJEf6Rj|+C3Xv%QOYn2Z z*Cj-C3{l4c2S;Fa-3$Ow1qW>*UH<7F{9Ywi&j#DBH+L=otrA*(e0wvNB%3OT8?d7c zA0iHc94K`_%DIn#+V`sQ;rIudXXh=gRuaAR5qAwIGGL1WY3m^_RP$TbeI)5X_Ij!2 zq3>f0BJ{wu*IUmHao4ufYcH}0sDH~vfv&ZWd3E)3-hT!;BwQEH#}-GWznu8rGUICN zntlaR*`E^=69zSM9=m;b0r^&c*tQ!kelUI{k(fhOQ+y@a{dJa=8L}{Dpg9DWc}nk4 zmz2`@Zd|kV%;rEZ|E)gjw^IY8$Mw0ryh9x{i3LhgPJ@H_k}jd&YR-JAK<1(qYc^OW z{R>ZeFps%uC@*fjaAUL!URgw`{41A7@uQya+iGx=gwGQ@&cYP21=Bltn!d<1-O$Zy zr#Q+fizTtguAa5l)R*i*^XIRtHv&xc;ZkQ;21ryboIg;;Ek7poO~G@ARuyo$rbWG` z{|_bL0GB^?sCsUo=2}LP+USYVc>H{w#@f2@VkjhcW9a-*X>j|yoU`W7r1L3FsxvnO zy)9mBAHIHijNihI>&J<)5b*?v`JcV-NITR@S@?qGZ-E^h9qYQ-cP~8kS^KIczBj@q zh8uodH%y~O75dX$oiFLD9*>ZKMBmKjAD1^KF80KeEsmPx5F1w)qZ+pqh~JTXhx7-x z&M?%?0T$877qUZ9?>XkB0gQ)DKLm*S9}TT8?pHlXy2z(x7R1#f4+^kD>95xq|zp72VD@oIp{#H&5moU=#3hG{1U^ ziufV#%d$_$jEuAgO$)Yy8*S*m%*tlwGNh0f{iEYgfxi5=<6aA@awhO!-9UwLctvi; z-yZ}8pq+@;@;rFGIMJwsmK^@uB*=w>*TD^<_v!IK7(mJ7D%D2Z;J1YeG8ZQY8}tn% zyYF-?@vg6wK|mt9b(;8y9JSbT5wq2y40BJ5Yel{oU7r&64*i>oRA2N|=e1F~=s_|* z|DX78?X!KIfeiYvYY`_%KB;i)iZjY<$VnL}-N+E%>rd1CRp$gs#cMAkB8J+_()#(; z36Usi=9#&nl8Pr@0f>w3r)bE-qL!z!N0N%PUXZ{@P%VY@OzTh4w& zDo&>-Ry!eJ{K%q}fV@U^m!ztKKhY^l=W$A(H8|AVyI-!w?|N#1(qZ>I(z)4r$FS^% znEs*K)1{Fl5$y~xG0j8!|wpQoz75bEh=CTcrSWUv~o98Yi)aSwueZN2n#Qm?v_cQW&#}nBN4}n);|`pD z`532Q`Qnxp`a6NL=Cw$|`vT6+yjns6QM9>BvCaEf4sNht?n|PDU3YQY2u~apEm4BF zhmTZBp5M1t33p*_+Nn5_za2hUQ{Hd(FUsVscKUZEa`V7)D^cJLDQqP0Izb$4e7jFH zLQuNg<#|>rel4 z=?4A?Lc!aM2>4IN+w*xUzMs-lB(wBDJx+IO94g@U^cI;Q-L&(h#?M+jiNlrzU%9VnJ)yjQE?0%~P7OK!(DdH!V^gW8OLn|ps(yX;{Gw{r zqVAEW4wyKLa!qaLgja_7F%;T&KB|%uNs!uc>VabvJa13-m|UGA_s>U=RD^OkLXdN{Y?a$Y?vwEff1kD<5dPen%LdOP5 z2fm!}+m3_fu7lQ0V287GT+(X!0s8hbpyYeA?+*yy@Mg7TzgQ2R7?mRtZsuUe4m-y} z+LIZw>PlcbpYBtkEkBeXa(ITkR z*U0Oeo6YpG%`64s@vmc7TguIbi?89A?>tZqg>eU0SJe;pV#;4xPW{`wZqQjQVNdg| zr;oPA!dthV2`w-9?i{x|q*S&zxp&CPd)qHCR>wHFxTMRQo-8C!U9ZJFJj81-^6L@J zDxNl)=>f@I)7)&^RD6CUEX&;I(7>=E9mkmV`$t9V=TBFGCsKTywizh~h2tw5Jh>2* zmCOZ1+;!ZFK889IxwrMAd8e$^8)eRtaJ>Sr}l=dlwcHwj)H#y}mk{~cdcsP4_O)3L_p4C?P+&azy zD;0^1_egtX_Fa6bEaEc*j&n8cUCMDvGie1O!s<0jk(ajIzZQN!`=Z4ZYmp~FgSyE& zZFB1>&Dv_se8oF{D8T^EWF(P5ArH%I6Sa0qwB=-?NINuHtTYcUE#YoF|T-$;{?i-jDDc<;ir1@z#3r zn7u@>%o$Q@@lfQ{bCTIsZ2iKQ##Z5It04H-T6-4oio+l|G|r>D~TC_)g|>+}m21xA2OS3hUvy@Vg? zVjDWSHzEfC@GJbUWV8k{S{lqM)O!{i(4;eRq<9ynbos|VNyjz+XjD*F5rJKuQdvs; z3_iU6{prdyxH~f-Jn+0O(`Q!I>T!S5`p+%AzvAgeu;Be#nl+ zSBX6VTW$I5gSS4@R!Ig3v%pWHh9scDvs=`6n~O~(qNY;f;&2>(yA`GX`~Jz`?IlH> ze$LZt^ch{?ajaS+a=SqInEjVa;12ao*LwEPu{G?~3Ym&N*4zN%Ht+c)Kh%ffun(Z3 zbtl2LBb|rGW3(wrQKx%*MqcnUR-!lB$Fu#iZ*rmQ-Hr>3y`(u(A_|}Acji8o`Q6B- zx-Et|)l|z$Hlq)>6c(EIfO;iw_Zo|GqxjVkQ)o(N+c_5mGAR6N@#Wq{)*BNCY%OH9ogs;I9_>f9H)9HkHP!{pQ|lU~8;( zGk8D7YtdsGrvF&O@=SsWsddNHEx!OqS5-ym(I<(5HyYn?Uq_ck$`YnQck%4OlztBfrV2EhMt?_58e`YmyMZJdX~YzWDm6Lb#rv%FpfFXh^yB6G1quoixZfvm?b$+J8?k4*%CfL_3gkBx ze9GB(Hqv%@Ckc*1dBR$wSNRnrM2PzOo_0@%Bs9Rzr+JFb_J4 zNDk<{?(}$(B<2`Hm8d9v-?0Mpz?E~J)m9jfp(g{d zsC|tt|6g65=_hY$5$8L((D$PYXqKDPa+{0Z+}*;4r!YJzf^L5?oZ<5l*$X37G z5j#Tu1Ab0)kGME^p1;LWbtiD`a=pdUE|~OooZL}TK!R5^TT_|2s{(4r{s-Sfwx5wx zAtC6g2CGFM6maauKDRSqSzdwp(>Q*6#Yu<_T{P^17zXM>0DqDd^CjuT_MGSY}oSs@%xwl z@0K6o8PYo7zsER`eJQ4pHJUJW|1d|JDq)6(;Prj`#$XCVK`o>fJ&7j00~^^C#?&ep zH-o62>hNdgXeC}xt4|&U2WN3 zNDNmQJN9m3wnk=UsWdGqi5JBVk*c6{gTPOgT+C%`=UdcD+=$QXh}=<^>wTN^W7B{H zWd=X81KFv(7jw%@H$NqxIfyE~<57^skolHNPOHw`UjH12Q0Qm2PsYRg>d!SHv9X#f z63SUIam1L6oTowCqAd=RG+ z^S-@k_I)gg2{L2)u=V!z#L`_d;J7`6ZG@ZzFW8Vu6U)W*3-~?rT_VoR5+%i0WFmL@ z8oRC$LAzP;vu(QYWSbn=&xG>wOB^XrM+|4ylI*8l2ed6!KQ-Tm8!6S06blGQ8laXsvf`rG0>rO`y_6mFciCpvG5dxAok} zb?brOlB`Q%&GS*Pq}QW=MT{dfgL7|hR-maT@^DXr2KgVU{EH1qNNI?T)x5aLkD#{O zB{j)5S@B}zZ1j9|;CI2&db*nJ=ZpmJ?&r)3 z9DX8nU+_h0!vgoTO?*w^5KCK-3anz?I>s`n5{T+PI0S7w}NLZ6|v+=bdv8UB@MwO9c-J zr+HUT4w|yw%GAXPwN;+^OhE;t1Nr}!CeGUBVe1T6#RXap;_T)oKyrs<82SQtqU?wT%EG_#sx9PvEfxiRX?ntu%AVPOUul_u`E$`6 zr*JiYkD(_e*6MX%VArTHVsWz{0@D6I+11+Yz$Pm?V9fp)IApE9U%xgIEz8v|2pXJt z$7j?h4ZkvZvv}ms;B)v?8_#pi!zY$B?$lcwQPo3kTe`_5PlpwY$@m@+|G_VQGdWICKl)cZWeb94a-%c51>cQ zcMGRN)MR^tE8bJDY#ynT9@KsWOWq7}$~`SGSWbvwU~vmNQQX)pKXYA>ACU!`XBiy|qKlJ#_G@P4lL}BM`xqsKrdAl_H_vUx& zpEo(oa)G@{10Z=t*F$PxJtTd=xa4pPYDxR|h80^BKc}&4N3^4|UEsy(i$&rTy3W6gkGkfm-wZd-kKNgziXPaQunZ~s?^Dz(eY=(Itq5o zB6rmD3B7kM-L$tXD^pc;8*T49TWt+HtA5_HS3u~~eZgxpG4;xul(BV>fZ^uUp|R3p zTex*SF9-zl#?19zRSh^lWo|v|V|e4Voskl>@r%a9Er8I)+fDkQ(O$5^VD@`@10on; zdMAfq*_Q41Qz{h>L}c{+|Fss7>RYnY|=WBXZECZoSecryF7^9L{OG6hgIOr3r4bVdGvg`@PYaB!9O@Ct9i<7yXIQ*% z-wCc{=v-zxoH2`{9Jj8bXMX7rZe&OvR?jkAHmvwkgy!yiyuTouDN$Fg=q`SLwsb!b`|5l&(``-Vz=di?~ z&fas+TyxFLHJI;`g}NwsgD;YjMc*yT#Co)S8;S2ne;Ox2@xAL}osjbxQ5Y zVgJ~;T27M<`aq{yxq}ihW_IiRX6=iCG37(vg0+Jrvq(NnsTZU#-Nfs_B%Q`Fuj`b! z3Sz3XW6NF}7c!08W3aKHTeer_#Le@3)R`P-C39dB!LAyQqjZ-@KZRWHd6&2Z_N-S` zR*#PA(BIvjHX|RF_}=XKXP2^Iz$LvUZ`}7K20a@IoN0;Or2r%7SVS>R|E0n{%3QkA)a*e>=cUIYdfr zcD3Iyo`(Hr!llUNBKBS)58F|LutCS-B0s`rZ?o0B!QD_^SoPo_KUV3ma4||cm|A~) z5C{$Sr;5+D>kN0L>Z8S%+Q}y+K^t(@e9s?UbI>yigxASC(zSx-Dy!b0>&;Z2b>Ss1 z29&qY0EQQQyC0%1<4g&Ihhi`8UPnxB6I;7t;$!!V6El5iW3pzk^~SX*@$-4XHye38 z;%zt0?zG{l73Smb4GC(%bzgK#zzVzKsK5Gj2vKgNNuPQSuV~2czlHv0YfllwqtvhD z9byhY0XOmvaU=*k-h|JxnZT8=yv{tA=6?TF1&eLKQ`f!_HJee=`wZ{{kun-~2w5wU ztfr&MX-*r}RN3a40(K23KMb;NiA~^4 z?old;UCCOQKOUD7+TVSe-V%+BC@8&4NaS4KDg|bv$jI|F+Cwwc zBVE0A_^>!GC;pbo)8<$0^wD^mbD73O!${y)0=2>j~-ROls(Wc=i+m4R6=#~^gYCc|I&IYWt%OS zzFwllRCX1C=-jc*T!w;H%0cIsF=eor6!}tm!n^auHT#@bpB2@?yRYH`fxBtx8fK{( z^gHWOl|R)hgGi@uaypU@_&smMTohK`o%=dX6uEdS>e0kMWmHuy~QsJBA%mp zyhP(Zdb*y&RjNXI?o968k?ub&|4>ky)_+zv^ZMD8*OX* zMgLTgSc{lurj$|jXrjFEh7q?CWQAHSWb11d^_E{vBfL10Tgt3wBhg@V`w<{wLHD07 zzkX^(U1QrOGu#^e3QV*uiH7<p8V^xL=vn*Ht*a(aMvUGgh{Y01NFz_HWqIE zr2JwwfLN*zv7En*Cm0`1zAE#$8Ps2dZ@|6o)~3GTs!GgV%K|&ITXMtku1EI<>6=PQ z)83SbVzJ{om{?eS-t-ziijt9;zwVT;+j?92T~Jse+T4&}N^iQ$nY^0T(Ob{~|NYy` zKHRX=_3wVtLL%9QE}~)!RdwN|rE|iwcWGgpBJ08ARgUf9v-w&4F}*VrdYj$`GcD40Lq^%53 z+s2nf_w00lU?WiRCZQ+INd3uu-TUNz^np5}@{-o(4&hG)*$Cxx!CC5sz(B7NMQj*< zHu^XT-@?i$iN4+Z^q88_qbmN z>eFEwC6r*xFFK zD{G)vrlmG)udm_bXAaR(_0ROL3+PI|IK3-y)+~TeC@2b!T7F7xJ+Am@tJCPl7oNyz zHgqV_K66Va-~tVdDO+^hFCf=)O-G66-{rbJ0j-sxCxqb>x5T z##ilFbtq^b%HB$IgumF0>9%Kq&GtC4%LmkKwM3ou+u~eq-(;$mQUQn{COKP!{|_=q zt|{Ux`Y`nCyM%Dz9M^>UB3yXS{np;%I%sHEFSP-wdWRIL@!n?tZg|;D`XNdt1(L`0 z)wx<6+7L|*y2DwzLQZhngqd55B@f5q9#jT(_stwkL4So&bK9nlY|T4S|Hu)q%ZCN} zd5YE)&wNbEyxNt!y&x}P6bX28^su-tbjo0UaE~V=-OzJO0>y9vKDbqT=I{Q9G;bC$ zUie`HY_UIFQWP)#KkMTDWDvkpKiAXdis@gFZnr+#2kl2)?+V}Bq~wmuZekI+1r)d| z>_Vt+(3o;rPFAE71Vhf=U2PYh^J!3i-!1Hz0s3X0mZ2L_5DE*30Xx6-mxjQ~`QSmn zDwnhJJ^+0*A*RcqrN66XDHXgwIH8P7W22jx&4VK(t#& zhNW`)l@b*nz55T)Lrx^IwKYIGH9TR|`pP_|_N}Ze=sfB^=Pp=@R89+mYi&P@D{OWt zVp-g2-1~%>*!F@M#`$0${u;dGxxC1Gsy}4SQB=Y)VJ>OyA zvl5Pc*6J1_4DTL|xU~}*a-$R7WE1q-QX+n2%D-Mtxi6mj;Tu@-Ro^=W`A>DKWC4;A z5eP&4X<|DWUKhD)0k%a9TqG6pYn%)F*e|i`q#H{a-p>`N0#Gu}%>>Xr0zCL5e}=6| z7%aBT7KfPIq#791L_ZA>ygkS+{YJ58vlt5G#_sS;@g9WlMSSB~qj7d$jAM&G^a1Q< zj-cpfz0jQLt8cx;i5C$FG0|NI-(?17pGmyD7bNdNkoiPS);gbB%)?JJqHj;%Ubo9M zQ0x7b*6CLRVsZmalHmVpLOx9P3%ed{qZm7AYIdLa`A&5}U7OMI^DA`oAFP_5vFISG zd(cMap~c&#uRodDHy#A^K3VhxA!tac7~@R zw)8yt-Xa~2)_ygoC3IgTy(B+=989-&-#>w10LF=I{aVS|>MA;)g*oN?a=>J2k9!>ivplTw|_Z=)Svc*vRlrqFEOeV4?$n#`qZUq!WC@Q&Sj z@%ou}lLWF7T0wBifisT}(rm)Ey9fSaG*W&lYIn?-;8gjnwtfdO-zu5m;{%dHa4V^s z0V|kW*OV1fU>#et$I0{fHs+5;G2iaCp3w*Hw)6({=9{|WgG!ZN=zwK)z~Z!#s3Y$8 zd>!&P`AKGx$FgeN>)Wd{C&Orwp9iAklgRH8h8B=;}BL9@}c1&n_fUY#GTam`|UF#Nx|hG`Xz2=TLF8IntY zCg02xw3;l+jI5X4WHJCz%1abfTH9CATo|H1dC_p}4pf|HE>YzV{1 z*V#C&vuewNjLkWKBn>4>#Ue>{E77>bGTNQF!*?2Z9win`WhECa;~*rTrN#7$gqJu( zJNT2-YqKw{l~_`r>FtpZkiYGTk)lW7OfH_fRp#pnO=#OuYka$22(mQul0c}$pnG^3 zt;^5VaI;rZco7oOEvC9kK>GZH&IP|DoCDNd#nY5CvM~@^3aX8aT)O7l+z~622`Q75 za3?<3h>*ZS=XS2;&8tS{GAWjHRB%^?|tgs8Y#CSJOoo+$c|i6QVNvkk};VaQPr zI(O**TCE^IFR;a}7%*8#vG=K->q4%70V6+%Hb?TG*Rm#1DoZDHM#hQ{XwysEjIy$3 zZ$`K8{Y8F*dW)VuCvlla{Q^S~H6M8F$ABNMvL*ZdNL0*?chPT%IOHW68M(T0;W(H8 zCJ~f%ub>#4PxJR<_NoVf#9c6h8ikSSqc>%kye7fE(!vCkbW6RO>j%+Nu|By9#Sd_o>@^OG&o1LvmGjY zh81J`UBw3c3^B=I`u;mDaiGgZ$n5kBN@|O~*~{YvEt!1? z5L_Tne#@FIvc05%& zRnWq%G3dEGE1^U3y@T+?j}waArczchBAzbh+-bjc*IdYW^rY>#EtPC=))vm-x!pm2 zo?FLKva|Ixn%f=b;bRr)0=(l>1Lw}c1RLhl3s${y@aEinG0gc~co_R9>)<^DcRoAs ziSVIDH568K^!txGs|xZC+8ik+?0g(1T(X|dW1vKuMr-i;Iqc$eV(4@U+7R?{K(LDV!4-ynM^@!AX>9@U*TWbFE@&Nv*Qb%7>YUeGa~URfc6I;bmIagj3l^{LzM;&z^uPjT z&Hxs%xeQT7eemZo*5f(UP6X=T97yfftsD|X&`*}=U2R*BGk=^sdSTh}vO`S(FC6a` z_|s`r3nohHxk}Q5qvWA9X!LAMmB}0sUi>`NAd6l5owon<&ID8W%~2yQQKh(RhUK&iHX-fm0XNcVA0|A-^K-+&IPcq502S79QS@{d#H@Z^Y!`Ia=lQScKS z6&$q8A0(Gs0{gpBcECU^0ViFwAXxxIzifxHD4;Is%m$QhxO5fpCHdY6BFjt7$%ka8 z_Pm>nw#+_Yn1|$fW#}%RSIZ?bjBQU87dKvh#`70`R{u3vWPYM^p=wLCmU~FjD)iIJ ztKd9QOz}=g1VbWj-AZ|9OpW-oC}JE=h+ zbg=@?+k9a+bTmC!NB-MuuH6%fh`hQuNabFAE3E%Qat=wn`f$(n{Dj;pb8Bz!T@ygIBlvKovAQvo6rJ$?G^R9dpioXqHPJxhvCvoD9ZzU@M8|y>*O%0v--m zA*HLMok7794qJIL*Ml`RWk#9??Ur9Ema_cWVb`hf#?y`Pi`C-9ib`f%r&l!lr6;|1 z)~o082%-AF4OPkQEPTAq#BO^jf>w0NLFNCOi2wa)GY4?!zbwY`j>)Lc7Mq<9W~+#X zXK-#cEU8g(`pBFE|Vz0n}CHWLiiPztjef=Q2TkGA_@yFOvG68ZBjS!Mma@=%XYP zisiLB~< zc7SOXH zABwRCa)IF>Hn=hPrk#8(xxzn$k?}Mc0q3FPB{RqHDtTWv$;iE3S{DI-kLhqUcJgwQQb8_&H)^ASB z^o8@!o~mW{eNXT>TyRN(iTn7W-t-nWkGdZFFF6_F4NKOq1%Vh-;vAC7x+;N+XZ8HK&^N z#~@AWCC;ZIB$P?dO^R=J8V>9Cpff*S{U56};nu0KrB#)@Sa%C2poG|JH+jIL&9hlz zDq^v{Ua<6xJgWJU$A*@L%SZ9EDmPjeG4ac}Fi@7HlGoCoL>WcvK0dVv)UP@_0Bje+;6v5eh^lz75 z!Oodrb4-XaKBIX^dtC_q*sqnP!G;k(Sj>~74(4pBWmY^)dfYp@xlIvQ9CadF5rlKk z$`vh?wUgE*Niv$=iFZ2-Y#=qlH2RNX0`~^d-MT8}Hq3ksP%!nqyT1FPLDDkS-poZI zK(lO5wn>pX@_k@rs+7QfhEehP+y@>Z!J_KqazxJ)i6-wPb)xK%gRW&RUaym1ozHZw z`8tF`Oy*8W$*a`C(@I&{L7SUqK$l6!jGI$i=$Ny{m;`#43GG-0I)uRJ4M@dwjV8z# zFYJ^!7~kZQqP*$r0h;Na10^pr5p#4YKBC)PD}$c9L!Ph1lp%0N!0NAZkSq&I74md= z>TsbyAlj~#&OHMj4N|Um=fFQVwgi@-?xHV0rC;8Qb9oq}Z7$dRRLBjoOCM^U@?@z$ zJvUzjIWALs9^ZKWll;_wN^f%7_$5_Qf``x98N;8qo%4LRF=jkB1V;iYT92qDEewyO z%fI$=yzzlv4%=qT&VdT&B;Q_Lv0t~+&LQbR^MiAxIvt*+`fWf7V>C8(rY0~1yU@$3 z9sSmMK_4*O!0~}5yP?b(Pz#{Xo4j;0NVe!cVT`Kr%{#ec7uU_;VZu0AueWz(ysnNh zu8#_2&c2d<5L?23_txj&&Sur_aITlW`R0*r-A4wOU^A0lwh3f+$obI}$j6@x8_V2; zn$deB5OlfXBH6qt>a*j_f$W^(Tmzgp<q}+Dld4}6+ z7~psB+1BlqG#sV}#r_{Vm)*<(*21c;yOJ@(Zge$E^}UBUzcTUjXhC`dDNmBcxnT-k z(xO~%6|LN0qUw^L@Ms1_*e4!Lrw>t2%iD z90ZW7cbI~2o?GFxU*3MM-~-@wk*Jvjnj`r6{#Tg+R$@j;q5ZkFMl|lN zNC31uIDo!+f7)9tt2=u$>mGD}cWZ&rg9bV!)!d#au2Fy;6#h)hQ4vpg=_4MR zs`YeBHCJlEq$PZx2E#?^{FH{KOI+$H!>u0yZnSh=*gM z7M&UinK)LQm;gdeS*3w?l9Qdu-heN|sWd2ecJKNRyr|HGzI>}^k zC71s1+$pfUqSc(!g5V#v^PwmKkb(6-)sw)m_Avr2U9U7O_=g$E>FH`~gckWBu+S>Fz9?LbL`wk#j`O=f?0rLT<1;@Mdr}H=cMs(g; zAz?~>l8MZNrvvb-i_Oa$S^pIjcfXcP+xYP%-c-?ttm2)1C=T6^93ao@1023~!v-&r zes-%)GAdaoy&CEDp1e|fj{Arj*#i#EqmWj-6< z8;V5E-=}@02CWSSzXF-L%q7LnPeT+@WilwDLkblwKH7YY9x_-wy$6sYu5Eop@5Xu) zMA(2v5U%SX`h%pSlSmKop^l}+<~Tc>Y0%0B2f_YR6?0(co;mPpW-h=vH8YpmuuJrQ z5Af`)ms{XtF8O>26%(cf5YG9@u;YUH%`dG#cgAc85-lOL;$HypB-&!sf?=WkIT{r$ z;h{>eKifFrGBW0W^?(B!qj6b2Z~y$jdcVzdnLp4o7geJ*A&NKzwvd)2N2bVb;#qOc z@G3HJ6JxQu$ctmp#QYIcM5G6tafbULBRV}E@f?MQe%;t&TofP(kmH8}V*IDXaG5zRGJ zSFH6AR?{z{qgM*njKtbyRn^7+6H(Un2ov3(pzENJn)ce;%X3nPlZ@W2s0vU|HI*rM z2v%ar(cw_b`t3*Gv0O$by@jjJ3#a5ngx|nBOY*(JrpX`Z!xtTWZE_4V~bPpw=wdd|= zCo_JE{7KYislay@WD+gt$dnqLP5*PZs6j-rHBHI3OoLVGq)K^y4^f1au}N#^L|8Pz$UJ)6QPZS`T0cENQ) zM)0>_H*i@zJ$~%6Qle@ z_gqw2O^tXsLi*1I+6*V47CJ(%MMnb{h~hK@XvVSvSj>LB299FRs7q?S;Lsjzh-Pl_ z2y@PZYvqfh z5eX^u7|oIj9(}Z6A?#g}Szf&SG_?Go6vdZblhE&>|3m;qNj|IqQ5H0>9AEJbmwfko z5xq34Dw7$lh7k-vafvt<_{P+aq$%MVKi@q{d?OT4`=m8)xj<@Wjf59B$w`FR>p=vc z$@kDr;|yN>yvaYzacHR0XMk|o^ta?%S(+68?dn^ZAVG9T9JSB#^K8=mqW~7Kn-xWJ zhs{|<>dIH?`~Kmf{TXY`Po2lFj3AsM(SjL0`N-Ei6AP&`dUWgAhdjUjrxzfdGV1K? zq(rzWR)IbvJZ;pFnU>&5e1Utl)pik4Kn5H3B|E^(Jgdh~HcvwU%wZ}JuA=qL@hdkO zAI$juQ--hc2#cLfW}?zR{n-~o)Byy%-SJIDi#I!}y`a&yEP#BA1sX9F7G^+U ze@D;y2}o#@cAI<=yAy@5B)|j9nzh$7l&+_=l>j+EoY%ngt`m_Yfu0AYHgH_@)R z0bj-^x^Z9T(c$Q;{672YfrHDIZ|b${5cX90ZG>PpdR7+=wUbAq1rY{lpxUgy>1~xD z74mtS8x>|gg{$|x-=P4ZBm%;dLD4AjaY>vGw#Tplz<%PR@!WB+%`;4|XZT*olj*Xf zn6XMKx^Y{u#C&ROH&G6f4qK0KDQ*>8{7jTWgz8)2h$P8YdcZ5F*`SlB&k{>32(Vp9`#*d2Ym)avg~lfa_OJh3k%GP$7aI0qy`|&Q|BEjN z?*R^4w9grl=;i`5y1kflb%gz-f3!dECkRhAP$u>hgg|*IBnk3;q6gRWh&}>GGGtFL zK1xnMhD{ytE1|{hh|OjDNiUwB7pwst<6Sp1Ij8x?s>|%>x|tFk;BT0PA%-P1vORxH zZmY}YEo`4sOEmv&hBj0BXt;|o%Vv2PGjkGjQ@R$AzE{g6ISqWD>}KPV+lq}wqmLv9 zqoby4?3zHsVw*wHH9{^Cz*<|y^x&=~S`X*!KH@(IF3KTsb2f$=OI+hhxJM6ea5-=_ z&ti&k{3MuQos|29Yq=?Z(^3N*)WPZo+bKR@EqcnF3uc2@2J_+r(op|I@IJ+e4^j3! zLNJYGvXnmtXWM;u6f!9P zsXd(4}%C)`%Qif%dXbGf0eC4d=KtK2vr$DuQX8laDm!$Ht zCX@L2zPg}IMSF;xr!lZSAVVX<==bzq77?EXrhX zv;|mzF$K@p_OU$eMka>au3c`LQ|m>A_N0v`0t9(b&1qFhA*#ySQwuG-a}Jz5UP`?A z!lG;AB+AI>IGQezc+`3TlApLA$^G}gUoS$f9j61!tPN7g8gBy**r_9WQU4XVCFe_9nVbKtW%bBh)jL5-w!%BQ6kxMmX z=ovS27`Tgo6Why6?0Z`KA$mVGsghy(w1olusQhheHO`k97xnN`9WS<)L{1IqG`uGf z_H}6Y@RYF(D&C|9k?vh|F(;|>xRl|&rNwlN^%fy$n23Hxq6K!~E3uhL7G@uPLZ`a= z=%+=zda#-DhZoY`b7a1APQ2<;8o{fZ6VJAM5V26|?sfCSvU z?hwOs`s_&Od(+S(4QyUuTDeiwhj7XR4T%H0IpQq+bEYmABihySR~E2ivwmkYH#R%I zNeIUc{{BpBUS?75)j%T39sEszP|uWnBmMX(m>d9qkx-gsiR6AYXxcy@A~VMV_1fdt@?bVO70`@Js~{XtsVlvco+RM3 zbNY)D7|nBwb!$#qFo+_^-BRz->i~w(+z(XWw}4TZnICl9wDNpX#LLH8oH3C-n3Vf| zre*vJxqyb^9?44`tFZ5(ByX8i4l7r3e5f$$Scm(aunJW?r;#EDkv4s6dqxZGTVaX{ zVCjL0C{cP*TKa1VsuKy8eb4oiX&sh^W)=NfN;WD#r7z5bk9&h(uI4d1IL7S9-g6jL zN+bKl-D1e6RWz038TXEZXas)!{#^Wqq6zyo=E{*I&D9$fc^u@CBNL7Q_$W5f{vuv8 z!#$g^qQ^bN5iaRa_FMt5ki#t7`jGmWrRL11xli$#WklA>CXHnP2^m=4BuO41wp=jm~VN{+U1e8GU`ky@ZI9krHa6&0Y<__|7(t5{8txl#FuyEPX#?_M>& z+(Y%h)e1*IwD;wpx<$&U#G5==i%Q!}6c?(1`i?7>YJYN{7+Z||l zSBSpK1QTHiQ=}UAg@m~jXTw^!2@!;&I{gpRjH_+`*GhnESZy;`dv^;=By!%DL>bGH zBp!2E=(Bl@8}g$UcfduK*^K**CVu^H+KE-*&NEx4MQ*zmhuasg5vfcJ$myp7|Doel zt4@rsh?7lr-xtS)Wg}!_b4bqfu=x5G$@_`7q~KHZ50;s~PX5L%S(DXjfHjF((iVaA zhrpm$hou7mRlP+8!3T78?>|J#A~-Gql+u1tawb^n*4wj+LIT%fAr^$_uH5$_JsT-*Qv;=Iw07?8fY;zxOe<8) zc%!&?V*;22#truLQbQ*2PDI=(DdRO!!7H}Sa0;uQZg+k)EXcsN1JUkHMXS=mG`}*) zJ7uTL-ipiU4J>udS_%5*iSnZeLHrr?pVhLR@jvQGLEAX&WE%>9d!zaRC32N@PUqUv zj=S5biK5%XreR;=fOf5cA8d^L^pw46k7lzcPs8=S+r1%Z*nO@GxkQ$~wuE{f z<(;dxSp!~rYCAr=h>IjF)XH3?k*KSc+vZQ|uzlMaE9`4z_|dive7T2X@xevZOz|Ie z-rdQYQznd-kUC7E8=UGz49&%RK#xaxkOj}5CA7c^vzP(h5G1&0h?Z{D+4`mcd>AHx zYvlRvK%NLXy)Ea=i<<_7r>N_^!si^EPqEB%u|CbkU zj*DDION8_eEN3UQcbt^R;y1u7y-NFCRjJb%NZYVVoW9SbisjA~CcO!=eX$CkJ7`5j zrV!qULwX)Gec6X-?r4vePyNrIi-=t9FJZlCgpG)rgBso!tu*DQI$M}>)t7{KzlBZq zTFc4FXSU0go41w>_$Q1h2$0azC?*< z2P?6+iqr2Gy9^z^w2q?PbUyGee?9nm)FScuStyMS#cJwGY2WGG&eD)l#Jw&zkFRo zbs$(1pWLVO%ZLDultgOFc*fLmAwE7x4+KlR%w%5|bDU9caowzdB;sZAoa;3%9Yfrj ziMgQmb(`0}`i6tYSE+O#=uWH8ww3I12V1r8|2#03H^s)tMQ2wFGJfNwT~-p>qjR(v zXU3MEBg0|AHH2=o9kQf_D)?Yr0ni z7Tt`4imE7-==}7b84{?Gsuhs}$db>B+L-113H0Kp)wja1`%BQ(%n(qWYYuljbXsUc+!{njMcvML3@FNe^e6Zy@cuoLHxZw;AP$QUll-LL ze0yflHcn8S^RjS(QGk*THFOeDwpnX99?vOyXykWpd5PczCLo2=j}eaZL#s$sGM2;5 z?C@%_{F>hpuXPy@SY-yK4qpSKvD7dg4e=3;ruurCi zr$kSQxrBK3OAq%o^`nQ{7=vPIeZmSKTvGch&5~>e_{UOKa%U2gtX23k`{QCi-KW<2 zv-TO-^KEz%`5;Ox@bY@udlmjzXLl}J<|GBvpMI*-uw@-!1Bq9^UprT!787&@vM@QJ z7Yy-A5Q_c&gro0e!*-;c5C3mw54zT5fr~ zN4f7*RY&%vz}%@>XSe0CqmHQ+g64agjo3vA)&E||qM)rz-;4$r)Uytujdo3xot^Dl zPUrY2hJ+FVNP_GfLsE@^XWKi63kv4~lwWfDMUxXDY9NbJ$7ToW7b4S5j7eSWD(Fh6=tY9a z%Fgw5CRg!u#+!hE{|3!5cwMi_^E_a_26!m()c09qe%O*2stf3aU?*>tf#~*|%wT#i zI{j0X+D#z}8qui=lnT_0_-~n`LSNiyFZ7IAY@eC3vIz^N_0(bUll!$Ri7US|u_2zi zGJmnp`aPGU<<@vCzq@FZj|5FYR2a*}tvEY>C{(@aT-!0zOVN(Ao$Pc6ngiF0+TG6>NGI7L{Y*i-L%aD!n{dOL7qgb~H%^a`uQjqrzy6Sohpa4lx9=D2o9Mbz-*ozXHhNgNW%Sa7 zmXl6X%pyc()~H0Hd-|G!N2$35Z;Xd`ETdId)r=qLg_WXs6Z)V-Ekf`-aDY&p&QZN& z)Uv&DiV4|}xK%y2u;dvbtcBXNoX)I-@!j^tJR#o#KCI$&Z~kv9Fk?P2O%5E)OrqKJ z-SnxffMXzcCzZWf=MX_yXb+Z2L@O1J0%dB-2JFx?xX{3v4+gcos>?|EuMm@>JJ2>h zGBV;@1DG=K!jlqSW6UEGhtqZsYJ=FvtJ^#L7o$AcEwD2hF)|uSf=ffJY(rwGTaz|m z94On!*8~)vd>)lR3Ft1xX=K`v0I<@^QM&J1Zt~Xh$rmWtr1}&`4sNnf-s&&7%wB#dl1sYh~CUh z8an9gMR7q8@sXv5=?{^PH%6i19OMG()JC;J{UuO6{Kp|by54;@a(H(K2$By1>zAG> z0`{WwDtu;=6XFQqf*Z!62$0NEi#LViKi>Zw|1J1H%^z57Ica>*C(NOBo>ui~?W1Zy zi>FhDPFQDl^>J{E?mcqOAV2wZwCCu0c5hDpO-e6NGHlduHfdjNmJLE^wKx~E5zhgI zTI0ol?p2zc6%dI%7KNF+mH$s$?Eqr)4bqj}J|&%T6k zdvP;fJQwdRr}*tVw{tps3z$`UOM9#Q$z%;li5EQ>4i*3Mhlv;*9Hw&{g0(w?{6lWZ zGJMMrf_Vmkc6SWoPPmOLnk(hH9tQt&m+ZHP8GzP;l6XwNyVmXP?Pk4vi?E&t+7LD% z{7|F9kClVSJrd%%Bz3J-`y1W?l{l9MWne^v4oEd9TBU7wcRpo!Qr#X5`81N)8c6NL z58CmedGS?>oodr5?A0@IGxWxiNPB0^(2vQNzfL62zunkzf(0EJ>9k+s zZLn&fEFo}ofE!;v@RpU5HDN4rcdso8Rp1eE-AB%-%=K5BC)=tB%w=r!>^}r-WxT=p zc}ai(At$i7oKy~2naGC)Q4#mOxR$Lj?t{ZDh>;wT69JctJU;XpMX52B^-MsbU7_gt zQ;L6%!769?d{}Q`Na646KS&D{JFQbcrR7)K<`GqHUImzk48Yd z#)nRLkLdN$h3}s4*H zB#F>m*BO?>vz8W$6j}FZ8o>v%^)ieUMHL`yc1x{)bT%`b$Wv}>O)s_=+K~r z)#0@9wAQ88`4nVBBmFPerGbefXEs2dqdd@~VNlCE0*Fa81@uP7KA(2ZpB20+_{#BB zDeU7fB?fk2@f(HKd~@4cqELm_K^JKubjTt^*C(wC=dmzFn&a|GBx`*!;lU0|@eUU7 zJaFtzwdUxwsbg}0nP^hhFZ#FIDLY66M4uVIRgt{+g(H!8#F$^U!zdoc;01KgeNivy z?-Z-%f5Vo!hx=b6F-6J1O}l?vIx?chg&JM>7}j{hAwk z`y;j5yHcao7ceWD8$Pcagc0&m9RK?J)EPARuOIGV`FOUic78Ai=pE%BY&G3AqtN(L z@mQtoI_G_%ZxoLU$bO1!ZPyY4Sa0=FBjQ;(*5Gsg%n{ovK7R&$=}%93fF8!t(`6VW ztkC?~BIVRtN12@}-Pe>0e0jRf1Msb5uNU2yjQXz~%&e82EwlaR7b19&^eOQ`p&Xh7 zwh+_TMqvl>2m3p7?T63>d;~!SfGzx2(Q?ZI1<%1lTC&_|8RD3YaV{TNZ8m2eBLV} zXo@YbuSwKJwqs>JRi$~VlNoS)P7Ih{@0kDE@;Z$g(Ef#W=9p-+0%%`SL6Q3|`r_)0 zeR;f-Ru(CtJuI8Y!0&2fB)41o-R!oP+vqd2T$hpX-vLeQZ$P_qLEQt!a=u(zx9!uT z?WF+MCR)!u)1zwDwrb7NB46TGtHt=5r=U;W%~+tD?!}=!lf^Cccx?KhTRnR?_VRB) zR$ptb9(9(f3rFyy7*OyQeIPcdL5RAEQ!%*PMKf!H6I=%(dL^33RVKM+fnY>*iBlWq2*y zOQG*n?dT?x-Ed?gez}CtV}y^l80bpvF+Yxs zir1&tVZf&6)bIdK406r74_7X?JIYV@8-KvSL;tlqH)rb)c+UyR@FhOHar_YtcbPB4 zu|vMAy-i$JBFBfh=`C(XwY+t0iF1`Uht`~m$Ir;vFB!BUK-i_g4kv`-n}zCsT`3oa z=OWHi;dWJ60DwImdEn6gR{0gsot4{!?((KV$Zfdie*&Nh1{FQMIc%}14?5K5d8Y}0 z{JVkY%8Ifc9mZ^OFWa8vP(1!MxoVHe@}!!t6VL}av~WqS)V0AmeWC_*jgdl)4?B{B zZ8KMc-$hRq8oq-`EPB!q{#g-S9$2zBI`B6DUXL=nPuI9A+8jf}*Jun7jd*Y2tom4( z8rkeX46Lj5;A{BVFuhQdy5QY_`s^mi2Vf(r`TQlEfgsp3qci`a)m@(TfOjs#v|6xF z$tw8Q1z#8ST7RYahg_~lj~d|@W{=eXuL>-gP9jm&2v6lpv-cJ)JZOGk?mei}>J-68 z(f=#*AAZ&R5f&R(lY_6DNb!L%tb;I=drkMC&NMMuz)v*e`1zk485NH+Z^$0b^j}Lm#&gx~zI1C^{;%{nbr{G6mVhmzRjB-H-C8hz`Bt@kEW3%`b7P0JO`w4)VD|=JW65wk0n3>{( zUGTt{EXZTMqv5S@d=qn2i|ziND|J^ZC%P+n(K0rkc2@s70qZAmad8|AA8tUAK=w@b z8HaSnzNo50h=m2~Nu|4zk~QSF5v3K^fNfmC1zR~&yO=6fj)|IFf+?od7wjVLKs7gC z@NgAOjTosDiFi=MGpUV#s*jIQ0ZX&)r45s{w=`%A6W!`lI954IY~fSbm30~Ol76~Z zRr_z!9B~%O3#Q&&-R;~jI?SPoAA(1`G>Jp4j&!oX2$sul1-7%v@5zhmfPT9{(h4R? z+1LP?;OUO9;iju1T{@|miT&EaE?0E6mcMpK`$Bw6D-*OuUg=sxrCthWON@ON82c_U zl_M&t3bBql2ZvWKbTYdm5y4`K|AsUanZa)N6nxiNdz(HjO$igQCyeN%K1nnr*AG<_ z0hTs*t*F);N1!KebR(qiPc@TFHRJt9K@;We7*qSl$4Olm-C5IB%gz4wZ1Zc#VE z15pngMjuifc?E6$q|#I)lNhqh)f|s4Ruc3BQ?rQ($fs#M@agW@#qYc)#lzb?-ELbO zZJO{)JV1@->BJpYx|)EWH>oH$x~)B|f_=)|4}tlT=?F9xuZ&(hz$y?ek72>oAi|B- z#mT?)*+bEx;xliut|Zl^k9}OtbwKjaG$d_8f@A%Hk5ipX!(njbwQglBS(xIHTZ%S` z`KkT>`@)yRSeUK9s!0{<+n%<)zNh4!;WQg}tO8x|99r!*-mW=~>Nhp<$*PMO-;$~X z0M4s~FSRCY-&_EknvIng%#uSvh6;*OVKy5!sGz8M^p@y9y#R-^wl0VRGk~fB94os+ z&=O6_j5WXtZGlOKUudIw7`)MCCHL zU#ken94@>sVEv)WrwQ_n(x-34ATDcBL;TL6~ibFMc{ zM6WBdpWjQXBe6zp!GY~Y%mos#O)~`4mH+d|am~xit6hr{d;bXSHn|20FTUHLziy?k zg(m?EIeUWn;R49R{N?RvPq7j{cV0y5Epx}lV${uRcyQ^^+`f_9>fX_~q{5t)f#)jP z{Aq#skCV@??GrUprhT(h0HS(06Y=REfb@dTEr;2)WgGaZWY-9SAE++ksxA>sc@dY~ z<-hrHUi}|D zRr-aAB#~YuUWWr+y+`8&Rw6g~x2E0W1UyUxUh7h=xb>uY4z~ouyl24$B$Frj6Foht zk5>{>`k0`TN|E^|uNH+#8E;S2Z$f~Bbl;;k)3u=X4w3`_Q42~`b26hluKugaY*u__ zk`*l;y06QscHZ2W#_PxIxeqqflZ~@N0UgQBRP{8=#yDu%chMr3!NP5?_mJYeNnG@8 zLa$W|RpDgN^SB8h4#X z2}_?+B?&=wcs|I-Kcb7h7bfw=Png~IIqY{*muHDG8#4V-eprq?emOY08|3BxIiTDE7>4AzEz|Bo)whWH?~wp zwC;}VJT<-o_~Z0hGRba9x&jh3)c*$d1- z3_H+=892hJqDV3le<#3x)c zw@iQJJSA&cwg$|y^r{Wadz%6_iUQu`3eI&>oQn2mMK~Y8a(`R_mGfkZq1YbnI>) z{T3nU`7p0vHaajt_qmy^6E~=uwvn3v!;FNCy_irCDS)nWg?HXU)N$<4JxY3C{ZX+3 zoqo;s1lt#PM8}f8uGUb7;pCNmRI!-l><6NFa}R{p>CPX;XQ$h<=&sU(zV-==E3;HJ|SdEGKkVvX39$KhB?aEub=Wb%G1?gDFF*ELG*b#NYfTF0S zq_0{>x7<{>K$-{W8$mc6TJP5 zd)RUM*F$>YSWD)x$c*)I@m0q@fJ%$~+jLdPaQO+bjlQo43<}lyY>944GdEBk`*ELfGie3hR`IuF@5rtGL92hp**gV2kPuuQt&r;Mq)Lq51!if`E^7?B5stB4^{pEnj!9uP%EY#B}6B^!GPxd z;m2Ev9g+=PeNGpZ5G&0cblrQ!i4r-%Qjw`M-BXXp`>r9HJg*0L#ukzP}xOmhd z8G1lB9hhs!KJF{gu=g(7>BI}BM!Dj_clk0GRaM~SF>sS2S$yy z(?b(ZBR___;lt|9j{zF3=O*>AQ_b_4TBJn5caWX&@De@vadhKPXjvhebuAftUa=63 zC^!|6Lb)S*+#3(Xt3C^29-OkHklcS?+Tuw(}G z&v(7lA7_$+E`wN5-}m{-Op{qzzJ48&(i17 zcuRPcMIq<-W2aa7O5=#s{K=~WgQp<}iS|h*5twN#tHhr89^l=yXTkUSe!hNmp=b2{Tr)Wg zl?@Jz-uE!ZD)hvwJrYaTUfmj9{VWXBR_uZkGAVai6tdfKx5L&*Y<1CpO+C6fDi@wK zG4leV`RyyXl$|!jL@i*xBTRoGy}!l(MEhw;v(4`gIG~{BjDi_tapUW7>N5T~6h*@n zGnzn!#=D3>s896MmhwLyB!xM3Fr~VJp6L`kYWYSiiYH+z9#Vah_ZglMh1Wj!BhU~N zzDul|Pc26Yuj|0wk7!ZppWoNmJCI3RHC6FZ=2-pNTdflRP9;uval2@<$4Y#1;55Fu z)$6o&R)TW$jk3N8AkX`@)!c^M1P8>L!Et&W9~5PN4>r~QN=6BG)(6g`+?rw4E-HQ< ziQUN}ahz}Ck_2C$op~3(O4)<9viG_KVAK-!V7~QYtY?yS>|1;aTF~hl zWeOs>&sqv zYR46~tu98a_BW!Q6y!R794vmRSa`rjqAW6SW^iaQvJ*Ek-Q94WI>8kmhOjI6pF7N2 z_cb^N{L`v26FI5{$4l!D%=XGTH?0J*c*M1i=|I2ehQ6E1bbDGa7IRu1$N5oy*-iDu zdL4;D~oXVAfIozz){a&+W{CifUU_w%y$JgWE6=aE_a0eq`QpqBP6z^$R6z zP>hznfsZmT^pKLZU_PJ^@@{ZOK!=1nd@e}I9K{#^JpFW5nZ}#RyGwPPAV>jk%%qdS z7fePx|KnZ&^|`smyD#t0IOj*E4{kZsqD*^GpdCnB)_B(|+LV59bVEwi)~ril8kBG* znsxGEHc|=>mYcPbb)Xog&XZ;;nBPHe-Pr@N*_14UsXmRV z?u|9>Vr%5S!H!mwk+9}m7%p&U;D-EVG)hjd9=7=<%ToKoA@EF&*G6XBRUk8OanEG= zk<=8d`w(9g^5ik4zirAYclsoAMpnCBPeZTc%hX#tT$I_hBf(deOXvgsa2>uP6QWq^v|xl zY&!Q>G*aAEFz1rF4o^I&RRFdo3Zrac1!?zB2#3~7qn`;|Pwt^_$}g#?*cifhq8x@Z z$Lt5zL~|-ud&(`*H+&>1L-$)rh9BOr_U+)S{{7JkSFgx|$xh~c-C|Y`$A3$@qQz-p zm$x)oM(`!n(`#w(6N2ui-@C#2s92U zB(SbyR}r;Ghl|$^uWL%PtdJrnU*-+$pe4N+*Ns6lwjLaa4O`o= zIztK31=(yZ7|jLlx7g~3BO+T~p;S5mkYDR&|FR)_fcf+zgwY<$t694{#E*YRx7_Hk z^Sm4DqN&`RYgf|Mnt8v@@$_)wPJGN!M9)I{OtJ_DV)Q)LU-Um;uWddNYWT^a zQ~P{?JKV7Hpg&z?aKef31)8n==fJrs_$eNF?V^FF zF{U*<@U7hTA)^NWhtBMlcf6&&=c8vDeUPX9%{@)iBjSggjHtpLUD*SMqJ@F!k;{jd zTqnKlK&PjN=S26{!QIq8{z-S3&(5kKKlvCf;G7@EG~$8{_YN~6PtozdbLQA2N;vB0 zk}$x_4|IYKm~DAuqSfd;sy`HMYSs3h)XsEyD}G>qRYH=QCqLo})HiTbSF6ABwE?Vr zTt|yquhpYBE4`|EPl8kEIqmG19|~*#teJilZAM@7Wmt>Cr*Ke(hnYOR0WY~BzUjz! zF6nS-_OVeD6p?K+clpqD^yt>&4%$=nJp6@C+xWBafVbjr-?eDV!B;y^%sM82XM&;w z0Bdw)0LGwUTC);~E>*9PBXefGBFe`xz+=}MOc78J->yGOWLj07n}iq(aVebLuzF^@ zbs|P9#VpT^VoG{H+74K8K!D?3#RBKO%)d{8Cm8(sP1~aXf`jYMWtxnMlOc=g0p8p1>g-4>mss^vR2FEWuu9l!o5l4$O?)2q(7-KMVgnDHcm&D(s$^R6+hu z1w!6WozT$hLU=Rv4MCfJB!(w^l^gM&tN)^>tGE1APyVTBybuy%WudEOfzi$JGKnKq zM>YmqgbVALcdo@mg8K=aT#5?UNzX~_AA+bCZbNGZ zd{m51N-st9zyWE?Q`SjgpzN9(Xf_)Ti)lAfD}nU(sr+U3x)hPr>Oj|BKxfrJe6dQ~ zpIub}AIO-_bk{?Bb1rNY@IlhvCQe=D3d_@8yi;u*?=a5pL@?NE9W@;7Y`%dHNM{hD z2LQ{$Mtm*yXHSxw8k&zZk8{8sm?O2d@AXN(2bP{;OIv02|=c{XmH3=mfP zVh3$5!v2edoTM!Ujj4@Xq;rlc=mW)WBADaBHEQ@k(Z|A#Uu|elc3^$NPxEj(LpL1O z&<3`PJ8NfM)BM)%iE$V=Kn;}qk6*4ikx}4~504I>Ou)N~NY;FPARSXg$8OCGvY3VER33{p$U`mTNG3H!!5qd=gn z-xO;Wsc1p&*&1EY%|Zf%Ch+)r0$*<$&}H;eb+0_+z!7ffvEf@eJB1AK!~MkjKRm|O zDTjEUll}a8AL{5JlS3$ou>2EGAFzGD0sKVy+AUt{b$Z!}!pmQofR-lOrW5KCrCAzG z%rmSVaJ_NVBH*EVr=v9W{`%?trHX!_v0tFwV>E>r>l$|fcaPRA{O7uH-a}r2CjmP+ zQxu@3ul%H^(}NYEG2{3XKPJ9W**uT~UN-KM+kKMY96`Ya#QULy*`>*+Xteut?Z!&# zYhUl{Ep$rUwt`d8b}#jeDPu2~o7?VsqpnK+6Y!W#dx3Kl+?2MCTVxRW%CsoCquQhH z_;QhqU#+3@*YVTpdX)~>x3h20Ol5;B?=f~9Nz8qP^(zNfdeI~6Cc)xp2Z=%5X)gie zT1+f|0?tqi^!=j>rR5O0|mj9mN<4`{HRaNB~*%O3IdmU`7Zxv{>mgoe_Jrv}by&Cm11k|hVR2-+lw!qRU9gs4s zUPZmmR-+AmV8VQtY5bGIfQQtPAGBw|AMFJ5VZN1IX`Yj*^SXJj?LD#$i6jgbiF>B~ zg?}Z3e`5}$rHJ2(m0!=V@h#T`8I&2IgBJHLIlTf_SNm)VkbkXT(SthZ7Ci-HqGWTp z5dU^*P8v`#TAzaUm!qwAx#1t*DpnXpl&oF#w9SC@Z(gQ~318)Op#w%(A?s&giE)j* zQ0U=utGa}gdxB{(kc>ZT^Y8`xg~~lN)}l778@@5gP0Vbx`WhGOY;@rnzK7ErAn$|U zBj*7XNS4pESxL;0M^#Oq{Z=obO>!c1`Txv4kAdneH2-$DHTmc5TmAO~qEfr(O&NY^ zp>hWUQQR|tr}zn-j;a}>!)h5p*e{ZymKcz~>rw7y!?#EprPBg7{X|Iu$(Dh*M+2}5Y4xK9Nhd(#l;G1p8O+qeE+?aCVu;UU2+Hu>PY1z|w9q&6n zg0bt5`*BJBBgq-e4qlz}ZQtH2g}8;uW|$CEbHEfB`JTIkEiVes?K#~_js^DDZ|Ge6He*_9K=hB9Bb6-nc|H{kVRbd6sEed_1uf(_;Y))vjFYUwa>z z1r#6Cf~NwVEFlqtKXe}izx5qd&(Z!uMuWdr{Bz|6OaE!&R3V2P+{$A`r=a|Rx%3cA zkdVOhczOcG7C!4dlt>_T)dLhJk$&_!^0r2l@Guni~F=xC24 z?);6eZ>j`Dvf%X%Z_=hGPKpmEi9oJ=UJi_cggW~E;Ns;%0%@3gTG&Wss`p(D{*Oa_ zxE^hC?o`ywYhsX%!FzR%>_)Z}-jCZYSIj1nJ(QB#BCgy>Yb>jfBRlx3(&>|x@Sx2u zj1tb~RR!vyCWldfa^*a57XZti#O*<&l@40@zxfi(o5G4NB}wxHM3iU|7_=LJVb=Q$ zOljpKJ>B!*!8FyX`6V1g$;VXJ6X!_WSW6^H%ZbrW?M zv*NMh=+h}Vzx1^G+D|z1>^S=*z=2v;JOaG}AXPp*#mCDgb$+=|<}xMm>>2)N-5gW9 zdOA7KJ|-9B67~Bl8yoQAd@4(Dcsy5^{mY@K4k9Ue;%=IsshMXIX)yl#UZ2{c&|To( z9Y~K6PDn|c|JifHFvT=yo!m&MJz@d?0U+8RKJ;z!|aDA zJZgeg`Vg*j$@8N2XYaU)TCwc7985k7G~RQ1b9P^L;hQRBt0#WtG~T6+*SQI}p8j{< ze49db;YE`m-kiy)b3FG8a44-X(+Yvd`QgOZS5?gYco*R>4e6O^#q`+LL+)~ZohmDo zKI4fvBbP$b0SMxG-Lv?w|D|N$9y9J)HEA=j8OolCR_0ZRjJqHkvu8kYHFADce~a0E z{4x=+a>r$Hp|_5eY?cbNOW8(vc1+iK8R=%{yz9J0GyeXWe)Ak?71tbR?YfrY9wchc zmzV(^&T(G_2@TMAL_05&eg=tecIw9&9Y;6}gI)vQM0PfZbYAZZ_nA0?uM@ecFsu#q z)%wb4U41hZC&HUPH}wbn2;xcfe>mDF0O=0Y`lj}GIT<1@2nMwB+K)a_bn(;6G+UK} zcxh#?oOulZMw?<~+Qpd;^vwUS*45v0Fi6Jhdja1BxG?cKAP}Sz=TO-m;bL>(sddwJ zUn=wyzb9O8F~l-LrF&dr`<(#o9DLuul1zh>lCv!{6J|h$or2;<9#Y{r7V3~4KD*_< z*(Z|C)SX6)?I2*>=(WVaCGpn_pl*Bxm;``P4%BS4w@CoG{d{f(5Y8f^=L`bnRy%0r z8?D=>0ZYaofcfXge1tVRv36Rk%HY9HDI-q5R?N|3Y1PyCZirpKz2{~pQI{Xzl%E!q z>`RO;Ten1BsuuW6wg3Of0WmLt95D5-9I*ZP^=oUi{zrM?m(Orq=nuTYaQW8r!X-R& zlCUF^P*N7dg4G@Cq_RKlEmSyttJHvNf zUj4<-_@JM(uA@o{TWSy3I<2$q0YU)6T&(LugX&jai+Ap%;e|;0nS{P!fB*n_Jm*_Z zSy6T|3PsgaxHcUipZN*3(^C z0uURaEWUJ6XCCXTmIfZLg&~p!Xa|&5osL{A`faj>1c)|Kb>25Wh02iPZLIr59{)nq zg@w(LEP>tA_n{bnX`%?1C}3nY^xkS)sICVPO>!TYNlRT5;@;}tYrf7#bmq6eAtnA{ zM`j0g;ImUecn{_tYxgLN^XV70@ta_^MfWy)SKNY`QoS%kO;l07w5h1*+SI#u3Gb%% zT3cHc*E(%CBit2NUF?|R@>@Q9lXk3 zWQg?K(`^+M4c@$B>9IaXDOCwhiX(D=0%SzC{iU1SJodjpSie-NU&495QyDj_e%^CB z`eGWk9X&tb2hZnNu^r!|@Ta$dS(%gz=_y?-!}!`t@UfI$kc^C%?EKiuh>TxJLdbq& z>Skb#@6|8cE0_Z2WK+1Gu9qU{qUZ-z(T$1l()9n+x!ta{F5QE}z}r7%Uh> zwBBTs3mB5XDDf9(Jk3+j9r-c@ply;R5R86RJyk>~Ca(7U%2s!90V2Y1Dd+(w!`8Ot zx5lHs-&n_LKCUevXGv@J@KIMM@JVarbEUX^ujX~rbT9FGDF)s9)>g)bpwri0MCqZBB^Si@}- z_{M@P$p-OKn0=LLjYzw(fJghyebbQU8;Y~!;7>?~3HUom2BXnid7+TgO!%K_Z7k)# z1^CFkE^gLcgfQA1DH^)Z<9#CAB&37~+i$99lJsNvM-mrSPSm%r)f9c|a@Z8z+{NES zkrvvAS{X@|Bqa5{!hFKuF;oL5mL+XD(QLTj85PTR)I845F%fA&c;}RT(h`UCbN!9+ zXCiCWgwtoMMTm{2KTKl`@y&jhC??7FaQ^zr$viVCqV51x-(J4F$Ly@LdTFE4T^Wr1 z9&7(>d`a8uGKhkBubkd>Ih9zfb`d@%KHgpamCWN!dO)fU;H$}dSlVK&foM7X zvoia)BKEQ7vvFUNVG`$wpZ05o>sGcUpLCz!+-**tGKjJLP?G}g<&f=D$Vj4%niII4 z87>(qNp}^5?5}kQW>$itks{;L=+9ZE zs1*io9)YH~s_yuJ1Pjl^?j;N9@l(-Ahrq5yHt>>YZ#sWp?L*q&pr>Fw%UP z^s|R2B?SrbKBt>_fh6b5zrA8xOu!uS-KLg|`FPr>kg=FGW4)3{Wo?}#R{m!C+&?$- z!GF(?8<8@1cCy(J=bzJ`uh0N;s{^wZwx8dsIxfqhK0Vi!OrsrWQ#p5T?suH&V{(r{ z{w5dF#;yLw-Q}Ue3EQSF{uT`*|2jxejVuNpjD-FkC%AFW7Bz-=ET{?rFf?!{&BU3? zH`4Wt&3og(7$)twsT5AwahYa1vu0D~z>IwO?y|+XrT__Q)aPL8V3+=t$^+~-jf4-I zv0*!pnu83dTV{~?>a!dviL&y#>WPo7a>Q1@ie^HN+jxBd%fA3TH(?ma;KIjH%qYQ- z(eRvLk@9xXfivB9_QThKp*m7BWYgHlo`t;uq-$<$ebJzB`7_B=67Vr6?h^rG5r8ID zVU7fVUWcGx;tz__Gv_}6|2Ss^pY7^GgrG;eUbSqu5LjC^AL2U}H;v22dODcxIuE|7^c~n$p3I_OLsxA$`=)XLXJ)y2L1pdYJZ|(rA*M z1u*o*(8OR9#L$p?G>Hsd(i|~*@xCs9GUjEd1K+tz#0B<#=V)~I{sV?wvzAEoqz2=i zk@ZQ*z(a^@7nNq1&UqgUVOH?kwiAY79E{ZB^~n-&$l&$+5$e}hyQXpn@F+#MAZ0wJ z)LU%*uAyEYbzFFE6i+t%jSd^&N04TDKU^0pTqCnx@rW~0N2EP+-zYS{g7j}ENSSq+Zdy4`0l7a3$3^3>75iP6zUIn#?9V{zUPnboRLmkoNrKKZ&~4^@tpk@LxA*9ygxK>BYZKwxuJ>*fbiR;4 zEM-a`dxAu1Rxi{)iW(gd9!oMWkW^Asl;EOBPH=v9Ygax(MCAm(bbv5{p=fy4OXewA zOma%fEGt%G_e+F*maax?sUSvKr6O<6({LLwqaz+i6k=J`9Zt5#!``crMXwPd)}Cmm zdPkGRtX4#=6xMneVw0)N#RtaLLlL}XPQ51{?y1o=d5KgqXY?xukTk}qVDVQeF4|^~ zP(dGzShpxbzT7DPR4&L!szJcr>I(*hOU;=??r&WlnzR3ZDr<9{a4d~9uZ^mO#X&H6 zhrDXfLfT_ZqwV7!-o$>~1bm7mFx8!;+@Pw;t*#(p1p&|DZ|UNftEf75wNjc%J||~B z>Sm2VMY06^*dMwy+x()%3Y{i!ug$>6@>&CVNIKa}v>S(MoEHDb%M5QFyS^E|;AbH9n zhN{~@jeqsmMw#`VE^z*f%lbh}_evxBqV5br)0LusfBpF3+C{3Q4N~Yl6$!b|Km^@u z;;}=<*OvRI^kXWY*pRXZb`taZhnAtkeYj{VxzK0iA$mb{iWjdYLGAWdkbK^ zN?oixtryw*`k44(JB&{ozJL z6MBb1Bj^qPbe3qFgwlpHm}jA^XPzGckniE7c&aZRY$r!?NF^W%=T1Bo=EkXLuVHM? zBBd1=S7x(K$=_3Z4|wFC3Jx{XLlIQ5dwjOtGn$m`KKcGItyCEC{uPSuGS{xtjSrFn zG(I{!@8Sg*NlHOH*&lENvo~zCGp}jBJ*Bm^6Rh}q0q0rix&AaI{~J&XJHf}-aJo)K ztlC?$RtHYe>lON=V=Y;%CiXy5IBs+2y?j1VHtHf)yXtP@0W+TXw8#ArUXT_vQcv0^ zMZ$5$tR~yjSdky^B9Y?zEup;Os^N(S5=$1B{w3O3=ghTA(_ve9L@vICBYu`ME7Wv- zfhz^&OfKq+h;EtiCH^q;?^%jectG0@>JRF`L1OvNg6&u5mAF%2m;pIDS%QrDE-(Rf ziO-;26+Gnqt@C`@!2hNZz7u9_h%!B|Fpsr>f;(LM*5-+YZSAM^E;n>!bzHh0sz~Bw zyo9mvSruSf&tK@+T9V=-&UnE`0l%rfRRKN*a2Eec(M}roOg8aL5a$YL%zzKrdykPJ zRGj0(SuRrLN;tyvtLIe-fP793(-eo_5P@+galdK#h)XkSuwXk|`O#KV-jE#yTZ7t- zyC4f227;bSeXpo@ip72H^kxwv?cZM5JP*7b!xGa<@Py~24Zf1;TJb?cr=W;gYZCD( z$b}U7D#_x+suC$vPWE7fjub{Y@nV*}4Tl8;*;{&J^bmFeii;xFwHWW>5|Vo=ByWmQ z{d=O9e<@)_$5`LvSy4`GGuBlj?`LuZrIrI@o^#bZp>Sp-W~l0~1IdxCDUW2lVWGeem!h7Z-XL zT>_!pH1{L{4^5|CM3b%x98aOL%xRv`s80e+9_Sio+foIfTvtCM?)Nvv7dB4zIg!2B zyM+d%*n6K1NLl-cbCGo|$V01i!Qx|AJt1VL zQIlC(fV?ab1Vv_7=kxd2{haiv*#iHX z#B*1`n)8{QY^bh7d6vt@DLNoH@*cCXI_HCaG@{{BHn|eYFSd~updGPJBYSZ3eNBqx z@Ym&}@7vVtdBnIWPHp)N_iR@0T7W5`a)O?q5Ta><4f(7UZde&vuz1;ejcJZ6isW58 z0=KZFGfaZ8PjDFE~C+?D(Rh^2y6!160Ai_g7nN%%?1PjHV}oAbK~ z*Vl1cd7Ecm+LqgJvJyGDY;HvY^eQc!SCr-4WQHl$*j%6~k(G*>KH#T{q=k zq#&qgc=H6WMG9PtMB}E1Quo2{ej*5<3d4C)%itduw#$FXVSPm`;7~Ew=+^Mq4oAY% zFDNF7-@$r7DvN#MkV5B?)8-qyJL-l#JusRk(kKle`Bb>*L;kUxYKN_ zb7@(Gpsd$?XAIu(7q9?E?8kxk2Z5#;f%YPRw^M@~(v^H$A6Nx!4U1Ex5>!v|_1!I^ ztf+7%`6sY5oDXl5-S^ZO^9Pvll9_o=HE{1XDstRc z(DP+psybS35M^6|ZvRB~u$uv#*WXc~8aocWrB+SyecId##V99f1Fh<2hp8$mS&`!l zQJTX6qQW(gZ>`1xtPjwC`-^R<2Aebok?C#o!nRkoNiHr3acQ3<#I3Xz(o@qg z?|&Xq_3wnaBJxqS@BM?poYgb#N!JX2c;Vq8_i052e!3WQ42>WqaWU^$d(;4l&C|$> zJP2w4Tb}j=l>p=)j@M8P^k)6nIImV~5G{uJJ^fOzjo|p3n01OfL0?#>V zTnNnn1r5ZL#Z>pjoJMgwBD`GvsV~bX*OgyNEDJTT(+zM~sV?=4dp;%^m2YDcrZvm#uW<>vWFLP>Lz=e_eK@q5;5Wuh1H)5G5&? z66{0^7RYc9>o_#P4bSEjs1}<$%!~0rdVfPn4DK728EtIS%25 z);M3^?_M=*sjf}Gj$C~SIm+VmsTEvo4(6ubC}}s1G`NaU81e!TH|6XTqfonS%DAwD zrq2()?KA>brcA28YsY(;cFCsWeuf(ze> zaPRYf1>NFdp#tqc*F+P)sT*q$GSA=Y&~d-;qJ(_?b^xOc3P=b@LfB=ldenX z&R`}$Ys!CXi{hGW`nBiaXsrNd(tVym83&5DM%;>?a!{v^K-MO8+WXV2EMJHC7KXYw z2p(vP7FB6RpD_Eyv?p2>@43*%`wQm%2y-QgN0<*8%*%Uqa!-_{D>C~p4vH(P#xW0Qrp2E#MXSnaJPnDJFhr!U;t_e zfLse`cZcar^)&IQcXkgL+rg+dt2)BSAQnz!+G+2^#>4<}p~pga z0GFbdphOC^pA>&RV-UV(mf7M4_hgM z*@L>)gmVo4EZjDsy@uu&4E7Ph-En&_G>6JI`s0)R$R^rEq|dJI^#nh71scK)d!7il z0#No)syWVs@a7giFg9~>0$2*$aZSeq(Yn1V#kZk`SJYN5&v-it?RQ{RPcNFM{sJnL< z%U2Ga_UGe%r364wvW_cyfshmU#Ed}$;X-~OM6dPOaVfP;c#9|H(92`rx3lyG-XllF`3x zv4!+jD+PLzG<;8^aAv*Pg4kMR67eG36t0-88s1?Moo`=FPgTC+g}7v9Ke`#@&FD2qFM}HSt!E^g*tm4GZ}e zECL>Uwui`wP!Y|O*WgjP)z1`pEY-o{6I2L07pdQiEEICvVBD*^Tc<`EkAO3V@IO|eFALeChF*PF@>rU*8VnMTj!0ROzL z3^23rT3SmTOK^5Qwz@a--JM*}mcZk^BMa;Rn6k(@WJnr!xgWY{@K1Gb1{?k=J$}gh zU7hPEs&79$fUBI-yG`Lh&Rs`c4&Z-gEOb&yAI-<2m#}vC#?hJit^+ikrWY>r?rk0p z>=+=B`aOc$H-LYZP+AK9*m8%zuMYoS?!*`9uoLuVg~IOOGskhknH2SA2rXxvEl-~SI0+ONY^s!3xmTes4qRk4X?xatdcb9nr8fwM+MzpjfuT50 zuwB(E#6&WJD3M7odB!7A0HAHQ|NPG&NFekmup+z8p-S;-Zp1 z4c&^H9t83bx`fghe`ijc8+#k_$ zNQm;ZPI5a1t8`8wASF@hxcrA!8*A0PD?s)00=A2&%8-(Jdn0dn4+oB%s*=~!uyyzI z-+8&fiyV$_O!g&*p4??TCsIuV>8Or62eSLazwBD|^^)Jdyry7-8p7ht46IZjbmRN%Ha^O9C{T2ZQ zBMIynC^|z$SMOyE8aJyMYpAG2HNhhS+ZapRP~VC75v{=dcX~%}mUr!;TTymNC}2bx z$DQ9wDsD6iF+;bI(h5hN$MK6?b>Ax}F=S+9(etLz?q!BK)rxE&ST%F%Uwuy!NM^hC ztg)mjgl5Y*y=R1e+glL5_2~*f240^yb%V1r{V6*Cd{_<=R>^4-0V5s&a%YT-A0Ndp zk-B*a+Xo2K*LUWCeOdxgu2s{F9$-A&!`UDK{H@yHqMhLEWk)T2Kd}<#g1xQ4>06po z4K)G{P4JW!dX;$vHsAZR93KPkOvJ7OG8Fi~KL%VwYZG$h_xM>Ex|@Uf6f2*Ucvj(v8P{h0iO$xsJ)q34 zlC+1FMyHl60Mn5~K1xNh(t%+lCFID7dBfFF=f~INt zS(ATv#d2s-Vr-?!NxTbS)Ss(PY`m%Q#Wmc?fGg!*jtaRs>Q0JkZU{v*5Rjg7 z^`wGS^=l5fe9lZ#hc&%#D^LqT{&9_pR#`zkEi*CU4Nd@-HW&u-foQ~Krb^Ce8-@V~ zocZGcR>~o{Iz6j;Nk9rTODJ`hy-V^V zGc&I*MIw)T0jIwX;t-(TH6pqC`cf@kxqSpB4tOjhzhg2#|3L*@99J_~u~8Q4n>O9Y zip`C9blASq_J*!!;b#-ZVb>ka8s+8{faWRxi|pnve7)FwyLaJaNbnI9VW!jE#zs*C zwcZmNYeDA;Ej*dKrc=e^zB@>yAEHBa?iNl{^hT=t<>SY{5}{cl(vPhyLmcX&_M{@p zR7~K$l;n{SWEHv(T3TAI!&nq5!DPj@gUHNA!%~_1UREoQlk!QdlQ3zRTu41AjO;|+ zqcpQsatE30{9W0)U7+Gl0sX!!8s2B6X%=pl^rZ44I^z7!PGvRSFn`fAXdBPeBr0F; zfoMRRPp}Ru!h#5HLWGU$9Uohkg;euP=7=6TT9QH`&X;LC`jbhfdK|*@xc)4BR8eiNm0=L@b&h|UbZ_RTZxD`Ae~(sk0HAqwNsdx2k2 z;}W5+2VMcb4bi29m~g_1Rh^|^5G=a*pI%j7%imbIw~kRk3~L7n96f0i$m(nlF>u~= zw*z}cuf}+tC`ehrL4}54!~M>$kA*4n2?7KfNxhpnTS1WT@7SqTx!=fd>mC`9VRS|d zVqR%mKCeTni@B%b;vIVHz}m#YHQ~ghv@dA~ThgE+;_gc`sQlKX_+U_7%0N-tuQg0BCN|g+JBpFn%L>3ezcMpDo?RzgFD@aE%A?txoR9YrYfN~@z zQKEl=;H$h$TOtG7B?+aZ1<;C`l(jn;F{!=1?Y2E2;4o8(v|Mr5RjoVZK^S_x6YgEw zr{1XaaF=+qK2gOeu*<+Jvqx%_!30?_LPZzWZ-tB`B8+Gkx|LYqn`g)TM`!LV8G=Gl zp*KoH)cm$8mj*t&n)MJjG~|3DsdS++hZW z5g>R03iqC^Ws%6_ecHpE&Bjz&637w$#|ol9o?g&3jh;6?FGYxl+DAXI-smLlJjfgJ zhQs6;c7|>==qPfR0BtKc>>sMIEz^Hl|Lmj}XRPWChflfk6=5!X?g4-b95VC=GYJXH z{LeUfG^bwn4Un=Qu-{#2w2*h~Gq{E!1533km+l5#WFSBH^{1g}9AKpi`A428SpH+i zoy^KtI+9xXE*U295hSurcUT+Q*rIn8gM}*XiW#2 zBp7zxiq=qCRbK36)bajJJbP1M@P` zW9BwCAB4aIy94tJp@I5Af6*A3TE0$l$d-p9+R7~{8>(X>)kHk@d)Uf-nPXjZS_K!_ z(m$|0|B#@}s390vQuZ-2)0FpJmABYnH&di=X5xOLx(2_CP?Im^K;hYFKS={71_Bhg7_4kTqz#3epJtO;aqK_xbbH%z#fe=5fz) zTk)8!FSeRDW|ZI6>d26+f)3yeO%`qkL`-?RrDB?pNqPw7jNk*~x`6=HEtHj{0qV%am#PAwV68fG0W*&~?bR~%Z-lXa;cVXF zpW>I8q#A*_;<>_%uOEo?o?I=ReEHIItplWnwKg`xW-yikXm@l`q2b}$*aYb;1rx>| zRWcf}6jIwi1HI2SWx6RkSmq|fGlUuPyBA$PQzG^5)gMN>1l=>`ebH~#xx=*(#n#PL z6)`IDCHN?g`HIJzE|*%Vj((;XAvUNI;Y&JXWYcSA!?+n&t0ggxrA#iq$0Kbx5bBnk zc<9KRn(w>Ux?EIGc`P@2j0y87vPK%gRfEbqG`SOQ<`&?WxHej_*iusrh*gI}O%zDl4yP{Zl4PByr*#-5@@ zlHXd_*9&~t-&xHpofE*0u+i${@qxU)-f1-4S)SsdPm5!yUm3Bj_0Qbv52D~OP9tD5*8U$hwX1(@)*|^+Q24b z>2SdiW&Im2bkyM@aaDbcz%iwmjY*d-=HMeU3^*PL)_xv;BcYSi4%mSS=CBJwftHW z9eX;})VHE`h5tH1Y^F>>=!iS8MwZF|YoyrvovEZnpqKIY*0(OLaRQU4;&`KHlycR5 zGVBXYtF4VXMGybBNH^caDhamH@+sC;l7Umk%a8 zFBGYwO)ZUI$dGz+rDO2ctquvd!(6Gue8|@1L4$hD(+>J?AI$`Cm5P@q*XGEpoOCvp zvgs;`<`|2uIFFd+{rex16|ob&8~C1367enV+SldalxG@iyw2B!$>`;;JeOAKrl*H0 z4KB2Lsx2|*`zlM~FYRh9?R7qmM%{ua@%7*6r}fxAprSPsXg6KUcQ;8X^qwK~UM5WI z`2Xm7>#(TXZ+n<#=DP<&-?(S|u1w>$^1q7tKq@`PW2pPI#h=KQm z&+|R!`kiy$f94usX5ix5_rBL&d+oJpLTd^B5OFLz)LrMmVstxgTI&+)JG;^J{<`Idw-oRyObC^ZInb|K#t(v$E#BX=Hl_Ef2*F2hiGb9{h-6>i zdNse~Bh`Ej`LTwLHDA`}^Qf6<>B#tS+C1EvuyYL>-qQu#_(Sb%ftZQ@xP-_@%}0ve zwwgdvep7{;%!+?gBZrz8SOD77@&!6Xj-3!FKR?Pz4^ijh0k#~i-9O$ENyc4U6NQ&^ zGp)4?-jpb9orpI{C3j<~*E ziS^s-BWd+KW^Zvw5JOHh~(q!d|kO3Bz?#ieV}tB6VVw| z`a0@>UcOEHeF0*T->fY$SfgNpT499kSVnM!ttO=w+=a#3p8H#?nXlW!_Z5LeLhHcm z%VoCjv~@p_lBwlJ-&!gt*A{)KG!acBe(7zrXl7ro73x zzY%`7h~GmE-2LP!hxQ~2^XgJ4VP;s&&0p*0U z2%s=L*FSf1LNJ%l9rF;z)AQWQF#^g%ptg$mL4EW24-GJgkURgXK%`S25_6w@r$(Fs zNVzuTT>OcrbLEkG+B2z(TDKAIeBTY+WhcX{2f;M2qyM z-NVWwZbX?G0T;1&kjO9hzB;rcL9yQ(!Vxw#QQ4~oIg|q(?+e;y;S<)vLNnOp5Y>wMxMNv7dh;9OUw6w@ma}rEafy4%>iXM5Vvd2*}oOXXqUh&_6?$ zD+xHD1EdjD5f^~&GwE#jg}9d^FeZVg?T^#yNnW}1&zwZD)JhpNqG<_R$Ne8=%Xig3 z_J;|}A!0Yu(&u7_lm4MZ3GYTIUc>&o*AD)t*FJkXoFUN(0Fu7S-Qp7o_-!}v{C0@e zT|>zsiu)F;mUzzUDdG3=gU1=6(&5$Ems1yPb--%2Y$iZbtN#9d7ywvV-HEUx30-W~i9H>fKD6T< zmL`_JmzqTZfF`iP!rC90ggm-D!qfZfFKjx)5rtM<@B~oxV%@jJNbBv)R>Hl8vIk9! z-yg**6|~+|#0JA!Pn^Xi_eA$pVzqKL%V#0G4MNh%0kJM}*&jJDhB?`pAE9>8s=7+R z`{FwrG8V)e3smRbHq-bS=JV;!H&y%_b(rXA6y(}3Zdgz0>Z)5Q+uF*`+}M!j8%HIx zP+)uAI$of*k;wxifk@#<#`?*lg#|omy+Bkk>pnO`8PO>LKc<5P3{@f%2^LeKMRxLUnX!EuUL-;4q_8*H7?K&#MM5jD<8-lm!Z^k9`v#`+%@d zmejB!cvV4-wnG+1Y!M|5HA^2K5gg}Z8*&|&HlMS4?mypP^kqXbK;1+P{%H91PBnu=O z0_F_>T|t=6zq*1&rm!URf0eK@#rr{?{@=wP_^b=8G&l+#j&;Z5c)`~0DTObAIA%x) zRs5TOLtOek#8)~aQ)Ncb5UHw(jL78~K=~txGTrITLfAxnTrb&n!8JDoHlmuheO0+% zJZUuYSJrsdN^97ELLZCys#Zp$#k6pV|8{uU!yZsV*4hHvy87-(&8jQZXkg|eF4ECo zdIwCJ_@k=%127VFFLw^Km%E3;&*yrcNmrAc3zhbec}`CA4NR+U@(5&};!byy9Y|Rgd}* z=F;#qgB`%ZjxC1xC`?^~Ch@%lZmsz@2Y4s^t&!{e*w`&9sb($Oo@J_zwW_w2n%2dN zzB!t{#fnP<{nrw2<+{%t&3=|>T#p`*2OoMrm(E3v45}KnN`XI(gBBi*))kEm5q?`a z%biEw%{E=z3=B86pDZt*?54U7`bp10_pMdqKn3IxcveA za)`+n>g#AwyuI{A@}edH`lj4<2ar5h9n4cRFFnZVEvVglfXl)c132iZF&M}`I2i9d9`3Z^}en# zHBwrZQErV!WgShVYz1Gm^VXXYW7jq?It#{C3u87P$;Yl)xlHH>6^m~HL|PeD*L~Dg zR-uK80?d}!pXKE1=5s+$w)ehTc<{#t(Lv(CJ=FitgVZRkY}%FMUT6{UgW6A@I}hvb zh@}1R-c#{8A-}+U11M=Bie|Ooc@tMshX8@*8`Hx~fuA$7xV^0nw`-IPUI;=j#0MwX zgZiUPr!!mXr9#^H``=NUR1|vH(uQB|*DPuDD;G+4OFg08x!8t!afj)5alJA(11WF$ z_peEf0UBcE+e$m_gF z&pX#?dMnDtnkSq8sqQhe4eVDx?^dL2jNlygA0;>jXA`Hyn1p;3DuroA3T3tIPO6%M z(A#mqsCD8&YNFY2$5AMKhIrr92SeA(-+xR*eQ4NbqcGctYW2cGwAwoDJX0q2CJZqA zu4uBPk?bSGGO^k+vL^sf%w~V@63XdyK$Uvr$2NKvKO=)^8NUhL>Bb?9jDmHM&}PS! zOF9)n%J5H{>^I&dILxZd#eC6Q_`WKsAvY4?^tFGyE3B7;+kvk`L{CLU?l(UzkJ(wY zb$gEEj;uc5kn||o#IPkMu~Qm=qkyxcEKmfWrTi}>qYaou92<}2v$qd`+ZaM3Z3s(4N(lUDro%Twn+-~L%Vdfom za_G+8%)gY!d2a4bkyC4DmU18gZ#wpPcgC6fqhf_OhYaDt3Rq)1%)dh$k$!Xo){;Sm zUKx17x)0L>(F|KH5RiY*)F7px7gX6Og?H$RE|QSpDnI@OCuESg0i*K4YBJA0CvKx` zu%J8(*1}KcJh3`{h#ghP`%8R5HIoo#w*h{XA`O}$Rd1IK^|Xk~ed)|mmM7m?>m7`; zT{GYL0<-21GfX0pXYDYG^ywlmLrHta>z|4%|QwmL%2QhIReQ#ps zGg*E0DoqJ!;a(`V|Iq?`c&NhJLk&%P5m!r;pdEYBi@Ew6&g2)r<5R)nBy*kEX`H1S z-X`*#teAW+ z%<<^VcZZtQIdRQDr90gWD z`mHLdDfeaO2D6=HE%>IZKbi2Y%t;hy$vG8X9SC_OF419?W%EjA?`vmYkzQf_NkZG} zt95Rr;u%yaw-VFltIJw0bak|)hEI+_09h9$)FgQn4lEMMbkaF~p4~MNv@+dWFkJf| znHczTkYf}0ci+1;m0Z2rHuYRQYqRT;qyavJYOhc6@bhxmgf^jP1Ap+BC4%y+UW0|- z)Kxyd<)LDCtP96_hkbiM75R!y0ZS-yC2KiY07=rkS$cTv+4;NmjOm|XE}6X}MP!?o zYJEKJmJ3>2roE+BZ9|13#D3gi)&JpKIZh=A#Q*n#n0*s^VMN{?uC2h!%5;CW0-Qsi z4^X>~r5J4bq0NHWC8E#?G^+3`HXfj`dPVo$knH=eJKvrz6(Tyml)YkK9?aR?ASTg; z0;bd|bIcloG@MvhMbUS4Zzc&r^?ww%(E)c zP0ldhyt_tk=6F>`;DNR)V3~b2352)tvyT9ssLUr0>~~yq?UfJ>jLWT3m8f-!)7pIh z1_zQ00jxhO`ATwrpF#F^ktW`^-2-sf`RtxHfk&-TunabJ(n`MEv3G)kU={qNE?^OL$?g?jaqRsmt!IqmVeDdIJa@kdV zeet#XCr_kuWa9{}qsU3Q=xvMN7v3kEDPdabvk$qXI5Knb+_c>`hfcRfQo|gWKR(e% zt^1Uf3o(T*1%bTW-+h#P*IbnaXY_%|%OY&=qAR(abz5%Ghi||&vW!v8!yOhF&A7cn zh?jXj{V&Y+aXU5_}g%_{EwEXnvsHprF z5$#bc*RC?x^wxP!awv%*8x_QPc5cduh7BslFpxGNUMN~sR#WOz0%^S!@5?MqvT{4l zuu56I#$i#pvQ#hRI$Vv?N}`qzt2a0&aCJCaAt5h?nz=c(f=*0|$yopmhcWsB^-1$& zdC@AY<_B2ni*ozl3;(}TbJgo#mFs|L?@J3UpbGE${hQi5%klgjbyfEB>kfSbWE)_1 zbsiet71Qq2 z$PxIKG2BuE$7`57?A5)kiygHuG`xWv7-X}nIjBO6W-CVC{<*(4tbUt>Y~gNwW5n{7+{DeJNjV7MIHE0x#@{;XYD*N}?Ly`Gh8goct~H(2cA zo+s>D8ro866^n0Z;lD}GR5$p%Gc>keCn4*Z(ODJgZ3Uo^O#c+EZ;Zz3DUY%e0F|Fn z`bt-(^R+9#=bp$xY$Gz=0>(>EHC)3-(s6y2mZ6Y4#Tl5+J5-?NV>uQkR}4?ne`5k}>!cHhnz7%r+nsj&!Fc2Hk@*wr#s4X3SN!G>LlDJGX5)c?H{jE8~^+kNFQ z5*N`gZdnEaDF(InGEv|yp3~mW%9I@H2SdWYS=#!?g%LGGbewJ(p;Fc|t%b1QXSf%d z=|Qh1V-BiN0uBIYn_JB1PZ?+-wLI=P>7vnZW4XAse5cyTi4<* zdxfpRDdlLiopf)$kdjog1J+Q_3}T)+{aOEXs>q}a@X^jWz9AnnKVa` z)LF;~_3jx5HBCf^e=44K%&tdsssACVUq^+rx34OLU0pr-%~bC< zI9Zy^0kV+SB(P$@{OywKg5BkrL3KmA!0D4KAsNYDs%?ZPbZLvfWsAStB$1jtJ|@CF zKs$DpcmT4XEqhKqB7MZ3>zy#bOrb^=87ibOVuqpZF0Gc)IYS1{BJozCa4t*Vwh@1< zUy3$yRxkevjf>hufdp+a=c_s8>6O0)1K~0;T*{1_cn3uUryny5yOu3qmU43bQN-go z)Q1Dz>c3pTX#DQLYS3FvhRE_%IQE#=V>hEsaTQQDZbAv^4$PMi{S@zsK@4^DFpGDB zHtC$QeA7(s4*lGY4qDU;kRKi`9TQxn9LczUy-Fp1v`donTPohL+Die$$-|lkGOd=I zqpq+-zmh+*|EE|c_e;x@p6|T>XB9ZVa4%t_Kq&-Zhg`R8+B*RE@_v!Rg(5Y*ws||v z&ui*_mfqo~f9N!?1zYvsraqq-1lBlm!swtOIaRl7Szh?E*DQ$f$dzu#@Khvm+^*4o zGBa+{_C*#|Gi9qY)xw4O>y`EQ*kjvynm}mJG`C9jk0Wkb5?}v&dF<=}?gI;em;b3x z3*Im%Yg^#`=B-^IKkou7uuDn_jWM8+NQ=BJjDa@1)UVLl-4CG7@nC2)QQZZ#< zsJrp2f#jZX9Jvbz;IPNSeJ+nlG4P zy4rJU{V$CuP!j#QWU{~FqNIlG@XS$-ZkMk{p7EQUeT~lHwjmVUe&3IA?sZd^;g{3j z*TqG)_5s+Zh!Dy+Iw`dV4da&0zy>|6vt?0RqV|5HDLQ5SypX=G&`BTW1{Dh<1 z4!UHQ=<>Sz;^i0nH((Sq>{=#27;5X~p<;Eqrc3akgf1sLt2m}Mh4=a6ZTcl&UAS6a zOt5X78UqTGQVxw$`wmWua{CUkSN0R4&0M!&*-;#h)_G+gg}9^~z8#@ayDkRTU|w9?|%tl_99>MIuF% zZq9J9Cx$b|0SWxjNM(awsD+Uc)!@o98hB>~F(Sov&s|{s?rPNWSVQjaRt5jb zs+ezSZKFJ~x%0WyN3d0Vj)D_+ljp&P+)W>^_n9WPsPCsZBST75vHy*zYr+2@4F)zW zug&t6B_bj@O6gXn+m5!N5;KW~KeP~jyH#8-q+Gb+9T{Sy5Ek54tZ=teDnwuoc+bq4 zKSv#;TPCC84gKwXuf^bDFE?`$#7{4qu&f=P-VquZeP zao!iHpA(6G;pSI|a2h(grgb(LtHOp5Y3k@GR*{CzN9lf=fnMq%)o9wc7xVO)5;3ua zCJaTVP8D=~&H!T}O=k_5`rIZV@A(b)rt-Cj0f(=jMFBVL4Iv;U+w*okrg@@(&-H{o zCkOvFG(YY5iE2k|f^&JtkKUJi#~*oGw_7;JFf@f|haPl$$@8&Ads(~;A^P_5qb#c> z1Ev6mH)AxFn*f;8I}q z>h+R`!H(_-sSiiC9%dhpg;p?nM_<(yPVwt{^p#2H5Gqd6>n0k|wFU-R+wIp1~X% z!&kOZtnmOQ5|-j|f!NZsD+M+d3?K31N&8awCbgH5QII$rP?scHnLCQfuj9DGi&ge1 zp*7g`GX@K+W#bzkVq(K?RGtvZDUMKX%`xd-PMo(XV>ZH0t;K3o;L(Q~-+HTv5z_$n zx)x{)0XFRA#Y_;c%p@@g6q71+NjYA80$WXmZ6in~C>`wNu07(xOHajoYyN-3lKbDV zT@RC! z6wb|rq~C2JbnxRex#;1Ed3&EeUAd{d+RN`E0ZyY6$rQZw)2TO#L)s7f1{oNc+Du?} z2^r0x-@k{!_pcUW7ZMV>FEoMJR4|Yug;WDbq6z{MPfXZlwaOJoH5x<^_~&gy+f70~ zVg_72+VZ?56!T?sLXP&%J7l=lOO|l4J_V-i)l4b8()R`hm%msS$b^!q8aBo175&jA ze*OadakFbB^DpepimxiHiS%c?zE7~BAFvx-Zl0XS??XoV7)eu^`x0VarE6$V$i!n1 zD8(z8`p~$RA+P+vhw+3i3A}vr%n$6>ah|pkQ44+~?&>%V< z8VxKtjF=6X!|WVj+tTw)*+3_LY8Izd`AdNG+PFNjQK5h_E&PlBEVMnWYR4Dp*pR>BcHobSsn4NI+W1SSYD}PeBGi#US zj(sg-(za))Q0*}6hRj;V%A-$lGe^l(5)6=GCZn(yEI}&dEE|xnXkHzt{YE-X70a$3 z&?^47)W2tJ|K7oaqSbRm1u=clPnK_)fbHwlRU)5E>kqU6fl&zIWzoAk4ZwB_yQz$E z-z6SA0tK1)Ylvh5TH&i59!jG!FWoP(o;UMO7mn>z0Za~FQq8-OU%{>a$(@+$=m3Sh za9Fz?#z%C+aXR10kh^OzaNAP|vy?*-Ya^;m`tR&X_1elRV&0)CUaPQb{CglHH+L>=b3w%|Y^mm`mAf;&%jRBF&QmI?gs{PyCi+&cy$@Rjj=F8jU@3Iw;$0oJ zVw?$s*1!mT3_y&PWi%(7ZIXxpcKmDl7v%R$@sx}*2-P`c`mU7y2&Z9$st^cN@kaqc z_eh}lsN{Y_!+;7ugpa8++895`vFLFj*p`LZg1L(a$R;p~m5{_QH35M&Gv>SYqC8mq ztO&_rUe+$FZy`U5IEP5*9D=_k1#ofYu4XdpBq^j6|0rSbBu2R)CR26|CW+Jn0PKAc zR@~n=$(8#7B7BS`tEn~;6I8y{`l9=az_sbSyEm0cfGOO-;FsCoi#|saZbNampZRX$ z%l;U2C)bj~etLX6Z+^^zSwh9ah%_eTMat9+QZ{=&fA@^5$uxPQ@H3A_^0#WGzLwk- zdYt!BupQ!hDi-&IL0{5?{*2Dp&TbHx)g2{++Bp6)3ar|va{x$oonutlaVxovhqhS zj)@Vo!=8=IB=Y*stlxMN-kHY~vjMqpt8Vg7?wPQ_FO^9g7 z|18+3y9(m^7uFYt<= z-IWC9;3~_W&UDH#W@uas`(3vEG`zzvLt;Bk5E8Hb8`}{PRLzOLnAF8yNP0$`7#K@*x790dv_Xk#u0mYNu4tfc@~Ler#S}#l z3I<}fXshtq$MAi$#nDpMulwIYyWX|g_f;6Rx+?XM%B)yp;ytZkH6vnDwUIjiADHT+Sy1xSsoq8AGu+6CO8uL-oEZ`!_FvKGG0IOg1^S_OL;G>H?HzT zX)B!ZrQ|PN`HnM&^q}*Sh{bdT7~!O?`!zi^N!nqbLn8E72?&AUA|v~d_ZFA0+kRvz zfOm$65NtUc&AR z#undMVZ{cgO@u)j{)3Mx^wllc-_=AGpy`Bxrff&3K|0Y(WL5MTxq9TMu_0zgrV+&a ztKU2-ilHkv{X3GM3leXsx<8z717%128AK7ZGHr07-W0PmEI7 ziqArPjahN)%7`{ZO>>mMIsh6T+cUfl*}2#%27<2c{O3%Gp*<)LQyWchN zKkwI@^MhWd0Um{=%HFjfhm3LxbXzXD6NevwArWFPO-`yE}Z1SfV3 zETanqQX$;x|ErC`GdMEh+RNZM>QHBxes&I6%-jbq1zm+%Pa464Eb+=O;+5EyI(cm< zIf}?S7R>jJ`JgDWC_;gxGp((9|e`k@;H zm~2;>XnyrJAc2eUIX)aP8~AP8(sEA%AK|=BAGZQMn%GLsOgqu_kQ2uXYv!Yd!b z3`f{{nDPztfHCcHD_BO!Z9>-$Z zKmHbQ-hHP(7QpU-J{KG2@YUBYc)vmvK)F}0GQYxQvzbPn&Od}P?9>rV@empvTogay z8{k1(a+vt?C09;PJJ2I#zew-Y+G;aXc1T~x#WHKc!L#ofDRVyVoLmTpZN#%Pg*otim zM^MK?R?BWrg^q00{HXr$CPK1_eiMU4dtA0(h-k5wDQn+($P$u~zV|*}^KiVxLnzt2 zkyFcc)hS@>AO={U00LIbIO-5*d5PRWzHapqR4xhCEk1zX9>9{ zA{=c6u2n9aU)`V>#+i5ARv>p7W;NLC_3NA|QN*M|qaMv>ush?ljI!B0R#Nj*XtJA# zW@uDS1%#g|Rsg6#DayE}uAUP=b=@$AV7PL19Q-*cXDRSKucR=I3F5>757<#x zo8&z8Pt7^@{G!Aig)|5>nKUEj(jh@gCNK9BJ=W8js#c%k|$p^ z#;!iGtwcI3;5XhVem^oLgl=UJ(W!Uq zjk~_qOxcumo(yO})AC&nvc`u|$DkVDM!%Zx8N7euqgA?Y0e3pPjsH(&G34*Lw8#)l9=lQ z)>G3Cft%B7uNkSOdLvuw!H6nQ{eMC6zY#dyom7$PRC#6!bW=v0FBdwOeTRw!q-$q) zUdPe!8?+FmE$p5>vXU7Z8gibuudDd+!>Qv^X}wlhGw}C6G@gdUrMTaQqSNk|PSY|_ z^SV7S(HC4TaSwb%N0xSALv5gPU)O zR`=WAY4pItP2N^H#hc+4zeBkTb@M|W{c#4bx#^6()9seh-Vi!w=hSxLr)!A2hx6@-;BA*xl+;AiVJ}&& zRWghUMBS{8QW&t2bLhKz5l6`TdSD4`#%{*?@1Nj}E7!qutG6P?%&<&O^%6lCd|E)42$n* z+uJB!Ib9}SIUcPfaRbPyzwl+;(|AEi36-Tj_2iG$gq;q*{42(98jp{k%PirpI8Di8 znMBi;a6eB~E?1S9&kfAcaBkMP(@$OMzZZPO%raI)b%AKH`}!B;*lDpPJ|h~mJ<9U@7Y;w^0;s%Tee?x(uN=v3yE`9Ggj+nA#X07U5L>yCdVA% zeO*bhY-Al(d}!v5o)WIFM=rNUC{WA;*h!M!F-~<8Q#gD>8$8{3M6AL|01frI_>m`QD4>6@sUGbK$ND#B7%O$&wiSLHt=buY_jY zT#MAsuBWWZqrg_SCEB~B`Z(&L;@%W1+lD9OscjiMZ9Bh)%%mWqasTrcsp5ZJFor;#`^`&U=%{XV!i>U2B6Ko`;QhXqLS$1 zj>hi~8}Yyjzwd~MLEe7lPGpk_WN>;cJ;cx-#UX%6`pO6~*IWDn_j_FqI?*y}q918l zGtNCPgQVR>&%Up!XO9X9e_q@QE}ULCEkoPME(inTCbT>5l~94?t=GLPbHK$ZdC~xBqtZ6&IEhx z1W7DxV;;Gqc&_iLMfLso^7VM3o10n7shB;xck96K!=sk=n`pKh_^FYH`K76e|Czk( zVNdFKAO9jg;K?^=ZBxK5%R;(EX_}(~6d1{gho`#}T)+H0vs%xiX*jSi$6MreTI zLS6Ou{M^7Nh@s0+nQgttOwGM)swusRdZ3pQy)CpqE%PxkU{V~L{YD@Q*n-N>@$L=a zgES_PW}1c>%&rbJW-@N#{(Pr)ny$L54_G;HHEUblE)DQMrC(X>aPC++99AsB4Z2oQ zNambU$NdGA9||bZ%;Bq&2KdiYBHP3BQM}O7QFB9{ivRxO+@xFCk5w8?(!=?Ha%~wd z#b3Gu93YPuEV|7bqlhO1dK{!c*`UM5f)#?LfKT2c+cHboLS}yzIe%K%L@w0wE`2W> zcRRUp)aQBTq8%PBTQ(O6dAn*E7?5>-w8lp-^W+-gJlC5z0oVzwuB)#u(3j1y5uh4$ zqqerX>9!EM4&*Gyt~kEHe=IAw+^z>5%4_HN5>4||4 zt|?qCv(uM|b*j}&o36m@=v!kE!*LBQJsa79dJCs}mhe%Y>}$ax>I)n;o&MO6yu}Aw zXKFEM<`Lcg7Q{P@e73W%uQSY{1FozqtbG#a5`{6?y3C3=TotXIzK>^c;sK2oX)?P6 z#QgUtvcu%rlHDlnTU~OFOtbR2XS6hzbA(d{!{)hV*97v14HjXmIwg zG%XXABVH5#t)punK!5(z;p_-yitLpma?TvV&d1eWHrE97R|5gWX2+sxv^!G&-X=}E zK3>;t;cP^mEq9oNa^irl${$%^85P>np2lJf1i)IZCj zUXub2K=mrkY&=*>o`OAgNd1>7w)(M7wO&p!9eHrsHjMuWu`j&e$CtUqdD+>SNG8yf zVAy>8so78aXP+8ghHAHI@*N{1gn7DR#-lB7zTXLnqmuvTCsjr=W~CQtISy&@GY6%P zV3-;^N4`A&Ll*`%q7QGn$&DO|IC2Nw!uIXHtd(^&XdK*%>_Dupgh%M5G@Itje|A@B zWjs9aAY6GwWW1xfRtX)#`QuD(csZ6T8Z^Bqn;ZpyHu+KDZ0gPK7 z>J}JN-G|4_2w;<=S@`Y9f>g@E!;FI+%Z^R?!d6=i-&j{dU(|;~M{F;nNt<2Q)t|6wzO|$o5{5ht1Ba0q&??K5vb8SvUf}tG z>aQA3clTr-{Vub1M3ottIeWqq`iGw=c;E7}T< z-DDdk&7V7+Mh<|L2GnM!lwOy?~8 zwe!M6KJTQYCAiuohvJDdMaw?J>RkvKkLQ@E=&f+dP<>+4r6)Yl>zo(F%o9tZ4T)em zo#T^6KD2^LE6}jEo4S6i*hUhcB7|)XK<8^F2$~du7SK+mnFNt|URq=JQ zvT@kj%_0&glJ;x1P9@(Msbu|m^G3~Ols>;pEdMi^_^LkTfZbViCzNsUrnyC9!J9kgitx2s; zgBFdC2;ifPVq~SV=#VLr#DpV@mcw;;-9AP<3U7?c-HqP(9CZ;FNAbw=g!9;kM}R)N zBG`)@copzbNoId7`;&28pg_RG5JQgX)FPgjj^;Xt#cn~hC&JB~ z8q#l*NiCSep2ZiwBRPD?tWIin7a@jnI5?qww7DGkK@r**tIFhy&z|!V=>v{h{B`N^ zHB${JfRpps=ht6UzSN<>`Qf!4N#Mm71NsFEdnE;L6;9Nfj7ngVL`>8}Qe>w^HQMn%Ho+5%XO z9Og`$B_JK^u``EU!&0CjhJdnc+8Wl;7BZn-c2|$Y^a8xT&a~VAipPpWKK<=^NX-IL zn_!}!WEVeMm?AzT5(UN;9+VdVa**SbZI`FBg!N8x+}O97js z*#zR9d0?x7BO{90CI5$#fi4g&QM}FL$viUl5VfvI{<*EOy^*8%iQcF!F0ie9a;SDm z)K>o7Evd3U3e^~UjyLr8c6KShbDolGu>L5%Fqr~P^rEaKUEaKP_C!aGHuGL{dI(?1 z35}3ac9(mBvuh!7eAlzUz~6whPnud0nw#h!n!6mZ-h5IZYst>Ua>nhQOje!nJeKo} zn{$p+d`z~(E-9p68>+liXPpOsHh?6y#OQVR)>k7_ zyO*)~$x-BdTf5z97YY&r@upAoL$GCLgsYGA(&->WPq(W3lrUOC4iU|=ECS& zf$kigG_r;V>$WTP#fA0(pzIsu+z*$T`AKjPw6kpD5Bl52uu>(hzoHaJ(0c7M)?W~n zEMrFQZC$Sj1TdC)%QRnczB>N(-zUWR3MuQkdzKBVIS#nW^ zUuFL$f*SH+ZQZEmVIJXJ*_85fooz$;bD(Q$5qK6ifW8D&ApBn}zD_1nudPB;&6(DK zsfnXXy_^Y5pYQC9+@qgSTv0O#HccL{=?2lmQ)QyFGEZ72p(b@i@kyfx6Xk3$Jb(m~ z_4znFmg|;4pY6L2%Iu6B3&+%DChLfOk7D+Q8^ui9}wFt1~V)0ZZZEL|injl_$!HqYG_`)%|dsp?+I=Mb>YJ&1uzi(-9b$HnDumv%d~el>8UBko~EB@wcK{!%&n>YAP;y;R4{6Zxn4qGl#19&91oF`3n3Qeo}a z%ODhIg!g|+-i-TR%BH2W_Y>XM)#n}hzyV+|U)vji%?LWw(I`i~SNjUjjW;J(@7wAvN@$*M(8J-Ln%n1VX} z%Q5ea3m5)&C2-j0xfvt_N*Y!iH43yD0^BhE2rOk3Y*|aA*agA-A1}7)-NsF|qtRaS zRD`|Y0rTjT{H}vi-F$~xW6YpGDazRn#r+1}kuP~s+Vf-M)!7Mahf3ztXw?zC>3`0%^tEq%BO>+;n-_}u5((*j}V@h;cS!DDY> zR4-S3nZgdJK|`3j+D0soh=1a0i(M_`7UW~b=P54epzT~^iqBLwQ+&KEMs~3k+=sv7~*KxW!F`9mkH_}bm$uH zim;NVTQVJBVOselQmdp6Iod2xVtBxPRNy6MnXD-~N=2)h`T3v)$yS1kDcp$q18>ve z^nffW(;!@_^*egFg8Lt_Ou)app=P}YXnu)fXV>$ta`7+3>yHZI8!ujF^qvJQb!x=~MF!!tf+khDyPv+ z5B$^gusz9!7`v|Q+*Eg7`umZZ-wY32w0`nimU7Y)Ga1$%Vx_XWB69Bh{UTF)$>sg> zbrGGwkxI0Q896G|e@(FeebVsM&Z2j+H%R+ln#5MN15E$g{XF7aF@}a#^{O;2iH94@ z;mMubzB(fjBk^VcR&8tF$TnZp!DgFQj>_9tcc&BQCGisda2T&$NPsRAl{+&!@WHbU zcKBlcjpCqRLKo!NN^eVjUv&;05oSrD2`m`Kon$QsZSRjI{Id?ru-c(+Ak%ZHA!)=& zn(*eMtTl^E&5l8}U0C^k&p`vD+y$G$34R1h0TW3JM$JP=kPW*`MP}bAZ;VkpEr_4o z@-P4)g7K8fuG7L8YhEyIkbId+yzYiu@JaUF!kD(d13Cm7oBwxI*8}~DZJ1xLd!H%c zV{ZO2mxnJ~m8EQfy~*tA3h8;&kftiw84e$A6yt&r&PCiJk8%% z?}*o85y>6)<5+rS!7_s1xTWm&a^)s()={!>OlZmbFrALXq<^)_X74u*6w2kL%gbj_bPi-cJJ(H!cE6%&WbsTim6I;Pmc<5oUO^J~H)B zi6@;Y8%=vXN<38H*6epgqwILF5XqtCWFf7HbX=M^mCPrp_o66pY89oQnK0v2hH~Kj zn9#pRbR^YHugQmnSklt*X$pQv8@_WT*gyhPi3>T~#}?3V)8I@h<{*0a?fdhW#WOJ< z$lo^6xusG1h%M?w^9)HzuTuRrWL9kJVwvON(E zd-r0=SN&Q#0hgHh`Q)u&l2o7C;5G_Ex0`yg6sXymCuM>YMz1*Kb5x&>GV5PYO!_}3 zJ(Ry+q8a+dW4EZ~bigGCk+gFQ0=npJiI~CeXfJN|tL4kk%!N)ER%-OaCNoHbOyQII z)3t@{y3T%3dibHaVODWM2aaQjh!;(A#ag!k@U1&pHe{RL&Qh@GAxQ75s9jB!mWz< zn_9VNT}SED+cJ{XEfss#XO^B&?Y*FT^Jg`;QVb0m2gtH*7(OsLzU0+@TCAO*m&wRp z`u5SA2o9Z!<8ufm(NXhx%do`q(d_Nc_TBq;Fw%pvCa&QPGw;OVjg-Xf5kl*&M@)%x0I2 zV(e9FBb7%@Q^W)is0g=Pn&JzF%gvmVu6OocluZpKZyt*o=LYYxFna{-u$@#4A0oa7{>el# zANY`}xi>dwkEa(=joiB-J(tW?6LvklGw9y*xTzCa*lp*tn#DGuf9-MHZP0Df)JH^C zwh56x#HqetDT`|Mu#v6RR1vhjkXv#G>ERB0(`sqPk_!ia&Yd5!Q+9{gu5=LcZU!y< zZ})QrD5mShb=31C?tlDXNW^L({7Hhdl1RaK)%aj}E~{|j78psf3tIZ#yu;qmR!}Wt z*krcW3dA*Uo!TRKV8q`|D{Nta7QN2MrtJQ3T%y9=7qZh)yyB>k){u$TM-anf?6L)Us$SSdO|6GeO zP$kT|q5Ir5f-|}=-h~dY?Q8+{059+ae*_iJr@nVS7C<7S)+?%17w=HFS9;sC>Gc}z zS`5$b9ASkrE4l^;SrANBaug#0-ywuk_$uN!EAyd7? zshm!Sp-O}loE$5nM@H6~J^t_n-W=r(dGn{EZ~OFP_w?V#x<|&kzt_kyc;&<6CHwZb z(}+&`cWE|MY<6dqFkuL}qTo|St|(N0B3|1wn6BcVIr3og=+?766qYa0P%nhY;kl#w zoFd}cVs2IFp=63IZsG8@d!oHlb6to-kyVQxZVKjSd*X4?Q@;!xV>Bb`#lzlR52V`; zj0=hXJDlVHdofYEU^1|^nV6eDY>-M)^glsc?qu9$W1DeVkP1B0MZSwxYqr95IpqmN z!yZ#TQ>pD4%S3j<2vHXTzN^e93zHW1bK!d?&8u`L?dF~AFk;Dbj@du`6=$Tzihq~9 zdh?Ah$hTsnPDtb~eb6UN$cKUGcO_50x8=4FBaZrA4|XVu3Ye7tJ_mxvnI~CY2NS=O zK|z|`QwMEQS=Oi!-B{~is_%2?JDyM22xgg)y1`XKXG0BX7@-48Gu}w$eR%r*A1$ik z5#&Za*-o=IH;Q5=gC{mdNhQtNS1u(sCf`aF?rx{J+pJeEi-31`F~l0XaD~99w?-zD z$GX+Eg!2gVK43wn#5?FU3yty&??QUqAU=@~0=+5{`DCWb4;r&EtHf(ryFD$qmK0}X ztR#aN-6rHym9~S|Gnhw zzNW04H6wV@CtNbgB*(vfnF6O>IxuHRhAFVgG@?zGNh{3~9!*ivO;OE=)B1SZ?`3BF zW;5Lfj56{*zKEO^kmU`Ox`DLaPmLoip)5M0=a3-Wzad(&{zuvrL!0=aH5wetmM z{f6xwjfb*Pf9>AnX_g0AbD6Q!GkJ0HU6VCJcNVOoEqChij_rN-k)@Tm-vf%S;oX-E zj(NFjtrb8<=^myRr>f#zfn}eiujv3UQc?yQh1bx8Jfkloe{;aEqa9vM_HW*N=H=zp zqbi*-M0kb-sBHP0ZZ-98S(UWoYcgVjeQ0CyV>r|+y7lkAd$hQmg{x&^2WNl}USwbz z`$@Z6qdVs>p4T1pFYJylxUk6O>irth_rckExdNmRH+@>8XtqPWH7Y!FMjYpPg* zl|CRW4#hjI2bp%-= zQVwqL(RSKLxAHkSb#5trut<%F#U=1NxWs*nVd0o-%{}~Z(dF?EIeg6qjd0mqH8wIq zZm2P@vY_D6F#m-Y8igmbd}3imswjC{<$D4L20(@a)L)}Ct@_ty@-+nE_wQ_=YrFh= z8u0$JM4OzbGX(-$Gx{BWCleK)`2z-u!UEH}m|mM{TIZ9;BH4l1IVU%pUCrGnB1$C= z3`G)A;dNKyvxoLPiB1>w*Wq)<-jQD6JlYkoitOeQMX0cfhV1dlaj6^g7Y4rP{owcQ zGm6FGC4bFu`#vHdiBY-(EIXPoK3w66Q}73YH}OQVLFMHdQAB-2uGFKJD;vi;Z0=+$ zD7o^3@4-U4M0${Eq685TcAkDoQ6W;#dVQ94|Bfi6u>O1T1h0;SZq+Z-j~gGrz;!Gu z2B;(?fytUA@Y5D?ruqD7nq;>HJF(5FCu0xT`;N6J#T9$2q^4l{^1v)`VP!G_MxeIq z;hwt`*6F9l?4ISrr!;>t8tz4s-SR6C_nG_Y%Uuy|-3*^D@iogq$e_$~*I&FiNLKQU z@vjnT7Tb@P{lxoTHi%bwGvuy$rlqY53JmY6wGHJIiYX>L)d-i~mguiwwV;cGMc)^; znPI`U91o<(kicia`Ama_x&Kn2Q0lXxVCvJapP*i^&W`nF>XIuj&p$X+xS2$JO{Du- zep|4=cgAV|X?)2zn@f#dwzTrniQ5N-Uv}d5o=q=zBqWCVviX>aL5@d%GsHOV%u?!y z!nP7C`oL78zV+FSHd93`9U&ZMRVfD|J(Y^IPi94i<*`m}CkH?P%Z3I!Kl-}h(O zs%`%*Qu|**SNq=kdV5;GQ62XDm8S3hSBi(tnm=27+SD$wyiFy4AH~HabQ~t4D`B`S zCp73WSU7hp{!U~mi;pG#bpdiNiC#@^8)(I9Dx3S`cKzYC1{WXL@Gl2v7V=u73g)es zS(CabyV^@~PDGp6Bp0G`?*k1!I4RkASJLs%%>1n3s^%iyfrn*HyMKng9n)h>VxPjF zQE*25zynjkEi!F|ZIhvaG?eGk1au5;lDaC(Z-l#Fck`;heXRY}aP%%#N+ORc=Lk<1 z!4Rk${*I~y6>b6T8q=Ok!xz1XnmW&*%ya&+$O#&r#g>Vw2g|ZVeQ|DaC)?e@4kZDm zotxE}O=TBYzKWaK4GBMmbT97sUU@3w?1uL&v1Y-34j^>b3{ww6Tx2qQPAH{U9U*wO zh|aKRIg-sLJ~dHQEJk8WDV$*I%g@Y5YDW`Hs9OmQInAT2D9?3?%x~#waaboEI6J3) zGQ`9xbAoPlns3)K5Z%#v#V}f<>h5pv2JJ`5wc%mO|`tAF6u`IVJjC@rS!V1r** z|Hw`vZ#sgXA)@seL7RX>PwT=tHkvrH{jA+@XdgNl8Nwj5li2xSZ){yWJ@n{RqOY^k#42)Dw zPevF!!`X$6a3`j|Zro3}wy=NCGwQ#|S$a)6bI92x9(@sjSM*5{2Mns)+E;XU+0vUf z%NC`#YRw}HFzrwnc~RYhwckV-C_Q!Oi3sLzNY0Z@wvz7*f-hl{{js~XKncS``QK(f z$6*ZcJcRy)?3`mU3rcg>?26vY3C{I%wnGlz<{d;9%D<#p>{StF8}!A#4pohd=! ziP8>Wr(=m3$2iB^A{jwBy#Mdi=lALX$%L{rxS>25nCvEgB=-1MgVb9~f| z_~j%?waole`Of3n=+MVm`U)TDMS2A5WuK0^pgvF0B0x8BC}CAWz_e5<4=(%jW~*mE=IwRQRvA~|4FwMM{e z*$D}byfDhIuDHLo{i2bW`1>FvtJ60b!`%Oa@Z{9FT@zv;amY5tO69gmK{&WzT)Kkg zTNj@QePfh3Qf6xS+bJ+7Tx5zTj3RF8^vU7-ex%8s)N`YJuVemFFg(#(P@iO-^XBGp~QtDqjU z>GflDbnF;a@fPje*s z+@Gh;GLLPm-k5BXf+^?!ofOE-_oU)#J*uF6;7~@Au9wZr(-$qsUeTPd2NalNj!@y` zSJ-363BhxqY~|HJ3a|)$e$R3Zl_Xz6&QFg8nNld?Xjd!MEEn%IAJ{JJ_CH(B(UsLwiAMds!S4s(2~kJCAB>H-4!2Z|>$;Oo4-$^O=uQu(eD$ z{SIdPB|Bf|Z90}AW-hFP3qGdN0i9>U*{a(eB<)`9-LwXtCxW?hpJRI0X`yixzQy?W zg+r6Js4DGH#T?YXTeSP@?0kNolyS#Wj)-%L^to3Y;z%%_nw=4sI|QvU*@CgiUac*$ zdlPUo%N5b^Up}a+2gsQwkFa?}xy*bfIn3#3G8%W0#v>C`7u2;Occ1UR7&4Q2Ro-%t z`rt;glhQg~0&djeWfh;)L2kLJtFf= zHkEX>8IFkih>h1ZGoB2jjfo&8M7EEaKL4l!@kvTxwMoSCCG>?pjmSM4^=C!LH~2lf zia6}qR{J49k6>Uppz;+-r~a3#w+mvbUDJH#YpN z9@VbqdpOJuOfZgp$VNLq7*8%_npdrg64H=Q<5i;*tnrQVu=gcPAqf5{Yp3e9KI(gal6H8 zniLNf4IBih5|U=umRW^X;l;31SL6&qa!)S9nHl@J{2M~w%HjTlV7$QL&aj@JH>4OW zAX=1m3<=eEIG>;SOTcHOPww+1LpCRo-mR5{&&vtd%o-r3)t>aSSM;A}IB4TvFyS%x zJ=t1G)K>Xtrvn9JI3&Yyl_sQutXq(9CB^blzwyrozAl3z=74dFk#(qVpK;!}mgVX= zgcQ44250W9fu2mMJb27;S9g*t<@3Fxt{aw4PUJI0Gv}^__pL~0pZd{PSBvXreFTx%!#nM` zFZHE|M|~luQc<`U*_OOF&&lAIvn+&l1!G9-ub}3M$tcv&VuP#n<&H8>*!%<;S3V(B zK(9edTp@{xf$y__cICxcF=}4d$^XOtcNGYh(7TvXDu$j6QbxnSx47&YC)vIaJD%TN z6S~?`Y~v%RTs7mg&*EGL^1~|Z8CdE7ZNg>dwFix~5Q%7Kh(=^CwvnW)Y@{Xq%i7xfkIo8iB41K*2G^PQS&$FyIf_{*c`>#w=gw zZ(B8x<|W&OpjJ|K>x>l`@W{Gvq}pAW?>pr!MW3=AjK<a1 zbA{N_{yu!Gy z9&)e?pwsC$KV-TXCxVBod^eOq5eK1+d0;1G!D|(qkx0M>u7j$Zc7z9@dE?(SI7=-O zSSyK&wRxv+Ap&m8#(OrI(!anBkxEh@^_)8@XXruPNBfIy8DI6!&|D!7pKs0H{yHg1 z7=j5y`1SssZO~XIE0x_~g-C`0lw+-ljGZXB-0JDYtmP2RNQ%(a8p zl&=n6i`7MF6GXZ&WKR0RX|JEM7E|OOv4lT+vz8l}5Z!v9-4d|Y|4ChoYWiLB2E;QL z7aPUsX0%$0@)fJQ>V^$vmd(NT_?YvsR3Axe$2#28prkbX{5hti>)Xt)SCHRM?rZoD zRx{XsYzMH~&BQyC_q18^+*I%k_8s&aET5_+4sy_!d7bYP3}8jTV}#(8U84% zs0&g>$6`=Y>@RZ^#uELYq@;C-?O(Ang|B<9M-G;Ivf`Q4X->RKsWDmxqlz1(>Hp0u z$B9FIhO$^?18z^+S;#P1#m%tcu<`7AOeB3HCukEoGzvaiStAaSjlw~~drV^30^d-K zP%UQI1!j3p3XaS*sdI6w`|RY)$eU_4`51heRR3Y^_=ciOL?Uh?ss9@1>rMKb3hYl+ z3++d?w#K`#C@5j3dtw;4D_>-O$5XP3x_l&Xi4>y=GzMG!YU4IoN+2;>ZANjp){8{h zH)i`1nj5~??LJ?IIfHHj*g{eLO6l*u>xHiWo@I^W9T!+87_(khH^u9)(}QYQWB!|= z8uOvrlwqXFmrRE~>-6u68IbHS!ciCIYg|WAQvHVWAMxf31N0_TmE^n-RlPDDO@S;V zh_~Ow2S^P_9KwBVccuUg$@Yv7_j;lCAtidzXCYKEI&!IiWp%0mZGP2bm4&$=(_#dv z!nN76?KehJoFFhQJ;XxI6^MLWWkSWE>mbpv=ATZ#MRipf$?}S2!hR$L!QfQ7F@k| zG+@NUUE58Tzih1QdzDdU-bL$5e}!`~x2O(sD;a#nj& z2Z2Mhi#%*`b$4)>ar_8BssHpMINskNZ%r>YrKD+H)Dw-eAgMKED;|Hu&GpZ>ndc6B z@$phnLIl7R6Fg2R2)mKI&VsVy@6AY>S?~x3W5det!Qhf-r@>W!SY3&I*V2@i2N&o` z8$CR}{jhGXSsv7Lkl2Gi_B9bSxY<9%A_>s@fZC zO-`uUGeI^vF#QTc3=4lLtHUD`kM7mM1zFQ-E| zDFT!1hm;TahhVVKbTiq$mOlDI@zsGz^Y|M7k^hGPHN0`O=`jQor+^G38-Dn0y64ZtEKjvb; z|0}UZl?cz56ffC_6wbE&;|Gl$6x~kH3(?nC^paaFV?pk#NQ8T~*jzNT^Tt?{Fmx(|ZOrj!9HFlw#ayx^CLC$WLra?F@!?64 zWB^6RxS}cF;uxz1Fxa-lnv;j&j=?z;)CAAgzZum#)0A-DeaEA%g$x+pde8=oZeBk` zr25E!EZOMb;M-tUp4%c`X&#oZ$91h9GvMKvMs0v35aBWvHu_SIHar%p^}*^cwN{PBHwT)+4f`*kv{G~p`O_Z$2@2&Hzw1`0q+d*t z-rt4#35?TmA5(OV-kH1ykoGioqu*d|-~!+5-aDbxt91en&@cdP3k$VSf?VMf{t96D z2#W>pz1d0davg5G9%{iBW3|}(;DA57V17;Us(4|X()JW{)!+K*Emyi-`2T~DURFy~ zL+_&dKz{H{_H$fJ?}U9$=$Rt<5EI=+V>yiFe7QBOa$~q0n52fN8&>clW&z%MV+cW- z47+jLwk~*f;)U{KiCC|<1s(hp8!D+=S0Y?U^#Kj#alEF&C;a%Kfy7$N4VQ} zQTbHwczUea7@UTV`>cz76K?12@?1y#5xHnHj%i)~H|NO1 z)cDovapANlkNJO>T>8U|r)CYNjiM%}b>(I#(0*nmvS6p}gC1JZHM=^asV-HV*M?u; zcK5htlN~yzXCH@&`6dH`TlU~UTqjqM4f!|93s@n0l9ijZJKU$_@wXqJ&s6OP%h_h- zjYievHg<0M31KNPV*9{(3HHqh8KD(!3EBqvuc*7bW4O6_QFEH0&gw1)b=FoHd$FOg zUPL0BBO^4QaFnfaZJnrSA3WJc-zi)+va(m)@{W^+7u#UK-3VCv;18MuxCObkHHL4xRMPwjl^ z=exFp-VaBAXL8*hE@hcqb3K&p5)WdZ4V0ZdnGf}T4J#UkRqg1 zC-Pe)kW4oSH|LCN_MEQ%=-EeciT}Lga#%1roCSS2s#{+7oIL{Vp_atx=PFyPu2M#3 zS!!tU7WuWQ7c-AHw|Mn?>AkI+9|Hqp_w%rwAoIsqCMwd@L8Q5ej)>}s>ZQ5sEeN6=$woTFQ-l; zTb-?%L`n-qv`ZivU(&UVchH8Dhwe^Sf78kREH2S)RTHOeu&7^5SWv{P=R$9^XU#%L z4nJua5^eUVm*X}z%6HqON~Gj|{vo?iL{@X_JCTg-Ao4a1QR(doX;-q*_+SPoKBg~j z-3RptgUUUS-^%vLrDBkb>B9&SQ?-EHzoO-h8M_fK)OKZJDuW_vY1V|L>&Y+fb^>MfHzQ5s*TvOdY(E7q&M zp%#_HMfUHBlwB#%02cw0OQhi%aCZANPqRfnV_2win%%Ne~r}}JD=7(y92%u zo-soEd9*FtKUT^mrJF)2K?JVyQDjpFWbBp+tfD|QqY~?1oOD2j<11I%tjgyCHlL}> z^13lX!#THXd{ObJWVVtThG6GywXZ@aN7~ONyWu*4fuqpqg;W~Cpz=7+06A8wJ!h8l zeYps>U8a2i%^$pgTfI+L`ogsr)h14Ffcb&fyuwb?~bR;C;LV@PNJ5% z&!7;htq1|j^6H2Y&;W=%Lx=lG6HD6aEbWQKO-qVwW-_gE9m#UKbTegGi3N!sVVB4K z9GYQwkg}!@42>!TeRxrVrP#cTDhfOc={}2SM{aAgp&z2b_;XUEhq;?}G#W zfx!_ux3JZ1{?hk!zl(HJhXxkX(mu{`Zr&JVr=5*vAPO<(!5jQi9(j*zKGTFyD(;T2 zF#a1n4NgawxSk%~9fY?1tGN9f`M2Jv&ocK^y})0VIqYj1*)B~T%R2s|SkL%C>RI-< zDE;?&Q@LC>+$T8sWJ*~jyJ3;g+GZRAnRMM1=>YdymNX|?2%TdRg2?oNO!(Rjwf8F` zhgvVW%)C?2XUrQCH~jq=YM=gBFM%Htnt#JNXS&bzh~(&2LIswcMocqAVL!S8Q(9nJ z9@DEMdBk;sX6Xok5rfPz=lrg?4xkqY#L(fbQEHdBoln&3kE$!q{`}7_-)*5U=fTuk zB4&WypOd+=EBw-!xNC(3=_%@ub^VI>n)mBs+Z>S-*~XSEmq$}M<~rDs!An_7p6hRR)u>V$=@0o;l|l{$+|2l zL9!L*HPDhhhGR!%gW87l&I|Wxw8y>W3B!?g=m#o1X*S-_IuNSkAoLsZ)K{ zvIc_`q!bB*F@pU;N#w!8q%H@AH$%zE8Gu;J#5!NR-B)f9MDlv?b0e~GayN@@tVzRi z%Y3;9oW&$z2W$X5ORP~*SIYWauW@5?XR*8tcb2? zL^`@bY;4^oz*_)>A7OSf({YE(={Z?gIbmoyB|gfS3CDbk+ePZ`z_0xauNP1>g0hOl zzbGgNJR7g5Gdb`a`rt*40g}!`Icza=eEc_>+jc_(!x?|M zA*fB%DwurHAPsT@JMoXBtT(Z7Re)w_;jE(sf;Io^xa31X+S2@mpCVQcX0@F*pQHWh z-Kk0u$I^%PlY(~vreD?&_2W={93H@{tD{fPQY5aRV^VC9iU)P7EWH40$yHR!H2!+X z#<_&Gg=LUo+GnfdMcnMwU& zui9P}m{$0oR|N4}>bD3$R0SI*a{!4%nI$jr`>5L@S++IFgfFBrU0SFvbgLN-9?L^b2}1 zvE_qaZ=?GY-2QmZYm z#aN<|V&1!eai6P8{&RV89j;|09_kBHzUv1PHi@E=p+fhXh(Y332pSBk!uW`yjQGxcsaK^ZQ$uUfzJ3{XpB*#EKyf+Ot7avcT9 z3XKRWQ|M2j>xFzQwa`ozl{8XrJZy(OdurHDz+R2LiPMMmE|k@(ZH!4gPa?j2tL9r% zYRL4h2_t>|H$3e{Ir{o+6ptL0r0*Ie^`9VL*a`fy_pxiZ9eSTi)fZLieHvs~{ZPW^ z)1HeIcT~{uQmNRvO>H^L4zo%doc(~#bW(t8-c(_yaV?^iV2M<9Q0T>WK+Ti!rCyb> zH}nBN0;CKTzaK44dQ=3vQed+PB|Iee;&`SiLek5#A|%o%x%ZC|*} zm^^r3KOZ0BLr)4~ueeTj{xC7D4tyK4q7JCETk9W@eE+Jn1IePqVreD{u>LTS&g(ru3r{q){O^ZuXuq;{Ce zAoSXYsQeACgg1P52?J4Ap~oF|&rIJ(uw2og(~^_D;efFm`Jd#%)OV8w*;k%;DIFw0 z+_Mlm)Y%Ecb-8>58OW0RcJwbP`L0j7YwHW>ULe1?2jFz}A!mWX+ahT0797+mY5fBC zbH#%@e=p;!{ONM4+bqr*Ws@b@Aux zf)r{Z6UJ5id}(4)y$`z%mi!P^*V3Mf?HeuD98088L|+AWZ!`w9y8r+Zk(=eS%v!Y7 z7*25#*MM5Q*vFL8NX|Qdh1TLL(-(3`u-5Q4{b-sppBW0R#AW=#ve-6-ef$(7`XcAk z2SZ-fLd|b0?$cY*+0i&d7d7a( zIeg-x;?H{zDdATC{g470J_02wNIoHD&v*EY#FxK(rXNTG$EXU6d0z!!^ylE2BPUXB zH8S-=_(Q4PJYeP&IJnm#IMhsT8W}M3Qy8|1S6dyD`0HvL=xROjOK!--i?8YIcRm}k z>W7+$m0ivLMN$4nyM{4|M(7vJ<+ELYG6J2UL~Km&6RXR6C&#cT=oWK~RVqpIN&&hZ zMzr!LW>SESZSBdNX#|JM*%K*$Fs{bObv3s(c(&xmb#>fAN!CK_+`?1_WBFroy>ic_ z(%YOo_k_KEh0Yf(gdEoc>qLLTNv?$)+XCoa82)4{><|jx2(I(7;`su(AG)1j(wJYY z`+O77=dF!QGaPL0g19z2$X7gx3nO>)TGAg+-zXGm6yyEu7scaZ!IPg7m4Cxb#XVg) zl25n7B-v!k0c0C=4*d3S_4&pLS&?A{@9*^m=@5pB?TCE~jIVVWb*>|l06hjkpO z#yXZ5)gnp1&OH7{qBvRT zf2MV5Ay_V1g2aag`4oTBOKpPrY2>BvfifN;^|`~ih_ zVdIx@`sxbD+w_0Aa>s)CLm#`!KWv0-|eFzf5@BI+OB9Oe(^&2-hwoahkD zXGS}x|H}1gLNbD4TttQHf%{CdLHUOXcLaqLi4`*ZmlrIHBJPeKkcLYTbtB!ybGUvnv0|7Lp+2d(CL)uZra*SqK!3u>d?tF1 z6l%BrSCWfnp@KXI{~(@^huGh<`f$oB=SI+cB2O6X&_kLhRq_4*C_18^=jvYP34CMs zT*7nDmKN`g#o*PeLyss4*fKDyaN+GZjW-5rmlEUUsd!=s; z3gv*W0oR4HLr?ii;~y`^5|)>ZGTQfw^<(+IKkXBnmV=T=#69}4vS`6KajS?o;(pd= zfbYy^Y8=TF_No5}IDYIbQCvHtGV$gUuYIu!FjaMf{fFVr!ylXKAJu+SnXp4H>32H+dB zKLF-YKI2DfDn||dia$K2+BkkAvW*(+x;-#u{E()ym)g#`xJy&4sPDJ77EjV`iSuaC z`LZn+bxqFSH)=@Fk3o%-j7cx4pQafCaj0U%v#4RIckdgVB6;Vf>Fvd{%Fp8|1B=3-%73 zAIoEA4BplS|&$XD-g$wTn@87xnnOtFO-g!?~*@rpR7AXey1qZ~c zK?$fkg->klj;OvqQ&n2laOI5?O5bg0|GcrrxQ;+bL1)xZ$ts$a7}bJWbQfwnp5T8e3$ga!*OtOjAh7 zF9J{856`MdVVKe{8xOhiZ%_b(6IRNC0OHmAlx_D(Sn)B z$QzfM!nKEfi~Z*32)$4E-O3v`RI2j1mN52=$aG-2Q;w9IbJ+n$gJfTjvvbaJEQ@*S zcipTm25)DQS`mDr_5>W9_o^Xyx2#eraEQDxKMxO|Zb`2Np;(H(G!~5)yq_=}(i%Ef zSakjJ_3NPD*3X|CUp8gtM{|AB(>DZ#pt{)|{6b6lgkd3BY!=xVAuz7Jg(d3v@nMTZ zM4RMQDZ;lbz4Y>)OYc02Y z45~6^#>B|Uy4f}OfBCts@?M#e^OgGjdkPmTryAUa=>a+=M^Y`nmrjh5Q9`vFHoI(z zM*kIC60(!H2BEEP+fyP;*R4EjIVA-zrr|x8C0&Iu*&|%7Gb*kfs{@iH`3YZi8DVHZGAf!aZnciZhCQL- zJ8lIV4#_bA&E@>ph749$hsuj(C+WKYWnXZQzLz$;A|9aq0nYU``^iMrJ)oeny{7C< z++YqOp>)oT53tTmfD;QC>!0zQK4U}fxOUCTy62`gWzDXA5@dSV3dZVy>34ocDs4du z&yj^J7l`k)%8pPr2FUvuFxJ?`OX%$Dne=nT-u6EaY`%yka4(H5(ic{ERz~xu<3eLJ zIP*Dp!)6&;YZfGcQH|I=-t^wErjtj-zKPJU(P(&DVE9$9Y}_taP90$DJnvlfRBW^$ zut5)#B4rx^x(ioNMXV$Y9)l9{5IUZ8L~$g>*(PzN$%0>Y#)@v2aV4AFN(s<)CZVI? zBJ!rVD~UfzJ~G9_R`%4*FId6Y=Ua1+H67e0^>|-&0D$<$&v_Q-0jHniA2%_}IK3|# zicz7eJff&zz(IN|+g*I?a%tRsfBZ3c6z}3hQWa}sv7ylEL2xt}(RIfOa8D8dC z2|D{{drq^I<*IDp=i~XN^a{fcdNC5b_X0ZJe{ZwsM<6nFeo2C0$dZ&IK|F812~0e_ zW^v&A<)!&qV2bI&C2U`#TVw6=%@!&U`C#{QqK}C&#e{!_2bn0TbMQIyvtQqnrDo(W zTD^*kAirI?WTD#AFST)xeo9ln=lel&!l-0LMA8kTI>e$7|Cv zdt+a``sjsCkInniA@`5L7PMI8rMGNF=|8i)=*}2b+>tt|8@mdoP*nj~zkjy4w%Z^? z1ycCx-6#D#!{XP61=Hd6b)?E+9ISWWt*bz~K`OiLxX-x6Sf+^aOS%^oa#V462PvQ6 z@A0S1PT0(4LQUcPGAgM34xuyH8d!-~Y8FyjniB*`iHr3OO4W=zcLS3VJTJ6FI~7#sgO>Wr}nny5fhb zv+=c5RJ z_y(cL^4?{+)hAs*)O9&=eGR>*cSp$Zm)bKQ*j41ReZ&4vZDP`%-i;pT{YMwdUDhqG zYh}c}w_}hoDB4mTrE5IZ9PP%7DD+LYZ0#n;&YGOXV%rx+Z~#2IO+d$**$~h zB9yrFrnHj766Zb@l^%+JsAA&Qbj+sFJIWo(m)Qv`yP^$!V6Y$wo@L1N>M?zH)sWa> zP+8p!BQ*wC59m)?jqmmOP;_XLEUv3d4m$$^t%f1D;2?#J+PLxE+xW_yCBhKhilXLd z+!|a)I@yke%1%aSMjMd6kJoE(exab}9DEt=l%N`rOsbs!w;con8pj{d-b&X{DZHf) zOY)cs#*(|6uHM~k_pU#}ErCdx5T{ur!;E}>>p{8N#Ew!9rEjt%{+4{GNY{ZfDn3MV z3qbxAQ!*wyk|wqZ?U<$cE$&NeCgIEOm*XHVl|YQSd_%EbT%e<_hw>&*fcoq=2$ zQ(6(P{a4lB8?U`&4nJs5+`i62swE`VJb*a117~Ajbb9k{%V_(u^aI7u&IHNtMxn@X zr$epUgix1yxfqyB7RW=wvFgcj!rb3i7;*kHPWa`?;=_WN5Y)6XuqA21~dvAOg5x95pm&gmk0w_JX;8~vBAr!)M`GH4R|<1@CvIKz=+yL9bkKfIGj#I6w`-`=Ns)A3=BD|XaEajdx&Mr&>s2%u=PtPTeh9{}4YypIylzz& z)sTqDM379jlC|u)o%~>-9`bnDXN^Yp#7~`&x`fOGT*gXe1PhW_@;DwjJ+b@?741p9W={4 z=E;YZzYcCs0s0{(EJnkG^&2bVY|-D?B=;<<@c7o8PWsrVu8WS4URAvIY3OQEWaE(7 zC42|v0>NVW-Yk|r+#ldsMK;&0DTGRCJi6n%d$8bPiIQh-y*v_B98k8v`C<7!b_DM_ z+c1>kJ!RVaNuw z`S&s-^dd;Z*lzDIzQ|bu{c<*xYw~^{$U5hkY0r0#saUscZ-!Pc)Y^*H!#8?bX-X`mT#NL|y6eUCYkb^+sK5(%rNjJoN2R@=bEu>N8G_4i27ApRSjb zR7fc5dI%2;3@f1Dmd{V9$~6a%y|$7I_Q)QI?nz5C_!{p~C~lX!b|)4u7KeGytjXW4^i`7$g1a zIx($;}7>vwA`yzX3Q7~5=?`f}-w3qtM6Ea7KYg#H7= zWl##-tK%Z%YU|CqX3964cK;^N?y1yt1E7d=V|s7MP# zNGhl_Djgyq3J3x!T@E1~Lw5;C3P_hhh;)P0&>#XzH$x81kOK_y?%?;C#qh+i#I;^QJDpz~zm_5)U4Ok)v#a*&;9BmRp4q!PA%Kwzs(L75v0#rP0UK>~XO0ocwkt#M%(v?cqtEE7wf(38a9w$xtQTXk{7 z+m`F9moi{gy;@N4N5Vb!aGuQy273rRl|0w(rNCfLDj98A_x3%2s?okEG<|T^mSKK1 zHQmB9{ob|49WP1JE~1_7^G^UtquCK0#Heh_zuE% zs*;V7xpVAp%h=|vg-g?ouK-H(ev-qjR1C1#=zPslQgY6*c=EwG^J&v0knG($MO_GO z)DdBh*Qj$!qi=t>$`=C%)CauM^S&2qd+OJ9^G@EwmnwUIq&;uOyLmRHV3w!oh0nu1 zUEawFT4tUQ@hzmRZhAxJUvZi4YD(40vj03iT}v&RV{Y6@v6YRA$%nIE0;mIuoIg<(rYkhmSV5o1TKT8V{MMiHYzPr6B zhidZ@Lhv`;lNzuU1*RX_i#B&}zty~v#1pm3_?!mrk83Bp+kv~=(X7Vpv{+DjTkT2j zFwV-dzL7AY+$9oprjS&QPmjmA*ipc>6&Q4>wSMk=lb=BNTfwy?_WvhFmhtdqy$00Ig~LN z?tW4=VTn0@u@^atc`*yLwlGK^42Z(RAT^aV8oX3O^q&qlzPPNASDs<+3DW~~4E}z_ z!4bx=+28y>Ex?}>#5Nhp1?gqTq+#_kE_wVBB5uRZ8>03>?VMYD1~Rx&MIwwz^_+Q(Kj%7tnlX$4JuGt4!#DT%8z`v%0~KuIkN>6Mog-Sr zgQlxioeFhRHP@;ea*0dUjPL=!Jh)%k{(;37LwB^S=C;!R#r-XEbW$&f@64E@x*pVX zJ>pJ+*FZ8K*H?6QTlJhfwhJsiyXUpp&!VbO7qw-%leW6f9EfbXmEkK+u=BtC>o2*} zM#U)Z5^=imrPSAPf90>QH@3hl6Ni+r&J;0A7gz>$Z5dgIM(6V%q3edtot_?+-oo#g z|0XEa_)wJ_GUliLs>LWYfH;~H-41IN2~D=^gMD=l0JzpkTtCgZ&4Gk4fFEvMdY19x zH)h;xcEO>Bjd0^uZU6JVPZ{d~AY>iqAY7$Mq|)@F_M)17&jrPkWktCk#3=K>PI+tS z%p9^FA}ZmM#2(4MQMi>&Gy47M>nHg%!FpaD69@WssQtJHNs(auYf4KAaCnvvzgOs( zSX}G)qe3aB7F0@ON1{z`w8yy12mmt>|1lF55>Z%AlD#Ku83}Z@VQTG=ly}IWdr&`( z@Cke;%D_Pe>Z{dX*MOBo!0me@>858Px5zsj1PHB4WnNm-T2)VtW^g5%0u^Dupk6{u z?mfUjfX;9q2tcd7y#gTX5_ON=8lcoJ|FG`zrAab8WNem~p{n1WVZWHcI=Xp5+J?bq zEFrZCdGGCPV^d^W<@$~tG;E3Usxc!~yTI+MY7Huz2pOy&Kzi~QiAVD8Zv(OnIP>0o z0JAQPP>gTlz6DlmPvKs*AEs@Rn8KL9o4@UTOY;invFq$9xa$uu&Y5+?7oky14Tyo_ z!I`{AN8FwAcXrpPrCl*rM|qhZw-yeR_7WYztVs%Tt9U2R7bTcuC5BS`N2e`1?k~ov zW(@l0&0u^z{>Q0Jj_L(@UQl_V%fA^O#w5b?eJOqnelx5BhrQI212)@Tv3uVsWf;Vb zY^vQ`@AX7&)`eTlzQ96;6y_^XSL}=|8{4;+Onh$G;c7Q#4R_~ z5>^7+dTAafZ=H>lT%sb-|0MxXw9$qCAaT`Ga-i}NkX9Ml?08IxMhJjopF1873Aig} zGqD?V6M45^a6l!bVvu#+X{A!9fQP$8Oj@;Ex{?N5O(Z7&^Cu{>1l(1Oe)E5_)h6?^ zJMJv&T_=Q%Hf_`!Hj#)xyD)KNvR^IZzrSJsF?w~~Id;ck4cqChOI*v4dQK% zl13qEwSSFJgkD==!Z(3cQD8r^t8&z#buKwvLXm<3H>s%IYmwHV0H>ylBfHD-v)aUn zccbUmO4)DN$OW-`nBlei9274eDnvOmz>4Mq{jd0cS|4IJbtMzS_pwT$ZexwQe%IGO z-`A<42Wu=5cw=rtlV)&70nscSsIY~bxOw^$$;6vedS<_nI+xQ#^4$5qit5?{o!bEh zv0UAfD1{R}(=$@*zgObIxaBTAb)kT2aczn8ea?yP+EK*lFNA;=aV;VIVhPxioEKjg z;J|*p78M}?mYl^8$FlKFTUi5V1*=8Iz*?o&YEj9M&esL;AdWUS*_0eDtI`n~TwSXW zwar2ajdzm^{U8(9x?KlcjNYA!J?iDG-kUv-UUYJD*a3fll&ZP^C{D ze4BGGe{RbI652zafH^zf87yTM8W|IZKk^=1J1SwrvpYrJ%^1DrDBB{>w(Gy z?w)6!k|fkSySG`3-jts8%y{w>G6b7P*kxV^1yMTb^zdu3{CrUEXr*T6)|S90P9*>) zte~N>FQjoV|FG>+dWOChjEj0P_`o*gfmc7wgTRab1|Gt;b!iIXMgCDYoJ@A!GT!ZN zz`zi7Jg9O&FZV>l89Q=H&^-oGiv?`1G4)Lfx63zvFAEC-X;n9%8^MW#R+8_n_?~3E zE$F1j?^q~F9G?sVCuQ|~@8o&Lq-VV=dAl4HCU5G<@#_a~T30_dHazO42bk6-_v?UJ z0$5OvSG4*T9WukveY|Q5>N`i8F;_0~?`Wl+5+YSTtG+~dRhx@Y)GE5Qr5Y4CP%J>} zxe$_D`pXM^1b9_FivpQ3H{HfP=jO!czDS4kt@RbVF5ScCCe3r{qnJ_n-Ynrlh>H)< z)qqsSFL2%Nv=jApyE*YfT;gQ>Z!y%l5lry!Q@H)D1EE^tO!?%JdKloBmhK19)m2uW zVU3!-CGN6uQU6~yQ<62pkLCZ8FvOo^{8Ai7N7(9UmmIbJ2XwvCc{}I>_*sbY*{E!4 zfA4+p#hm-LUq~ePba@Fy_>eXB={-%ME!{Rg6;}I!=NL+x#a=`Qp8c2O2l4nwaj?AzRY#3g0?3VC@1Imhc9-l ztoA2t0$5l=p)KkkY7F?8!eNgoh|qm9LsfR0mIDzs3# zl9q zpf#|gN;3_g=pzSnWFAWr2e75t?$?Q7V@lK)H2OCji@lqNPe-KP7@E#A-yF~9`Z4=N zvbaLXIEeW>?q+eYm8I^_?(gw-imKXjA2%X*2S)2-n$WJZ9Xz93OG*6!TsUaz}~i;5#aV@rL4TA^`CV{Jh)Zp((u7+9#kopZys zIlQ5BP9@xn3_5#;a9tZ&D9J{B0akyw^&ixFy=M$Ed zXkYS+83@j7%`G9j#7zRYBndvE7TxY;?=6k9)k^-AShtWeGFoH2F0pi6yMyc&+mBbz zKy;l`-?`dxctH@UMxcj%H=jPCu#eH-`m+!5q`%2@(Y$^&61k^PS0X_)eX~oVW7%lK z!km~2ST1}*w`-EeZPuEe=qQ`L*2+5^8HFg@&KMcqe<``2F3` zuHA?`O>))K?N>-i#^98l0%kA{G-J!8d3d1sHp%;muVKWr_cxu z3>upM8t6U%*m6$*!WUw^f=c;6lcLt-M!Sr0$RmKzVW%{6R+D7@vJ`bQKZu1wgUXGi z0AF_l{Qw7;l}PZt9Ze@)UAv#2eFrFt$v-KIAit}q%%2ob+dwGYqpt?cK_xU6CzeEc zdxG~QdfxH!V#hEl-(MM7Mrx<0euK>uq-*4^6c)_`7o6e{X6|C?>SYVh{lS!X;Nr(O z&35&^6GC)yO_KZQzlcayVW5tlNn%Se;HCQ1)3)U3P^**egTSf8b{@xN!BB?!HyL2X zn1JQuWvGp1Hz%?0vdR8Fx5lF2M>*D}{XSv)ce6}V7p+Xk)mzQ|zJc|V93*%x#Hefj z;h}m1z=*EvfkJ|KKvqO*P1s7u=pQbn%_#6y_qS1lfc`Vh zqr+)z88C?e-I;^rzkJ~MG?|5kTY$r|qjPR9TGrJDIa;?*Fon^zpJj%_49NK0#D@+6 z365?1^o@Se4O{&{gxI^dsp93jzn#=i_lcg?vx`mqEtGf?9XM^w7&m0O z*uXR+8o+;>7_Y?#%r&k&rEsb{G9de@U#3D7ha{k$+y2a)b?CRshptFM6Y9#Bcnj2g zeSxnU?yt*&qm1>%^x)#Eh+^jZI;Q<}W^;a*kqYpF>IKroB{Gl6gOgas96iC6xtmVG z8pYGR*oHSKHnD9JE1wKdZ-SDw2$%-5^XIs2oON0V2lWe!4`w*;9r%QI-7snU=x@8TZ)nu4l$W39Rs)&uJcU+jr&A)oHrcksOmP$B4W*vk;{5p0(|n$p(l#Oi zcbl|=#ze1W1-An(gO*v39;@1elksp7bwE&jS0i=+b^F$$iE7M` zm3+46QejqJFx$x4<0-0sOS*p$j;*W`xJ74J;pkm*B%-_WM;N~I2TpGk>Q;Uc)NeF^ zl&4S!%Ho*9h)q7cI8a75?pe5@TJ6_}#G7UesF+TPCHB=sPT$rX^T=k7?L z_pIOc%yq+4eXaAkmC>Cxd{i4BEhn*OcYn*!@HfMMO_v8+dU}fs%oiflwrFeNGrMAs z;e4O-u~KNF9giAzi&ot!!Oi|I*YFBNCGbY?n=o+?ev}aJ^uB0&;Lv8GP)MjENah(i zp`5Xk$~uG)j`_PSgAzxJCietutf_kxX$CdzG36*IGB(K?NH?W1`Olio$9ir-|bLuLBh&&pY zEC6GiV?-juNcH-@Jc&dYOH_E=qqKW?8OW@3()9S76QDfM)YMJ~a~RV7Yg3H*s*>%X zN^sAAZza^NTX=BfezBvi5}i)A++SfXX@yhIe8Hp=2&oYOffvFmMa*5h)dzcT8ppD^Ux&8Zh`4b-D20ur-3IiOV*DbR}B;x2x>e z9dG+n3MR~9>nWmC;Y$Nv11X0pu3nbU5L50&%V!+nl}X%bDI3CV9>b}Zp=HPLnAVq7to~(nUD8L znJ(T6Y}S(6p7x;9nDKAD;s(D=q97D8q1iIb7pNe01AT^D&=>7?r_n8H{|tjj(S$4c z7Kwlyj?HbPx***8#J439`?XKE@(m7tH0||Y980^J*L}ghKu;78EF11u7PdWkCr{MD z6PSP8bX?ZvC)?cct2dsf8AUV`>7M$Wkfgr>jkai*E#y>1UyQ^DjcpxwpL$SxkzaS6 znX9j3o1euGBz9xB<=0Lz`T4Nd+S>(!C;duV4gkC8bpY&cwn83|m~&Rr8&gwg-UrSA z!3QkP%Z#KeS8)48R}Q)`&34<8KC&-8>@#H;CmlSfG1jc8b2$Im*&qv!R9adqXz;#y z^K6iM(0X9qiGPHW$RaqH>K*{}8H?9+Vd z#^?)F493WrbW-g3AMK9C24jLLE<9c~M;SUu#_PWf;nfsHL-5zRC@98#Z?k$Q-_BQH zEL6Q9*AgskN~Y&=v(0qlaL@6MZ!t~{c9pP)l;UN!dbT84a}n77DfgTH;o@sl3c7iQ z0aTwLS#1gul1{5DE2*{s>I>Y$QdZtrB<9=6?7y%bg7E=&AK^=E^Sn%-`lo1+&=m?= zHzXTvAZ&D}ZrmsOqrBVFC7<5&QT+Jcghj9eZW|JJwca|X-9A*=UQsBZPG^sdAD=1;hWbTwF8uyvE}|taLgHsQU6TUZ z0RW|4V|((AG+0kG0z173kw4P8vCU`!<{(0H2PHUrU}-P_^oxes9spgJA4Vq4gFm+^ zbuFY?xTCb68c*6rnO`r%SdxGg+yY`(y$VE)!>{!q1KPT+!K|Qdn)mlJ@KAZRy6szd zhgde?LE1jcB~y0z>soKS{2O5Y+t*tvBwQ_(naPR5Rs?r>@kf%3H%^ruVCAdpy@|qo zlGKwGO`E_T6`(=ne(UDQ+W;J@&X2bVfMR*o!jg!T-(mQ*GLw|D)_sZ&0pnO|4MwsH z>)`*!orzX%R(6?we-o7#kNc~B;dTE~3cki48{+|?5$EQmq;oF4;?Yzf0!aJfW=8{s zYk4IhS_N<4v~94J9$bLZdWHgFc(iv&v1H!=4V!2G!bb9d-0S45 zWWViQB0~pY_YotR_gjpysU&tM5EYggGU-F#=uF*sXso3_c6?Bkh&U$${U#F4CK3ab zOOktEUomz(dvUysb!y+N=DZRV1atmmPh4#(*6ryeP92U$1l;=8=c+ROcaQ#S2WVDc zL#JkebmDAm{K3&j*p?(S81CM?E&yy0u&o8a88n|DKZ9u-USMQt4IPlkj<3?PD7F_A zd2aTAjSaxA1`=pEiyKApqgJEpZ6a$T0XwWzCHx3YgNp))D-j)BYUdk_v$gaKV7LHq zFG2R_Hej&=kQL*PTl0Xg0Hd&_#XqB0e?45d(=f}e$qy|t4n;Fj1-l^u;#Z6$1k$Js zQ-q|9@9bg&Pyzy~y%z=$)LxoI|IQ4p@rIAd#Gxz#&JQ+>Mh~xtit`ITGJ<63d5m_UVi)}4^pu#$_ z0sEicV|N{3aRJ;itA8ra*e-ZB9K1VZv246&D|Ix}(OLS}V$}Vjg1F|}n5y^)J^~;v z0XM7W2{tihFsjZ1=Er=e#}qx9Fe8oCp^e7xu;+^Ru+~ z=yTOHnD3cJ=E*A;|6mU64_BvWgb!>gQu1;C{L%rU5p4sBY`xw$t0%nrv)O~IM)*pQ zU;>%P?^+I4Tz!A(JzW+YkhlY*lN@F5)$nk)a}#yG*H>$NG#PyYGpzFuxvl&?=q4yg zOHCrM@O?d`_J_kwpaDD_KK%QP{7!gR5Sa-5dCk0%7I%$U}9<*czNSJVxr3s`$&Fpybt!HFyNKMd0n%w3k67VOb#XW*$ zZ^HWqDDz=3BOVZ-rjC@EH!%||Q34~eXb%%WZ20PkgW~bn{a^72wE?g_Poo`bRn6KH z);VaH=^flz@)~ifEQ9K8hE+SPb;272$b$j$KmYWQ{x%iW?S%#K=Mx9Vci@uZZ59l! z2z4lY6V%j7&Oi|6i^UFIS8|E}cle09oxyUdoiVd#r&JY#;gdudbLQhid413x@ZI~c zZLqeo8QmmVEp(MCFe8V^BaQ9te>d;)a zG?8$_hg{}sKoaYC^#Ng2eMORr#5HiI`0P)H-Rt&j^9#}N=_W$MqgypQz4GJ|dE5U= zzKqE4dTnsKQzg`}G_T6n*vKPMjfr3k=#JNHB)GzRrE$MJ!NwC?nKw2{zy+`sI_8r8 zz3IoEWf4I#O)NP98u1{|{Iuo_a-V}TbthJyfmcF9NbPPMbeH3zX8$wKDhQ$d^NJ6b_YPl?ev<^2O5}oBf)!G+MX7JslcVRUkjbR8A&wv-=qnPr)r@_8vrGxTAYY znQ+i&E7kbB=S%g>P+{ZH=akBf(AXg0kO%A?hRn>q16U0_n18hqfaVk+N7~}A$xz?G zM+8c1U=w)Eb$JSV>?hz;7^-Ew)Mom;mF)NSpJ&*27d(sO6I=dyhUdG9gO@pf+%&yZ3Z}%D!%DzY?{EZVsQtH*CUZYNVP_0=3pM8<1Oq`{}On zT};{!rn>s1V^_8RjRgrP?%ifo;rPCK66U`YPOF?;Z#JSPQI*pE|9aAQ$FQ$tLw+B( zb_6zd={-npDW=Yy$*uamzODC=L@cz?lX}ANwuKGH;KO|*xKU_elHx1YtCWt3*w)|R z7P%a52gKT_IdBgMv+5!qs;-*cn$S*l8Oe!r4qHJ7qpHE>qRf58uR0)K_>!no-C_qdCgTRo2-0sxPQUFdIVNip|9z$gEqJzML*l2q9fE6aOr#z12R8d&kkwW<>IFUH9PhV1xZ7@?aLD28>trC4 z9?_2o`#qj{E-Xa~g}{k=$^$VZyykS{6Z96v3c2HL+`O?>lOSiP=c{ETv24186CX{` zr!SeN+uvI%CfqqO#b~7pq&QJ<&jK{T44_A8f~itF>W_h9!@*4@+OO_> zNd`w^od^zt>ne>!`=vV4{iCpxlZ`hJG8|Ei#%n+FiCf4Su+m7m)Ol3&)|3HkJz4xotv2)**+s%Vh@ zZ$ASKM0s9|j-&%WC+WMlK&e|vpAA~?qwGB}6w`vFNC=p57YE=`j&@p z&_L&FWrZBpaw=CPrl=^kafOSLIja_dn9df+>*Gi7xWS+&?0qhtt@`rpNTzT2tH5S!a#m6Epr@MV3SHk9#2Z4Yx^tt z+G;KjpkH8*XMYb82)-NoOkZ*N0e3>zQ${-`q#H&g{Y}X5$bCr<6At!A;M$qwp0I9n z5kmqv(S`mhE9&;M?+VTxaSj|xaeyQf6?6%*>L{Ljwm=-2CG&0QGqvq@k|hN$FctwL zs5Jt)J$#U6-UGCfwP$!HP2eotoPT7bb*f(%=c_ zgnle%!p~*qbWJC1h`$MxWbu{DrRf;s%! zh)Nov;HF3)+Dl|in+Vjw{~q(wrqYJ;H`0yY`%AE64&c$d=4A8(kWq=9O*rUNg?AZ{ zO~<(VU|JbfKk59~AG~1veq4Kh8}0ccxBUn5evUgkdxo~^A?pUP^B(NBlN%1;z1T-^ z@*eUpJ`o|A+Lh3nBvO?muwwU##`EJqWq!fT&5M4T`SG#m@npN#w}!-Mo@u!U(R_#Y zV8vYGRdQRwO_bdO0|Vo>C$#A*$WE-cXyt!3W33|r*thXOJ?{95cXxV*YCKe3OK-Ms zg0Vk((E8D8iY*0h^}W0o4uBz##I?tjXcNj|8cx3dqO^Dydn4(NgZ{zUg&}gv^ziSy zMAPRpWim9eA3uJ~dQ4eGbNAkrYoFAgT<7_e{pY>UYIW0q&%J%j<`X5|YdkzW)bCmc z$_QdbNS}w6Z|9ebgx|8;$?<;p06nvZfj$j;yP*|(C(@)T(?_rW-Esy@I;9p?oRz#M zCAq(Z(R!`do-#oHCh-lG$J`JbTRF6#T{Zg|a?gk)V|&4!sfyxU->{oMMp2D{?u#Xl z10&T7WusUEa}uTla_i`m$w!CeGKj%jf;e7|78RYMu_8sq>x|E{pV+u1?eMpWC_EIv zee7%xdkzvE!JurTygAulqTDzQg{6%p(~eq?enSnXaiL2BkPO~m^F);7osMV5@r zU%@rt2u$ooARQ0>Z1<@+-nvEov##6KX-Kv?TwaiehhUt$V=o79ESKrh7A}TE{r{Zv z#!ido=-`7cxr)c}{~{-}OW6V&I={!q3~J_p2~FhQEc!TDamcKBa%UZ=G!H&AX)`dSJOnhJd)fVM>?J@zK0@9ee5Z5C4O4v7|Z7kOk1B? z{;N=W)`<_W0~UKE9KwC@c%z#I)m_X<<`6fU%e+K-lR(OOT2zk_>SyvcVC@h2?W;iF zywog{1_Ov1xX*l5d|#u^nvw(`w!A%TDM?UIk!6!iL(m7qhnrKLOS+%IQFcVPhXR{8 z@!?P;s-Rsdn?ISvr}Wv_z>}){a4%P39!SMIU&&s5^F@l;yRehA_t-$;rkOp-I(zuu2^UHtIn2~y32l2G(Od$2odIV9diOEsBjtwm!0Rh&$hWD$k7av6l$8E(fFT%puEcWItiR>iKau#67MmR2WLo%`r`dhWE4 zue%?h?5qT;&hOGg?IRyMgDgoAWA^{rN?E7l@BO0h{ts7WSvEGW?pVb?(1J7 zkJn$%E@h*Av;J)w?P1G!uA-WN22V7T?Qos|FWh&YnR1{-4K3 zmq0gt>o4`ND!pe?OEFg^a5%mul`8(;`g^}l;m515S>5rxd|W!}6()F&UlgR4DBKQ& ze-QROnr|!htoRl6<(h-zpX&I80{aA3#8S#(YIeaRhCj(<_p-bdwV4CI=!GYLzq7$u zR0933?i=@V5wfH$Yq#K*vCC69j`KZ}y=OS+i(};Ux7WeHQc#Fz1R2Jr_g>ti`l#xe zw=MWh1H+j1h1Sa|ti$!P7`he^jb;p=g zrH(+wo87vOXbZzD;mi;M`9+-D;GounMR^o4+1pd6ar*@98wEF0^g-I_ihUsZ_asBo zleBuR0nSwncC&Z*%S(*kMLm0x^qJ`>{YLri+Yk~9=@+c8Sx|UC9OA!}vRa!sh)`0d zIYch%Wq5lYLwbB~*gRvs`zOOTmupfUWY%Gxd~IEwo}X3DfZpGKqVDr!JUfgrz5oeQ zYnG#E?A;bEU9uq;+co>e2v&Lq_T(fM-oy_;!6VXvHzHc!A;uI*Zi^&kYLo134yfWB zb?z7n>|*eaxvjxE(;=$I{+)4c@1C-))$WP^q`+Viv)ioy=(J1%K0cfZ2U?Ox?E_9d z73iSFKsIG zF9trn7-ZX)#3};S+$SD<-+JQFuR!sqwGMkeMV?N~lZ2c!U*@w5KOTzO*>E9?t(Nv1 z*{sCN3pTry-{(nZ-gU5MNJH#ME=<*$Ch2BC7MD2>%blB;G?RVbSM+nKyjz&35*H~f zhF|yGb)wC@z`r_tcP`J{)Yj87G&K{lxE6AV`qTGU{)d){L!}vhpW*1QE1i|QU*qLR zoXxa{6O#Wf5_vw&x1N#gWABe}SXjUucYnjU*(2}%`g3710#VuK+x-rt30YC6QAc(BJvO)?@Z#bmNyZyvwPTG~stpcsTR735mYY#@;A<_4Qio zlJQ~mmU&`RcuJvK`J*4N@@jP&s5A_x)TB_o^k8<7oaUWU_22Y$GgI3;-tVP6_8JPh zia&GC4sJNgM|pHWPG5z+k|Oh?CD5|UjglvY>wr|BM@pt45G)cF`pYx|=GKA0DK0%X zVX1Z?ove{M`|e`If^Lp-%b8I-`w8QxBao_%>|XDaVdtMxo;|EsdO4Z2^%57+y_gNa z6klFQuIK7QA1PHWZc3VKCX*9g&Q32^Hg3;qm1R?|KJj;wilz!X(Zsb!Ca^ZTBUQi$sn9l4W`AsA z#rep?CZ{)icHTSJ`ZoCH$7_3o)^uBcRFULQ2`m{2&RymK8r zGV)x~{X}tAK|BIo^PS z4WZ)MpOJj$CS0DKKg!qaSl>4;nRZt8{^*U2-ZrnN?{`nN5-;obRF-sJ+8|PF*v*Q% zLKf8sTPMeKSi&qlM}E*KCL49EOILYDfYgSpC~W^T8N0k`UX0i@M>{_CEtP^DF*+^E zitVx@3-0Z3AqxnMwzcB7XZA=88%!BSrGG}7eDLA_0rsD{v&9>mWk)Xwun`k8Mmz8D zt>v&Y_x<2`>?$DdD$p*^IntjPxI{l&hoqAN?SrY^Hbemin+ru#dd-Y1V{aGN9!^+2 z;(u*&)l(B`bLub~-^(i-^%|K;FkD(&jn??c8!%1a16D`-OCHiA5ETrSV+n*`WdEQ=W@$-I3$pzX5|-GvBX9g_GN70&1kOynUp6# z{RDzD-jaPAR{MIp#RyVxVut32bHyR zcIWXFF-|nYD1Luy*5J{5ywxfpL6B?3#qK&etF3Hg{TY@otxJ6+6rQO_ku!MEIi7T~ zAhubGJ&!1~EvZ4%9Q!DwCo<1=T%6Y~)U31}iV~$tWj-L%5rKVv->>J$=4wkf&sA-` zU?^m3S|NyjIi3BBzV%M7>t4)tO<1!-;q_fN6)_uA|G_sjM~myxND$z=<2O`y12Gxe zpK!+eo6bxOB>o86oq6vbboT2S4xXL(PIWd}Pl+uYjJlX;U&JK-wqz(|*6lZPx0UIB zurqgEbMHLy#&5T?;@PTn!}HNP^NOvj`l3GD!&dH-+6{{uGmKmkHF27Y$K}EqU7QA< zj2BL=H0S%foizInDS7H0nFlbh0nXxuIei$JfX8Sp*YUz=@3xfBaELit@^?Ge#UYK5 zb&77stoiKe6J8P9W&ac3qv??2{hO&^OT6C?qnbDl94%Oi=XCz<&KA;Y(f__4SuZsM zGho(5tD=tAGv=9#JS}B7o{CVeFWY-rAFsS7=|^C?2$-5&e3+XKc3-Cr#bsK3AbJfX zPwP|h*bhDQiq!e&g~aa{(c77$HkW8!p&XKQ@(gOU*4O@BNp88QJ=MrYQTuG*_C3F3 zRbuoY<>NTlZak%Cy4qZK)lr`Mg;K-0I*f{ii#*$6{g1xc0Y;1OWZo5UEhvR{ic0Sm zVmiHgmm#_--gnwtr5wu`V4oQ1&?1uCWlLhClar}(#K37OUUN$;;wLs+%9*uPOC_@e zHj|&QE(|+ZI@}1qvy?q1^)ub(+aypS$9$kja~7eOK@df@N_qf5!Mu1cSU$`+rqPQz zU*}C}j_D06-BESL#CN?Fu~!9qd0#Ik8A+1OLQYv&x=rk#3*N+w5)gsfXApG&$30L# zPjwMf9Pn>-A8^PP-Z(&5i}Rd%-Y@W+xWgz$d!* zi5^!j)Ea{gfaqq$gG1??7b3|~udKLgx3)Y`u9~zw)6>)pqq#)B3|2Q!FI!VR0smEG zi{C-srSv`QpsEG2EkC(z!g9piwB>fbbHd}b)u~!$Ra5qE((rD^qtjoaT*pWGqkW!! ztIGBBK`sUkPsGtS40G&>l3mfvYDRvH6M0AR)OnY7{)UgD4$D1{ zyG+R($8ViTlyiI2rjPYy)}IGyUrFu{0mn&Z?V_9y`nAQYNP z{)xr&P}<@zbxAs?&4$w>A={&A*zrI|;ptYjFi-7gY&8?pF4*IrM{9}2o}r8{%Bp^i zMq}>hPGda(%Y?v|0Kf71(fmYDO;deIPw-no!VLIRbvdb@#{KmY#mE zsAB-K{4xA2mY|>=)EA6Yqn2`&^lFu1`EN=cNYsMDpg&+w7mH-X$*`NNduch93JXJ&{C-gW6LRB@wZ`AWVaF&kB=wOiy2|`?)qZ z3zlC@955>%@5Mi(4ZlpVB1ghm{FgPjcFX_rT#o^G%afH<=JENMlTvD(N&&)?+L>_n z+L(XjwUm&1wLsGA+nu$I*F0Wxw{q>5A1jqB%?-t0DLP&e)pO}2^;wr@HtK&@Iew>` zav+)Pc!)t2G1|9oh(c}SA5d$YjuvM&Us=~VPPdbmVv_Cp+wA0S(%x6TpA~)~gw=fi;*{9uY&MO)-ld%8Qc9Omo!wW%}M_Db< zHrf-BZPV)xZDO0o4|S>K3k;jiOMrz|ZW^rkl3Jh;r8l*Sk1nc-B9qz)@8!h;J+m(1 zt4*_>H|%^Cr~iEgyVavupU0wrI5KH-k_@x+0XQ!BF0iBJVIS zTfC?qh~NAwJgeken%Ve-nd>^&s?{of(lrvAm}UNv`CRp^GVR#AKbkleAoCE~&d7L@ z9V~yUtcNvomQxE-kW`+6k&Y4{3Pl2bha4r_&_X6L(YwFmT7uYaotBoQmYA!>Mf7V& z;P$h3ne7PDomwZbq~6iLueP$4^M@Fh&&fH)%8Ffso6@Y@P3AK+8M_C#b+27Y$$)wH z=BabxX=iqB`A^Bg4RxGnLsuv$jfuC|IFFn%PbwOd9hhI zbvX1=!wS14wYlT)HO$Fz8t+6cXzF=xR;u#+;}Cl7eda!xC9;4MyWB};ZU_5mCmyrb z-wif7IhwHtkF&?+vA?kQ^VkyOR>CUVX^)!M)$~x_dH}OB^@7TGx_}mgNr_mOkI4yRPiMI zjD(s9@{aB^SY(BwK!&^S{*K8Z@?ySEGIh&d)Ll}v%M`C|2$YfV6DgrM z*4OuA0E?h;KgPz6b9P3hu{`dH0?~04DWFb4B(+%6ND~`OYb2&Qi_;{0v7l4w@r$V2J#mD6?wU*I@Nzc+IXjMB71KM0NIME`0>Tvw7Ya7E>(imc`GZo$d&eIUfWHQ;7^HfF)J=r(YBoQkr1Bf`GWjh!kj!D zl7$y;FT7{fQeu>U^~;nk>DmP$T=X45fGVN?q($-GYV-79uM73*93GrZ&((v)P0-tc zl&CEdwcX8PKf6~l&TX70R|J+!llHhzWfy=_dZjPl0{K(hugeDT7ZBy@E@3kom_W(; zk1Ex6iSTdo8oYiq#x?q|?$fsxD}%A_(OH<7P3`CLY{oYTy2ky!!LDE?U*AoQUS0*7 zal1xqKkWbL%C2uMuJ1DNwWRgk$)QC}&U%%MXLkv3Q@MGajjGf%MjQT53xJHJbr!Ds z)GGF^smsRKUJ48aPSzfOXf{iHz{Pp6cs!BKH~-r|!7OoCL#G^f*84)c{%BCR#Is`J zzx8Wdgb(rPRx#SXz5z5h|DPuYngWYjFK+VT$SfZ-jc`8z{GZVO_`kh&w3i@5fb;#;ocwI~xN-qz~R57E&LzlvuK2@sHr#IY9^ zc^3J!s|r?QVLTfbB5)nS*pYNaG_6+%=Twvx(KjsH#GqtN@42Y#NQ(+{nr< zj(+PZT&w;;FHf$jGTzII%jf>`R3-{Wie&tt1i<0l520}oBxB>j z)l;0=6Ro|CAQCa&@X+6B|J#h(0)$fNk+@?7*PBP!B~9($m|Nc#4TS4T`M!KWc)pdW z!lB4$SaV*&EEoUnvCuv?g|>(rmX(cXOB6@zRis3wqW5~mT_4s_ixOsg^|<;hC>wY> znwKjjmli$gif8t@T6{iLI8~+`0QcRAU}`)q8oZm8xRv=DqYE5`C3E*un(A%}Pg-2^ z9|MrZ871WMcOSaW zHiuJd9Jj!98cN&mArAc*2ZSFq8@82;2TvF15B6iwXzJC8*rp0%!Owdh+ziBoQpvNIO=K#f5#$Sb+-?MF>Eg9? zi1e?*J<-L`y<_6KOS}mGfB1|r{6o-_E|My@-~aOk$Tu?)l^nNQejrJitb;i zh<|UED9G-6Q59F~G01cnJqn0WM%gE`yS-@MVjR@-_KNnfrKaDmQpipT`oQL_nzWwTryjiKj^=|%sNCnReg5jT7jfm zw0aVK7GC^w?FZ5S5bu>G-Av_=tSX&2`_!J0!YK6*_uWRI;P88C6Z&O>oc%8`sO?W* zu^g!{{y%KJ1yq!6*F8=tAP6XeARU6zA>A!4(%qnRcS^T_bSfp?-QA4RJ@iP;&^f^W z9-rrZ|G#g2-?i3&i{)Zm-e=C)XYYNTLz43?g?hW_z2{qi^ExBAC3=JN%kZG6a$ZKJ zA;{*d`c>l)hY3*q5V}=7E#`pEhE7brPXB9Jp`oSI@WH_ddb;q@?VIO=VF%7saY*PH zEZr)&aJMO_GF?zt3>6@rB4v+0+c`yRCiP>HDOCGW-ej2i-og$2(S!~_2}?#8|p zrUWdE@~Y(;ramsg-Q8lLVPS9M;u2{wSsc&ja+Uf=b-3g_ykHph)y4|8@C8h~olVay zKgz7k>TW*0)cz1Yy|39}F=GZB&l!%V;U zX__*qeBlaB9{YW_KM62FJEbtcXRFU12Y~BcQ%lJg$IF#*96?jPHY*}xTyi)qc7Jpq z>r7>?8g6CIy!N~J#-d~ppL5#aYu$7(2ihtV0T1DO4?vdVm~8(R<>wX!rFbX)e)nj? zS2?(dWDpA9TvA?tS~L!#Xbl^AM#2NLoSIM}UlJO~{{1R1DO~5^O};NjpgDlUHu-Ba z+gn^D2ajb76uRPsUAQfMEogKvk|67?T0}7a1<_jh)TD>Y!o;f_Z@14MQGl$@$MBcy zM^vc)o}n>b$b6F{O`Ooh{JI7int}I>y5>qJhWTIc%oN#$JJf^?jGNq_QvLItaE^_L zLoD<#Z)rieChOBX6B`q3OEMfyTvWpiAiF=UdC`M%O{r}EJq4kzzj349u@ zi^p;%ivB_*l^ijQ=a2$26~Yz4c67v!5p^(SHo*Hp44|ralKnafZ>ZB!k^K0-E%AnN zKJKkus5#Bj_Fg-jlIWsOq@zRa%7Uy%2U2!{Aj5TyiMF<{mu96a+Oz(FP?13AwDgyd z-+d>>5b_f3^h5IyTrMG)R+fm2++trf?)0cI%yaLUe!kfhU8OwK*>3Ngesu20BdHX& zGV>&*OuQ=#H6gg^m*U5R*Te2(z0ww+PArW!9k{!LpV38E7ZZ^TT=9kF zxS=iF^zmKB3QF1beI%=>h7>t;nVI|SeX^b!OA{R)eB38G#d8^@G)F>YT8-s z-$&3u<+mLCHZ31}fINL=rUzH684O!p1q?fF1sX-TBs0h00gL(y#{*L>&1Y@G6Z)#@ z&QG(hzuI@g6#RB7?M!~S9Szeab3)dJ+c%dReS^c?Vr%Tn2G%^#0_uNdW9>2)0K&ue z>r(ks4q{mu;jLbvTTy25KMTJ_3}yLD2Nc10$P8xLr@u(^=VQTXpo7@a#?&%!W{C_R zTWud_`Og~VSoH}$yOv!#a?h>!-g5p=<-RjF=ld|df5{`lD4>}T3+=)hLL;`4eQM1N zNLB3mw9ELwYGMR^Fu&nIOV_PcyA{;syP0@iTNlh+XTJDn{F37XsgeFZztSg>K)qC& z!y*9JJPL?nqM1F#nA|O{f>CB!aPW3(MI8&;5OE~S8JE3|rDiZS?Gq%a;kzU7uR2<% zd5R)3|J(7#7IO-S!BWFlLA8XI%)?uk$)Lo~wgtbYBt|0%Uhwk|0jjYz5dDCbuLh*) z_3Qg-lQI->^WC57r3dpJG2XC_C~s&>Vi-kJ&PuBrr{FsU&o=Cdb-EyB7Y2h_D@Sop z2T~q(Y0|m4rk$@-RHVe{=e|XP;l=7z5=(?;0_f(&57;){Xln%6-1b#(CGc*{CO>n8 zVDFl|vSv0N<~7APrL~K;Du{ebqOc&kU}Ckn8v=m`tVKTpg;73QAgp);9^G`equt|= zzwEf^Z@W2DA1_tSkN6L1A-_8EF&&uy@%a8(=&8Z^FY^2AP-Y+4s^w4VFkB+C^1f&d z6St?DO_1Gn$Z}(gP_MNzbjuQW0YVo5jA=@2tIuAj`dr?z(ust5p^tLiAIM}}w^E46 znm>*MD+sn(N5|=1Q06q7aOQMuNv`_ZQPlbxUT-7!kN zpP*N2^K9O;bUqLpJm5Bhn#uV%ln)tCvs&FwdT-sGfi;pAXI|()@uhpCyW^J5A-|hvU9^$x0s%I)f;+l1mA1+m3e`2->q4;!CL8;Sv|6xZ3uiQ z;w>`zyQZmtPX?c~r)UYHk!GUwCDe(P=KpKg|ECBrVL(WEz&@NA+_wD7B@z?Oa{wD- z5JZm1PFp`WwQ)gS!NEvbW0F**=mRyEkR5xbegTW#XqwX_%YRZCkAM zNv@2kg70Uzy!YoPVu2S50z%j1|ALH9#763$2|CUR?wM<_6(8$+cPOV0uVt2^8|p?K z`?je)Vb#YqRQwUXcg1V*DSTKZ5B+g~Ko{>Eub-gzLp)j_g~vM=bUmfe0Qw2Vkib@H z3=b1#4{{caBWJ!EGP1g}i^*y$0)R5jKfQ)9`4O3vhYYZPFe@f{MQXO6T-0=ztlM-w z5VPzLS~>98drLQhAM^Fk&Hdh5kze80?LlPOjV?v<8607%o;G%)jVFET3a-a)+}64iuuRTu;7%#HEdkC zJ+-&h>|G9BJL_aNUS^z*AgtY!kr(jPl@hc{y&|>@GX2v8KEyV-vLq=*c!6Pa zN>(o?7F$+1fLvEklf19*+d)U$?pfUXT~i{RTeSE47i8GVl2{*en0zCgeI8aVuZl<- z9Qskc-|rl)M*`2#ez_qF@p7K~b~Wgp*|Y20&o|?|>*?#W(TdBdl9AKp6ORgXDk)&s zSKmb%iOV_xZE^MC9DQCuBdamp&c{cj@@hZB^HToyYN@f~tBKczzgOE?fv*pwA`8CO zVYyRY(SPxW)70mfUia!Uqp{l3T_7zzV&W&1^-vdhy$1L}idb zh~mn(k?rsjb-hWVB0J{eKD7E{N4n53%o=UD%d34-I$1VH?1^|@9$0g47#7mt{TZ*N zB{p|bPvO+O%d14Wc!n2m+}u?W>eg>DfKu@B7BHrhNFDwysfXBoLy8h@_oMf^MmO-;@%bpqOgd4 zsx@A=#Ll8WuN@RJd~V9w=Zg)E@Dt)!=D)9`>c^cVRa?#ry_=91DZq2!yZBS|&zuJB zNx$7P0yzBhinEn&#Pj<<-f>5onj-8)qHAfd%KLmiZ)$YZIWk(Fz4Qb>LT$VJ;wRWz zx60;=h?<2&0n3>IzN?3h2Mm9=e$%KEp5ccMZ+ZaHHt+SaerJ9;)}#*r6`GgjI}h-q z>PKZt$v@sW`fN5F`rJg0+br_&+uyCi`zRszV3O;}%FGd<;dYumlurwo%bM(Oge~&f zb44gz9?z9+J`%dtZj8bowD&(1yT4y7BFrsm@o(Mz>~}H`Tzl)T(C$zc3r|hoP|*;98O3)ml)PuI;kUZOi%o+=Cgr6#~ETX-soM_Z~=qd(X~nha-Y^ z7`nK~gKNu^uX@|m9vO(z4H>ar&00!1KB{jD?FNvx4aLet>~Ata(bzoZo#4-OR5f0U zitqGz({Vg}MSNnMt@qVb%I^^>GisTw{^(xvjLUZGCs0Eo?kUi+qp>)>I2Oc3SQE#A zK7Ce)p|@8}S~``8yiib3!Q2MhiYxp_vHVLZ&=PFx^XEdDsGzKY!mt2krGR*%AZwoiffmH<|YSr&cv}mUm<%)~KJ_0=+z+?7P1A+ThZas`@_R^I!@%7tSYH0f{3lO-t zO&cep3+>M6v;Fz1$OEsc&V5C?xirfAW+2M!mk`{hJJ(#vzmc zm@AmHfo>h#u^r-U)e1b|*M?0&If4!L*`;27?zUt*ci^U+#;o=)A1!vMX0gf}UyoaY zPrhi^%Vuu+8n)*6FEqIZmhd+TG+-aM_&3E^i@348eJHZ@6Z#g{?({V0_BatcDd%DQ zEuR-6FZuxV{P8^W_|b0X^Ve;+VAyMbvELvTs4O{d@4)`vK(i(t7Y}Pgt5U~AW-=BP^6FT2v zgl~b!z#gX}E5nx}4uo#W6efTq?#6#g)hbhprJ9KdO_aZuo&S+oRx1?xkt7IA#G79ucO;wu7n) zFM;^2F(%AQRf#8do;V(xAUjxS&$zq2;1uSTF4uS+VY^1sHP}0-~SQ!DCBb>})8XLd=S$xd*WegvsfYjz32eWH_qf6fj zDAdy<0`;Y_v|H6_cep=AAQ$7JY*8&~XN|9lJi%we|F{|x&IKyUdj;nq~B23e85&NEx~8uw~`1CbL%XbrX;GJR7VO@Y6`76}>yv zhuy{9623^|aA33Mn%-9-32Z}2Ju z5Tt)3GhJQyc|6z&x30_jL6WR3W+rMwv6O8fH3Du-AO6Y?r~9!2(ElU$iBs1hOe3?4 zIfk8ncX2QC5HlI$O=FSEz!)r#9L~G-PRVXRVe_)dMi(ni_bP5z3GT0J$9>D`;gi{T zjv%_7U#Lm}(^Gy&sALoSg|@q~0w_z**Kw!WxXUhZFfx7EVSM1RszIdB*CIfC)~tw1 z>Q6$LmS<`r>us%NJ&TLE0k%^1xoYXmPc;TXj|bmn?>T)z_!^zt;o|W85njFABZ!{R zZ1XTHBlr^2C#TEnTpmoHMVn8Wk1w;xCl0np3)a=6$#=g|VOU?FJi1=PX%bF~*k5+; z>8b{r%FUTqG`+o&GnfhA?M0v2h-180wlS;TWcKiWZ*TDWG9$+zATk?VvHryV z3VyhJ-#I}~GU4-h|C>F+yt5hfaNUKX!Q-we+>~+YzloeZ&)M;F=`L}UVp|_lk^!ihfKty;$RAnE3~egRlUjRZ)`MLgC9BsHx$$J6#1s(IcPYmaEb|^- zZ@uxr20JMZ6X@|5R!ZbMRQgnF*6t|R5%ks)640e8aMO|E)~ zs8?=*@EMbpC{AaML0L{c1v+3Slz)ng|56g@~_?(74otn`J6a00CVUw>(@Ma!Gn*4 z)lmsvsupV$_dUZGZT|ROFU`ouV`ri6}%=UYA>t}@@QD2G)O=gA2=4Ksm zR^+7Qaim^H>*tU_ND;pCx~fD?g^R=I3g$0ViM5+-xl}w|QUR4EIEp&jQH!$~By!2c zb=M*gsRTO51EWE(Ri5MP;(}^}12^PTn6V~MAwihkTY_zb6rDnpGg(w~+PTxe7VjR3*MS# z4A5#%?MNd@+%4NM(aBaNJqzUqj}J9WA%z5tR*PAx{H^BN3Bvb#^)DuCACk6tI{YXa z1=*XB2$&81Z$dYZ55^uo`kdki!SCIgt&6sXKme)z<>6h=q*vu1$=Xbi48$=61CnEi73 zyM`qDAeG*cB7Q5!h~K(6iK0#m1SN<6-wO_Z8PorKF|&YnKKLP`xVK!xb)wy~H}q)= z>%T#q{F&VXn5yz_;Bl(-ub6?SON~AOIKBXd zuf~IaaNMGyl#w(eGaM65UZUlWGRe6DsM*Kwy+1pN#p->{qX$a>aa><+tv%He3iaV3 zTfjLnCSSrxSI27_T31x~<_WJJY+7%zUhud(Uv|B<#Xejblx&W6K3}!~r9SeH0exc! zj6`U&y{EoDAesvyD=jN6Y7qU2>2qsG7Ao22nF5sGZYg(Oq4^p4quUL3tIeNH`{I~T z%00Id?e7Yfe=}DSoirMqJV?x%Qmj$x{PWNC>xdv)Pi`b{s-P^dR!yOH1xg1WiZKVa8{PBCh;P=1Xo}eBc&j~- zauDdY;ej^-ebaYSD&jMRlu5YH`-%5zCG($hn^M^xISDURkS!u}D_6B6Y;fhI9fyYY69dFg7g zeCcKGkL~@Y2_}1C)BfnWN=ZzB9c!Q7C}59S^<9#_g0;FIM_HbYHI0)f9e%{PQlWK> z?bLeU^*?KuNpCS6h}cBLEJd5eO4(x8q^?$Ojxm1lwcvNC# zalaeN46tg9p1X^)#Er7($%dV|IU?=w-;c^{cA(1~eM=A9cI2NY&Cn9>?{;i!agard z1>)?Vs?@xjfFY77`adqF{})ilr+KagqBot->f$!)j1!&C0z$fv|G(|ug+dfN=i@Kf z1Gsx)o-D>tfKmhhU|&nR*g$6Qfw`hK%3>X-2uX(HP)1fQj4%8BLD-~>DHLqIGo1WLQrVLN^=%a#C4;OZg z;zBoniLJ57Iyfqz7zKH0mBA99_^^f2Is#X&zR}V;3c?22A-RN7wDmeP$8Leypj~~E zpjtm6MZdSCDOsq`!*f`l`w0`Xk!#sMYp8GPfcLXHE%0Jj~; zySHui=XeeQHVpFLKTz6{f>iw?+3kZ>1jG+as9AfGy1$ViuVHy;C2x-y!SU!qn|1~S z7EZ4p)@wV@u}HylzYlsO3BL)!5!M&rMD3@53}odk-0XQ_6qUz-Yr`RsL8rs-5Pq-S zu6Z=4Dbg(=AoH>!m+z|QT-T!h9x#M7izdD2^x2=tf_M9iw9$Uq^*`%^YB%x~@N^<2 z4OQ>iTAnAISYATf?7{Vk!2J)s+(?TFzN>baO}cBVp^*D_f(M9XO+BZzeiwNSN%?@- za*7Ewv)ffu!PzQG@V8-0TfkOm-$}Rr-&r(P8&~iMsd3q9bX_AV&|Tm6d=+BrR^u-k#7-VTpQ529Sv@n%<3qF-a|LjyuT3{0a z73aAtzayRVB&B!D8WJ5v(qCYS6pQ~R`wVZ5gklpL{r%7j(HY$n&sit#_SAQSH3scJF@y z6?{Jd?||I`M+h`EnAtUkgk@xJ)toOG@$U7KnaSkr=R}4jC#i^}AxE1*w=%VlN*^m~ zOy9;nr%)GGQ#!axFn?X#M4FQHrs1`%fUaLZ6K_-Y#5LU)diJv;m6R%q`&Ky6MjI78Ro4`2(kSXwu4mSx|n z%yGG@$Co^*+_TWNl#Y%kqM>@%$WAnV*E#su^+(B6AtoQ4*=WfjWezuoSY@^dh!J97 zVQLqUwE;%Y>6-V)fpVE^e^fsgi<7qdzEIDF>;MXkeP+Q~v-#+Hm{678GF8Mex&WWP z+5Y&&AcQb=cfuwnz@8&A;H9Tn(TcH~S2C~!ui6DHo2-;&bkQex7{cNv*lYPT2jvN+ zk{btEvwTdpsq1(F59<+pu2ZhE(eGE@^E6(?&A(T~slz7X?k>;=JH~Pz3SKrf=_nb! zbFUP9<^QMm66STieID6)vum&9AlV2hwgj)wj0#PRHM-Zs!zhFX6a+S{D$|dK%tX|7 zkKj9-nucu(l?rvIEB<^N@lsOm=CJ5mMT%?r91mj@nr0!xs~CBooo4qds5|Sy4M!Y{ z+x1}_^U;|zOu@mdRh8_^FotxtACwx_Y~LpPm|Xwha}ihCz2+2=JyOMQCCq)%1jsNw`!J4lZz}{lk+s+tjnHtByDWRY?q1JqN0!E zlVZ|3U~#h8!M3yjIe6W?!yOmt8{SPEYp{$U&VN`cJiQZ2cG;{a>lpxfCaY}mW&P+^YaLfBRn$l}GmlUw za8*~qkrS8GlGD=1moC@<{K%H}>7^aL*U}ivWXhjuFrd)^?k9DkDO= z$w0-o>u(i}#xrdEBIkD?F{A|Q>c4djiTGPivL%m!`8Ys7pqXxe+SQD(*V7`lCUJGLxU3Y5&+v4q9<}%TWLGxobDWWK zRe!2U_wL8iX`_g@T^R;%SDeq>TidC|Yo5y3ho)@OO(9^WLHLlL$HjuB>t6#qB3k}) zhFAn2;HN(Kr#YQ7CR|5h6WKzyaTmt#5ygSScXR~r%}nR(pPYWqS)LX%^dtO0NnIVj z#Ofd65A0foFQ#Nu=}_;C?++nkeaFlz+^P5ZRax% z>Q7y%fyCt{M2)u`(R&_DQud%EvDVQG%Ai?;uA+7Ar<-v{f0-j`WKNF{5si*-dh6Da zvP>q(MRS5VWA6T{reR!Wq9E#}=gly^=QiB4Yj~sEo(5++=F52Y&;2LpI#LyvZ^J^k z=qa*wm#W;l_>uP?^V7Gwq!jM5C~?;F_8vEzD!3QDJ^A5@U7q#^J#=YC7lZ2SVCGhY zUF+z<7}K4p(8sK%R}~+2d`Es2)ggbbA7C(A(=umU=OfvIJ{!;7``roW2Kk)Y#%2kQ zw7{T6PzK+_fYhsPJ&&=Y}9SI2`<_yKDtM_~MNn*U7_R$D!X z(dU-=b8|mPBa5Pgq%36k za}r&B3oNn)J8VA8^W+`56QWQ_n~a6CPfj@NXy;dn2F5o_$mR2|yM}0v4~Om_t=pd3 zE=7zV!+tZrBVtTw_mzbZQaQK-*$8v*RcXo2a`c~$XK1W7nJr4ZO0QNrmZII~hKbc8 zzD=^B2~!DR!;G@|IAmY4cJvmB9Lu*|jCg+Ga`X)&8LWzH$yl*)|CsfrG@VJ>UGu>Ky z$Hth{)t`yyCe>>_)zn^RsGpnGe!BlIk)C&chb(e=>I<^Lq^|zXL1hjkFpL8DFNu8z z?BGH?&aDr`JSf@A*SnysoL`@y1{O!hmxsdXH)ErtZAY_3nT7 zQV45#oNt<^RF^p}yepOJU~59;q46c%yYwZ^*N~U~cZ&B%VeTT;y}ejutG*_YkX5~` zwIL`=V0BDyr_cUbpZBV{x*Tnbz@lEe%hBFlW zbZL!T3t!tLL!TX~j(vgEQCz>lU7%VH_5Fk+N&z)>*g(*rfRE9b$0_T>fVqJ#RPmFf zdnHh$Vs9;UTMh1C;uybitF>e;?D{)nZ-8?ruvny> z;_oi2|2OIIMH~1WO9|gDfL0kAHoE-Jr&X2jR(xOmy}W-gbacVAnzn@TU5Pr-!#3-g zJlFS2oP|W9AP~B zh)Z#A&x7kxB}(pelA0KnxtX<@nI_a*ysMg-#@8EkitA)`@xu9#ujVV4BUn}_O)|Dh z{w3?lHmh&MDQjoXjaQsTHma@!ycIJ;=_4DeHOhl_G!QYZGe7iS)SZ4IeM4%Jl?zqn z)8Y%Lp`PZN{yaF0ES(X3C%3@g4LlEs`u@@L~HT-mOiWFKH(&FzSfa zCusQr=M6KPk!Y3;5dnFMDX=i06%=>)^Lcs9`EQf2=^f|wG8(wYPqATdk}`48QE}ge zEMU~du#rSy5idl1fku4ZN#4=c)7j`d#t+5|C&VOdK<0cM*NgnxmedzeM9LbY9J2yKC!l+CH${S z^lTx-88UIa0P;)zHaSk{%z2xLs6|V+T>lK@wL5FqqH*0hf;uuur{Am=_Fpi(+U=cr zmHMbgu$MIl!kKgP!oP(RlmkZ<8QLu{^>#78B+rWoaF1f?MuAT386}BvQEC~LaP^Zg z+8^DF?0<6|&Lv&jp_Ola5-1Z@XA)(%T9Dz+$L{*&))EF;zYg=^X$9DIjv@|N0-1-u^Un!_!3b^;dm7uhJ_h>-jFlDlvvS>Mac}^ zESH8xa7}OtbrONbT=2J}7V0LR{Vy>=uI^6);tuNM7dw_O9y)$IWjxq;+xTp5;S`5D z@iu(Rwc4mk3$!FohL~kzSTqT^mQ8GH23Fkck;uQX2QT(l){-gEX_&*TmGXb+W1{zkC zr|RSJ+eLQriE&l2KD^;tQum@ID2D*2{DVgv|4dnMsoHhG%)8*}2P-`da{+7?~_BLj$g?*b> zbK^e7m2WNc7h+k87o+6fzMgOlkNCH3jP5%E6Jyc7X@;K1Cul&tv6LtIZ1y~XwcC5m zrFcH19fN5|T`O5H2O|TlbrB3L`tEYGv*6v?6tL)ufb(|h@472QZT#=Fx7!0#keAy!!JR{#U@Rhsa zx|90ReA=UqOYj3_Tqa+0F=X9+3xjJVz3e%L$HZ{|nDCVl~v{x#Z^biUcO( z?uI_xj3oWed!sne1|{!U0Qoxics%_iz|-5y}v`AxjAaE ziS&;{S<7gA(b^os6XgYS(_f-l%e&&qfSLl${K*sLaS;3S)94>VnA*}n>_B^wJbqMI zeMy?0ZfznMS1SB1v ziHbYU*ZrLggR`1%+`>i4B~3rw)Xp(`A%xGO$Rce|Np-6~`7(X3J*B-nXT|4D@14#N zWf*{L&c?9S)r~FcB%)@TdKff|+i1-(X9LgaknBhV@SEqF1c3Zxb=noNIi~E6>-C-* zzu@1gU8JwT=WB4SQA0iE>pg2m{8!^Ehe5bwhh7UQtQED3;1yO0oXMnBsHNR_o})?O zS`6bRdWMwUPS#Af7_Jyp4A$unN4lu&aPgp7LweXN7&VpZ0y~4>l{5XSd>67G-XMc` z_KifFUDG0`z}Cn6nSTq;f7&VF`_T7OV1~hg)eqOT!5pu>;!a@l?B7L<8O?+f^5xo- zXPBQr-8ZktNj7C61ve${tKo`CiiQX9C0H~zULb!<>u}mNMxCIzB>mR~8@aF!Mb)#F6+e6)leS(G|GZWs=eFAx#rZ!i z4XmBLpt(DD)m^)Zpv`O`e+>_lqKpfd0g=vK#1uuF&c@p-dKI&A2#xU5-f(^Dhcrk| z!rSl`rQ+;Z<#Ut}IScO$1Du(dph{1_v@h$hRp@hO@Qz;+ z<4`m;rtdn_=6f!Xg_a{c316mYY3U*04$ETQ31R382UhW&4BF>+51UP z@J8=%FQzz6nf*Q6w|c0+_r9AkGu6qUyyNns!s~w;_13t5qKM}gVvOYfJgujDrIjZ@ zV11n95pnAoyAMM!JO%$jHIbX_^!1SUwU+OL)QQfjo5G$QWqt8@jE9j8{6M4g+8PcQ zx$pE`FVK81A9tMN2fDplqmlRK3H6RnLp12W3zWF9RIxJCh5D0L2}aZ=ZC#sn3~ZHV z)NhKxXx5HZ#%SzjX34-`y}l4EvQTogx_MD#seHNy4?>hMJ?~h-9YsnH-Dnlb0acuv zvdZ$B7N;aNO_J_|Ad`$QD;Cn&fr6t$r_t1-!?n?FHYjWCeAtiG-mV8B3;)?PpXsX& zG#ZF;ni{8lHV2-~kZxIcg#_k+#yleB)`!K+c2+;;bf6fIb6{S}N?%%Y4N*tNlCBcP zkanRT{A5mCJVPBUn)SR`X}Xwh<~(`7xJ2?KxM&)!3%88WT3{98bg2sfnlQhsuTf z+`|lZUVR5&VRFba3dHLj01?KtssBpbOL$3KKUX$u9n8=>g`^z&6x;CJBC#ZRTFCOu zkILLu=al}63?|gys;oqDRwYR%_a9*N0^kkPtYR)l4=Ou5IKKa0UI98Jt1`p)zL%{p zk2;;tEY6`@-U1RW7;jn_(Ko+`OlXaE9_=gwpvgVk+qn(s<0S?KA_MGy93sXHle+!y zLS^P|;C;vi5I3zEFm1Rp0`FkmzGFgwWnviw5I#Rf#{@311eJPIh}MzyR9Yx1B&B;? z3wGWt)WT0R4GX>gwDP81%I?SE>yVKP_-3XlRnO7zPh#f{J!z48$w}k6akl(Gso-naCOjN9X65gP3SK)lvctyIW+*g~?6+7k=dF{^2sQB0allQ<<5< z!#Ib^+3ocHkca<=v(KjcVZYsYRo-9g<0lCNQ z?fQ8@jYwC?^N}Y&t3BnAfW$pf8Ks=Da-?yCBXV1Kbh*B8E@DpnIvs|uesmLt%;<2TU+QtU%k5>rZykf1!_>%q1MG*n4~~ArjLBmudh7|Tc=(~ zMG?{TzO}5-Er796^$maz-ALS5Du%GVxFyL42O_e`ADPaFzU)1Kb3(c1q;D-1okoFX~Sneo1_# z`Kh@Am!F|dbg=MiJG|im3&Wosfjz9@?6KY=q^^tPfLbzS{C~2`U}_)yXm)Ym1sZSls6jj5oX5L0FODF}Ki#!p@`B8QgwBu(6$Toz{6P`0%IO-gGbU z@~H8?54I5m3F=1V-=o2fZsZcR69kUInzR5M-f?#aVnqjm302K(IDrOfH1sp zs*hWIpMZsKBN4omAlGki_E590U-&kFYA~V@OrM0*2-2a{8Yrd98ChqVFy~l-i>|IfD z!CMQZG4|GXg07Zn(1~9RIsn94s&JeOgpnHb11(0e7$bxPORjpEe4cHOXiPZvL7H#U*rE@rg%NjG^?7` zSpfOBclTXn0P3&dO#qX`<{AK_z|8#>8>wp#kA-_$9STIg|31iCBHsKg)z$b%^Pd=4 z&;P%a0w4x__Ed9zl$2z!K%oA2#YNdSs{ct1x~h|>Z4&KAl;;PS8zUJW%}=P51P>1K zo@r5P^^}m8>8+L9tL1AN=6T#(!)6OaUw?-Qi1sZuVp-qU~ z!aOcWAP(*$C50F7EF3)nI_%F=xsLnEeSnzsi4{4a7(bq$o?b132MC=Wcy?UXr)cda zeRIW+uDIKI*vbAz2S3zu06LH`>Mz=qxWwgvo=_T-^txCnA0b_-wUc*eA)#Fso{mf) zAE^X;dDFOh|M7mown~Z&_Uot~A)9z=L_`DL{oEwP;&;dj*I`^BTY_JQ3FJ$%(F}-E zf9)3yF;7Umm5UY%y)vZ5H-o zc=Hiklnq0yG9rS+?wb(58Qx+b8-B!~^M;R-ck$@K1}Rol6saMvQtO{zcJ&B~c*5?+ zeRwDQG7H%C;Bl>jmKlwQQk?X&h+!=E6TypWO08Tu0_*b|>E&f>`m?9c=Rgir?(H%D zt^6KxA2hGVWOtNA`dZ1oqc!B8Iq=>5|Dn{q6dnM68b1}}ARu<0_Z}?tRrY6sFjexM ztCt=8=vv(Q=lr~h~X_IM2xHa$x*16xatTdZRTpPM}T-V^2e(fg6T zVZT7=OH~g82?GfYRZpV=SQ!q3&9BXwRb3xfUou^hxN`qTr5qKY!;y9-J>MvgUGpCT z=IX}7sgh`<%HP_N4gJ?iK@W+B8|VNh=XtPxd--V_oiX%%*4pF(<>$2hMGWn=+ zVOG@{d6~?)lMuS<(#{RHZ<;l)SKOQ@0v&lZqIJn^%3_x6urfVj8lWp8qxs&P!d9jo zCLyOpxt{kx_6aG|IDiKm))+(lW8Ha>F;xSp^t~m zYHiu9$pIdA_f2bFYGOq|XtRfCN25J3ulL1)f9wCn;jMZ?$b|29mBA<8gwXp-pkI3H z3qovx-ugu{yNiuMygT1}wZyvq($GR=vR0Aam1vIB!P=yjiXxP#e83yF);>C4kkU;} zn8Di|H^AIzvDQuHEXZrX`?+Mm(rQvoagVlbn~h&tTB{hdROrBpw(OA&Gu|vs!>cMC zV~K^rS4QfUm~`G&8^7>9Vw+G6o@uO7`(G2=+>NXn4kLTQg6OYiZ(n}zlrFIz%lvfS zq5tq^{^?gK8W6QqHXvepW={<}@v|p*_KYCc3#btY|B=u(h6XEk!^XQcz+O^w`j^0$~_qbnp6uU$rjb3aF2pI_r0&zVGnq)R{#6lus1cV zY7>9S+jxoZiE$6s2T|6I(Q+$^c94!2&*FQFeMy$i&QBHGzQUB zFGsA9r#^v?A;=f-!9VK2-{$P!FF1Ko0OuN^?DNI1)4x>8|00j#?oW=#UUAVk9>hEH zO>=kZbF$?LUm(p?qer~#kbCbtX1#2JFTzEVrKqGD8=?XQ;qMR_q@-S^8!H{{#nmB^ zheC++CuLEOxaeJ}T)S__LDP6CF&+i9EF=w2xRFS-oICvWO`7GKcvSjSNIm7-J#iO~ zTFRjK-lJM27x!{FL%x?;TU!xQ;`%DyR)sQ0##f{jOIL^64Zj-tTTL+#B=DP0jXHHv zgi_Hjh|*Al5?V^Wml%EE{(bnZBBVY{;K@=)FHuMv&jR_{#ro-|BBZ7aV=BB_Y>=~f zHhv`OvTV@vN`{{dlSkK|{A>@GB-Q|Rlcz~F^t*j4_r&j0AEJ{6v)~t9=@1_jD^4Bu zgp=qkW^wh8VWR5lyrf2GZ3`g#OlfmnzM76ZREjnF`whb_I3ugG=QW3BN@YS!Hj3zC zn{9Jg&J*Eig;Hc;WNshWXVD`%Bw?~}PGV!aN$ow3+INFvlT5Wy&SOgB94lFcZz3(0 z1fGP$PB6WS#E$l78$Bt$JQJskQoL`Ng0cy5N~mk55;Gn%>>DR>85WcRajm;^dZo4`UDmpX+21r@-!; z1O{p+v*iiycEc62XGdaOtA2WkdWe`IRoVo0kH^RPY;}5^4AY+n#v*?D|D5GS7K64S zd}YCEM8`xyaXln+Kd*ehrMyaJh)oDYO+547!j#$|1$73WSOfe?{;N@G9YYaKP&!huXvKP zDPu{=z}_o)OcLRX?r0U*xis?8c>8+B<1QJIxSn+jl4lOU3auZMb-KYCrJncw;pgbI zU16X>iwvGN!pj)P6$Z49sX&@Mr1l~gW;}8f<2nQT0j;q2Wcc-v>E3(&NF^Qzw@+8m} zr89@a2RVDHqc7M{I;!frfa+7Ok>OU_{tOx1MnOz})NZ~YG{4M`^SC=51JF-aplrHx z!FZqQbzW$9o1*}d!puJ2Q=VM6GW$6wE?Jt#+{w51uAJ8jzHk-ct9aP9KU`I0z`YH! z9z>QpB&_;hI>wQv=38vCujIJpc#?CA;aKGe4-`jcd`0H5sEWBA= z@kpTT)pvWX;d-PdaAf`G9KRcPu4%9V0*EZSz8}9&f0J4aJ}? zbv|U^EVC`S$(rv>B|J^va$h4g3*uyK>NDnHLu<7o;TOj^7lKn1dwf1|lG({94`w}3I;k}w>K$vKA zgC$`~_k2>1)5y)N);(HyZD4G?5ubJa^FJM-x{$v}F7KwrV)7fmH_FnNuF^&Lr6`8x`L1k>kj7}#@N=*1&PX~u6?L`s4 z#Nt#2=D3wM?`QLQ7s;XK0ikp6Y}2|1$EYdcXy`z$gO+^y-}-NlqVg~gsCf@TQFzRR z0TvzQ4e>jv^(9J-uftwsjCSv5{)%p|6GUb#{CZlNaiod#1(Ko&rLMt#hcniC(B(93 zx0gmbp0;#1BAhF8RZ|_3c799SoN(ReZEpmQLlJ5aFnV)l5Vh3>a&vui2ZFBXF8>H zr$qAd2fC#+cNE4i8^zgz-bahtbX_iO-5hJ&9~FnH#>PRQ_P1SLUKW#2{D%nZqS4^8 zj;kSYgb8G72^$SB_(|oQ(n|wY(S#KKzwOrNH=I?3RP%3Dh)}$x5*ET9nVx+G!ooS@+B;7r6Y}l0# zyC9-|ig`j%3bbVTkb_tVyG8h+fuo=V{Nup~e1Gu{G?bGsM=;wZEjowLrdyPD>o?A$ zOgYik`7{O(BVkBCKMqz~S;1nh6h=E3OK7)@$Gz+iEIsAuW69;Puo`O;ZU> za5xs_&>1PeL?I)qL=M{zsq2{qrH+$6UK%^)TO7}9yN|pOX*1)wUEHN819s8rd#n&VY)WKj4|xSdyZMl38LfEuAsyGHQO$5%t;arxl7zIUuU`@j{+)#YyZ!;C z%*gI_EJew1;NO1q8{5W#g~#5IMRtlQW!S+$sm6N&z}jJVu$I=b@aUNe?vC+?D-apo z!_4!{|EwxA8P9Y|4pmxCRcfvQl}#flDamh5#pLo!vo(5NS%GUqesvMmJp2YVe8maCTc*`hWpSlTR5+7 zl124r6maDaJb0pJCuDBH_&Fucl9D|2bN!scEybHz9DfW0rX{nv=@M#WE)i<0x*ke; zQc|#ikZm<*NRI1yf%Aaxm77|BDw^l|qr%;dkSy!dDpngCsDRiz z2DDhoTZc@)bLy{_j}E5G^rUB-X{vBMI~4E2ioQt-cFY43<;ch070(6#juMl}M%2a= zEFB)RpacM*v>^`+Rgs7Jbpt?2U53R`d1M^dCCS%X^r2po5xV2tRJa{?r zJuTNJkE32n?r;PCHh2H}7ky69^Gm>CW!PZ_F|vhbpuQO1dztiIq(ei8c7vM3gF-vm zjBf?McBw)coeFo^s0ORhQ0mSznx4=xGE#%v;RPkb#{rI9){{j%1RZcMA-n+VpImS1 z_CMJLZAmCZy&B|0AM$$lJ6zx7Y)} z-p-mqA);U3O15*EwuLXh?`lz``L!Dioo)HiKzUPO(X>-8r3)!G+{}sOIc^u{Ic%RB zIiW^0zQ`N1bnp(X%lF!_-Uw$Tfv|+uuF8|l(R!kwX+-D&{@C;fI?;{2?>!8(E1#Tw z%cc4HH7Fu1MzXVkf_~E=k#6-UK31zU(DXs}4E=!F*oP-+zJ8VT_Hb5OvN$CGPqOu! zLe9T@^4r?V_Dfz=aSQ^+;$o_m{IDu+Za&Ry`9?@NN#fkh;Xu`^m=HzkreKe{GhXH; zt>?bLV62O7@p+FU8@Cz-DX4ETqD^FS2$=3w_G`RJyRR~P&uRZH7X81Sy$bQd!ourF zzat)9J-xbZ7pwF9f&v&E=t6(tdEf7^JoGj@mxXIQf1TySGtqA_ogn;)gLp9YMPYcj z>NwJOZrezr3Bk4G?PUYpB`5S~KyT5I@d$(XMc7J=gxU6S0ZYfd_VP z`(`hx3U_xqLEG*PwUqD3*1RTzTk0m`PL@%UIUC-gn#rwI!}DA23#SLP#*+_1zdK`p z(Q~CwAr6G3m@$%o-zbmk{b=V{aHd|w=2&KYA(;>Pj1MP4qp(@?8lJztmLZfoa5+#v z{_RXvLDO`^T3kqhI;5 zM>`pfUT)yYVDh4y0_J7^7>$m$Y7#Ryd>r< zBe=kTT2ItGQ{BTK;#EOYj|x(?6Q^@OF|DH!N^K_xA|_ycwxuKevtoLQGU2+t45c_PnJ@x{Yea+nEh*nkQ6tBmUQ5;^ z6gKBvXR@BPcXKW#Ozv=TTefn*IQT8_Df@JL+|5nbo!Z zl01)GFWLB8MpYW9KAWgEoW>ilC-MAm~$h>zddhj+!b-JSk-9r#Eu+RZV+Jwu|{6eOOL{-!z!=3M}ZA3N$MF= zLs?gk{o>k8TUB^6na2f<&y?Jvr<(sNFVd7OW(o*aM*sR{z@V={?s_bd*UP8>Qij;| z2er1~+tS!Pc}dXc0^B#YlhTHNw`2&@gX@-1~Mo;|m-X{sJ+< zyow*_SZ}+40Y;c(tLba4sin*<~m>l6h1O}|yWGhRLHl&nUlzHmL8{}K|Ty4%s zo;5vrqx`#q{PDs=H1m1icscpCZ@-e+p(E&YOuExG8sxNgx8DttUYE!j9gI8yZr=2E z>T-V9cVxRb{CyN~(uvCbQ~N;X?ibwA(U?|x@1nJwpyhaF{ZZ7$f&1+!s<>E@yy5z? zP=_5%MI2|qzZYZuM6%!5++%8>#m)vfK=;*AFO}+wuhjUR%6*`aMN4sM=}Dgk z%tZ$~chc?V>R%`&P@VqIW4_S4iSC|<3=9n1^N^O$Z!V_+9ki}qL+)Q_sa)%vt2W{i z$ILfHK=-?`SJ>x=T%gI1sxRd&0%3Qtw@+Kv<>=Y!PHJv1HI5RjGrtS53!GIvZ`&DC zlyD4g2+Jd4-v9Bku-68VB98;#WyWK8;Y@>X_uWF0o-~W1OGzv|z4aY4J>ObWr@FcL z)j@*Z86M(~%^bppe!%_H>Y2ncD_iJd@1I>F|5PsLa5B4`HuCbVg#7nRIy9)T@q8cP!wVHN&I2u(uTfBnDSHqjCi(-yDKS%r80kGe_qlXq4DQFp&f7Aut^s%(PU2yi5DG1KG@M+j+p! zBWwC~1ZY!zsB@&BzoXwBHk!!YXk>cb9pG|RTJ75Ti`FhkpgUN}d!VcR7E4{WRI002 znAp`UDbXw`)||3oj*&F{tMF+kba!D-0k}LdLZCM7eabJ;HU@g67ivk#IMP>dbgZ5> zz5UsvAy}d(Xqj=zYG?%1N6NuEpCOjR=H$?UR`^gB%q6-JlOrG@x_&7(vBMd(yiZe9 zETgRUyP+fv4fPaVs&PmdKOoIsz5`H1)s2O*vncc;eF{_-w?AvB#kn=;CK@#uWuq>@ z*ZT+5HTF{qQ#KEH>VFRNHuA$UTWciVg+V7{+AcXATTnEmK4-wT!g7VE4u|1P#n!YZ zR(g?&EjM!))dvZU4Jm5bXe!ICW97GB2!aF;9frH@0FAT}C-&jn7Y_?qgb=6Ei$~H>F2h z6C2>Og%tY@mNT9m)W#OnkPi%z4ehwz806ROS`|CyB zFkwu~e=#7b2)5U&V42e|GFs5DFSKjAk{mc0q({DUJNt1^zu;C_gJ>{O+$`9U*t|Z- zFQ|Mg31`O%_rW9peoJO%H;(I{^{~tR)8?7S^ZUl2UgUBaZnH+tMj$i&*YI zPXB+(Wp7sj9N{|fyr!(8!lmG4%OnEXg3N>-{H5=@f2N^!Xn;@m$`6v6OdXj_^GV~t z2@0I!TZO|t(adLnlhB4b%DSbT2b+42FAnK_DQhfi?O*OFdd^)@QQO=9U9N~mtaGOw zy^zK#|8Fa6A4BJ?XcU}G0QSXc6cW@TJd%MF!CHndLP1#m*v=BkxDO*HI2*VdqAmuw zA;|Tl%BzTH$>|w6uQ`b+BFP3USIpxW@X99%Wb4CR8>LBp?9-s#sE4UHsFg0{&e{I8 zuhH|o^&;4Zk9^0#7D3Isa!K4ttchC8d|NcjAdkUClh!0cg`WAYV7HYzNTSVy3^Pf| zBDEt}ZMDY6t*m~H4D(gmQB*?D!5)3AgZncbdy7p$uTS|2`~-vCl855m;NK#4Ap=BmeF&P9+kf1Fi`4(Z z0$fXf&h`9xhV5VM4)Aq}@6~w*AIHC8Qf>=63Z1?U2mdr033qBP$)G;(Wbl0G(iNQlU#{Sg(sm(oBIjGS3uD030ZP#&F?%=ry`OYF||*<1ZXKFWL_NX_)^fE0sxOtPNI8PK_Dl?`l_bEycsK zAgf9fGEKV!h}Dd^7%NYwR0?T)jq+?OiP0ToizsPEZk%4@hcPolifgdw z#BK-{eh=(&`_c;4qGE2CTwt07-#j#BlQQ{n~nR(>m^R*52>q4cA2F$p4Hd2cL*29WO$r>SGe@ApfVWW#if}*i)bU7z+ z9O)REF+1|llELl})MLe6tTP9Q?dr|7gsZ60?n4>gCcKJS@n* z=3fce*xgfRL!e@MZT140>2UUK1;t3>+C2w$TPY9^i-JR4in}`p2bY?xD1~sgs`O7&)#^Jqwm)LY6nDhyN~M=( zbq@|SZmxp(amYMkxYV{i8m7UW7{GUXlOtPhmb!__8?Yzv~KgR8sctu_K z8kcjI14^zIR-qbgzM$1?CaDrUEa5oXvtqe@U`JPE+hUH37k6}#`zEW7P5Tvb zvpy(%C@MtS%Ut!zr{1oWk91LrRB9(bn~!AUSzJ4pCy`@Nhh$2~OY4n|T`Ps=+y+El z)e#wxInBgGJ{w5`!an6)6iBvBXOrEt*EiB}s7wa5t3o4?K z8r)f7ie9&@A7X2APZLmUyJ|DL#(c1phkIw7)nJB(@-{83N(9H0Ys!Oq28bAboyW|@y++F&)>}z7P(`OsYC-4 zge8B58a#J-zcbUi-sHE2Ws0FEgeZ;t&(nwi<4~u-NVDf<@?e zv=oHS&As}AWD#qwUQ)E`D$`((di%+u+s$N9lL^!&V<1mu&*UJcykd-hr;cvv zacus54oP^ghzdv99*TY4#zanbRp&>dXBt+}^WwFEv++#Dt zBWAHp?*9C7Ap;CKKdeL23jgd1FcdrmI8;gIu4mBptR*KCh$(j zrl_c_x^b|-9sOAtAz^OU%h|$0mIZE`8kNjkl$mE$K=dDb>2zv!x?6ljZ2yMko~Wv1 zFw0Z2@Q9ZHj+)rE$#vg1w?aBtA@|H&+!K|X)a%}5zbVw@O2B$BGwGn34W2X)G9~J@ ze=Y-hlRwoL_Fzf#`wQSXKvB_E$+Y|^PWxV{P1GmTG1&WR87kc2e|mP~+E0aspz%r_ zwLUZi97<9JV&H2)JwZrNsD+L4!Th&s5xVWBi14VOp7^>b0hK<(Zd>bwprIfdTe=kh z{S0JSPF~u1?&kk%UUj-`5kInHX7ZjK`>trjG&b`uZaf{xvJjk{m3b-_+KTx#kR;)o zEbFh=_=S5V2rD~la^kp36~?8C8&x!!V4iU&=Y*oFDBh@>fR#%$)=8?sjmXB+Uf=6@ zcwJ_!4>Ikd*TYb7G5TJfs7CEWGdGY9H@MjJ4TN((k02TXuvMX10dUGdn|M&99ZD9z z9W?l!uxx#B;beTvY!QA^-~~H6(TMq;dNLOuCN6RPCNk|@8vsTT+a%K0`_PNx(nfH1 zzx82qwCrIk(kn7V?<$z2o{rn7ehbP}EgFSE)fo2}u^zIlfC zEm)rW4Hiyh?WJ)AL$E}b0_*i?C1&3&m}3Hu4;qSJEnEN?x9WY+QCOCG;Y(Mygmp6% za%aQFIZi!0Kt;Y)ZNiO2%{5I%QBVyX zz2{DXm>K8|7ulz5klmhU&)#!vdq>_a=v-i{2EVS)_&R>*pU@!p2f!ZXu@D=!$MHd4 zHZE&z+(2=`0@moA^J6*6`ILt~o9qi{^%_h*ZXDF~s03Ph@&Rt~W=mIdLvwp!X}ZpT z^|O`lJ(*^33Iwb7t#kVUZa3Bvc1wx?JJqlYwHKi%mQK-Xq+sKtZs~|mG@FaoI!dk@ zWFLItEf@VtC7I7pPR*^O5;C%Gx4z3UhxlV$XCsSsB36d(GHi z_eY5QBFS$%G;a2KdX8IsQ?|9`uBsuWM4q{723ZUwNG9DMfo@q^t^aR|P&L~C-~G~w z^kW296t9NZCa^cnzNV>GF6WeYgK z5XY5MhN_8gIt?#3v8$2P?+fi)#c#|~MJGI&OiThw(jP;E?1>MfHbUFg`k+ly(3fZ= z4>cNW-YPalm#~K})Y<^js=xB)lWdM`opGLap=L&^xw(5{U!7>~=4J}8<~P4iG?1ZH zKN3Gs#tB7<`6Ko0@NiiykU5JX0)o5Fx2_)zt5L~Y$X$5s7i-53Qq0cMUQ<H&a}K_t*x@$Szc=aVlmKO!7EJfM<* z8_>;PT3~xgqzr6X`_|heO&oAOE`CT*M6(3oqN8rD!pUE6ZO8ise>`O>dk{cNGtflO zt9wN@;An7&G_`~f-YyP;f&_ygO@fK~<=v{5p%=#z4bK`lLUQ7;>WPR&4ZfDKteW99 z>-HqEIkUB zLaWX&lI&y8^m5cOOS7&H8cJ_e$))*no)hkTHl8>K!tmRFo^&{JyY`9qojdGu4+Hz6 z2hn2nQ>b)aYdsI{_VDh2=5h3sxRV}bcG|k34}x@ZtQ3i*w7RP^IovwKU#sUg-a_pf zPwH(Byv@C$5~4Tq9GcD7gtB~Jh{oU7pw(|N|8b|zU^RUe*qXc4MWJ!ANqSYubyXq` z6seF5Ang};3|sH|&PakHBb9$PIJAen^zkBxq70@t7*%K43GlmhTR&KT$O2X|S>Y+Q zXr!`GpBU$L^pBF*4GjFI!mrODxG|0uQ0lG3OQ#P0g4GrWPhPJIBo0Zj;n;0;HOB8yl|6J@J3{$UE8r?T<>=6$;fgPrrB}Vb~g!o@UHozjT zR1olD{HCZ)i$>lAQ#gc%2=jpqh@^|xjE0mVGT7|ZJq47&n|cep|D%#lg4$TpJ$}av z6)wD;thX!r_|CKZh)E@bRo^Bus_mOJ8;C~dv9lT26Qd)5LCDhnLT2SWF~jy^9}mNC z#;s{Dtftz&lJ`}oDcwx?ba$svE)iKW#}N2!x_O02pS(@rba#+FC!ebPuruz1Bzt#@ zB36^sP8}<-S+MiPk%!h?FP`vz*d2r`SgL~-_N4*1_X+#1yU7f{axZCdL7Y420xwQ= zS52mGfQIjZ!$GqzecOtbZkAcm%tuS!vi+8?^Nq50yfRUxgDWcWJzU=!t};#)37|rzqaTQ=@g; z5=Ic6f4_|&E;8vq^r-L;(XKIo0^q#V8ld&un*k@#V}Gs&F+=+=>Op?kBTe=OD?gX9 zq#2uD=SVYwffGXL`*_YXuGOuayJxkUY)7m+oSr!DahSANTPFqpQ|xQDf6x6FPq$N1 zDJm}dqi>KsX8U*7T`81t$w3lxepY6y28lYGYV>*6Uk-dq3k{&K)S;Lm=pk=D{nBOO zOh`^og8%@kZ$|GPsSg84U9hY3R3O1S;};kw)`$>IconxnD3k#&OwTds+pKcautjOu z0N)3q*IY?@2KqnB8}B)RUS@pmwrSR;sMLt?Vxbuk=79zY<}g^>*ViGcZCzBUG|ay0 z@WmGvUAsr^pKD)F1G%t?%48}zZ7|wNZYDnNVbM_uR#!@!%!)~))z_;;_Z3Wtpkm(0 zs;VY}KgKpknF#Z1q~(gpB2JUk--p+)zAxMg%%*>I%QGISmF;@&P81QtNMK%|=>|#V zQsvW2|4F6u$zGLAUh({Uc(16cPBx!Vi9kT%psZn_G4601NKr<=!2$3SibS-UF)^Us~r zrt5VqJ?(SMMq|8-)7Yk%w7dNzrIQmo)kBfrjjOX9=aSVQt5t~W-mec=PAjLBb{ROF zBo-=&s~Z*F_9U4s0atk4nDHBLjD&}efj=&D*^#TyK0J;JFu4ezR&+o%Ae&zCxIup1 zuS!{4$@!m)-}#&)9H530h$cT|an0i8p!)bfA%WtDjA0RvcAt9-i4OcF*!9V>EAk7S zH`$m`S8dc&f(PO_#tY+sSEcargSFA-t1rP0d2+7y(cS&H(N%)8c6I_fIyQo70J8o9 z%i>b%J@Fwjm&AL3TqF!E$PnjVn{!&z^_`!G&Tohk>8a>GB}y3hYAdKb!5Q!Bs*0HH zI=zrMVU zj<3pqC^5tbK(XAhw#|!f=y}>Xyf3hIiV`A}i1Z(D1y-;Tyc+%LP@_VGDc^C3`1P8B zJK@))ZIJsUi2|_!;s!W1Ky&ptQGggY+bcW7>jY6?J>aw$47Df_zbZUnmFCg#iqPj32n4K^zC?2f9uk+G3 zDH1Ozq_3vBD}3+8OiB8?!ROa)*0<~niU_v7nsPIL@eS{`G+s-8YOHJtZ)~#%Ch07t zL#q*_Y2=?X&QY>y_u4to6q&28LJ&9;(J$JDV%e?b=L~XjTF|YH^ zL*XO3+W`t>?0?tB`2VRkA~U70Dy1QJw_3N7yWbgbns)&S!`GI5=igxN{UubB- zJB@+iDLIEW=hq##g7|pV!6DvCsPG9C$>#?M=m)beK`(&2%$LtG&Xbaij%IS%-1;acFgXd1?p|tw#!_Q>K>=qVEvPkCQaTk< zz2DRW#(AJ|KtXtpo^jUU(ll7)pJ3kRyi%cO{Mg#|~W~276uR3MAZ=eRk;t$f@VR!nBa`5mP zjG~xJ);EOY3UrhlmjJQAZ?u^R%!|rBC041i>GVS#s$CyCN`Z3=)JuRuxlY&|nC02CzDkAM_F_k%(Gv+kt@*ZS!X2 z+mq|%AnYF9iI8QJ>uoLOFn@SiVLOlC;gjn@gtP?kV-GGba9fUVgk$CpVq2WUOIyA{ z>hC2Icgh?{0q+LT#rOYHr>%SHg{a#tY4F@g(Td4xMr+&zPOxN+xbZ#V?e(&lE|dy) zK3k~Wp@FTu`QS?kTPD`^p_wh5{u#tdiklH^xHQa|FsO6r&<#-k3*P0cs=vv~%$4Hr7{8X#Iyq4#%me63R8`R72MBobpciIP z$~%2pZk{gybZ2sox13+?1c8Br1@$niN~Oxb-^R8-pIuo1n`3w_76}*ccqiqWV=t%6 z=d6j)4~}UzZ%ol~b4YS*6U=jD4FTmg(h~vn`lm4*iOLpw?iN}2@Bxwb(U)s0%hyXZ zD@Px{5CAyyoj9Px>3HQIkqj(YrYgl7FLoFZk_R$;BYJ|<;l#Y>ebP2u8arQkai?K9 zzOLxhZMJ0a)LQZoYV=;toSGDy_o0Dl1z1V41PC4iI54mynoK@ehy~oHG|9!};-Gn1 z9uu0y_`CBS4_D-Z36tk7tbGClv*~T%(^hJ6 z(1Z*7#d61mIlizLN3$*lHDB|z^Gt*WZ2KW>n`iMw4tVx#CalGm5Gm2rUJ5_j^TdTx z!jU^(w__$=Pmv?NBR@cqNk*>K?U{~&S zYjopwe_y3hMED06F|+Ht!-f*TYapM$K#_PzmJf=TrqSguXteC&(utIHv)^7{@V<37 zA4>?oyYN^9AB!$PQ7zKQwd8{PvRa3Vn&k!7VxZcy#b5thly-kq|NGG^+5;V-XhFTq z^xj!p&4VHc!^}__HH+T6%;MUq_fIm6`tZUyqw7h*TBS~Wsf3CrN=euI%SSh9HXBF< z*(zmloBrc&x<@NVOQFQSt+a%fvzcvQuFaQ;GI_Jtcsciveg(`3H4*?Wz*#nh2W<)7vio zoR+Si6Z!~m-8@A^%!Q^W-Ryl0eesPuR9Z)PxIx{JMR;JlZ1JZ6!fs*x8{6UPQSF_UGh z_|WM@3AV9~ZF;V3>^Ao7f?fLBojZk2l1vi-h3fWZRYN?mO9whHl;-uQtHf2WTqkx` z$L}N@9|fWi&kobxr3?Wdg{5fL(!tL|h9Qy4;s!zKe{6-Vf;6^zOq} z6^)0?pRLC>!`|b)r7Z=T!fLGVl?}e^k)nxoCqU=AUnc+uvbRg|e-MohB2BKDfa{`b zN=dxkMV<(_-)?aY%r&h4AF_z-^mc@{h<;iY1LK4 zrcE5zbNHKPL_|*_$qL^pC*XD|hkQz*%-z^XPR+1%5h+zyeGMd%Yv&WaBnAa7kf9wk zNs~Nn=qRc}F)+}CdO{I^fS@`&_}Q8g5WWkvb&U*JxXHki1m~NVumM+}%pmEVy|Cr2 zv2jg!es}AkWN8Z$_pYUT;T_4Xn3zKMmRh>U{psdw499uA7N7KG z%7c__7xfck(ailYIB+=I;D5~mh}Py)≪_uO zX&&a7!^Pz$fX%H{838|jDSPFzVS3qiP4{kRGVg-gvFWP_&Hn6Pst!lk>4YJ_&PLWv zAL*LIRZC?_TIpeI^A*+YEHJhId$R}Gzu8>Z>IlC=_d8QdN`H5STo4)PXgO4eT_Wi= z#*i()hbHXR$Uv|qHz=wB(HvM~Ea~>nmME^+YwH5*S;p6V7lAhoCU=KwKIhkKGx<4rural-qw`9@?QsVmabO?Ig>e5s?&Ra!2{hisy-rK**m0D)9_3sG;qqV8$0UHjE3TywF*hHU_Eda{tFT6_^J&u1KS3i%uR?P|gFJUXu>%OBt;i-$puc&YY7SukaG4jg z0)#Pxpb18wWC=_t;vv8D_H-{1&>)NJMR90)!%VaYPp^Cdtkn$yYJ3y~_@-ShDH0>t z50)lZe*C>`j|~5?(a1ccb*Y!7K5ACn&@F2haP#cS%jHO^UN1>GU$#y=_e}}lLz@wq zhxPPBXp@?&h91l_=Rq^fkF<&%zwQ@@`BCFd0&AQ#qYG4%a%YSd)mRH&N2q*lCvhfn z4ED=HMKLnD900L?Q3-^RYiCAlXHB*JTtcG$&Z6l{?T~A{Zp>tGD~e{$C}fg^2KI%5 zaDJraa%UfPj8`HN&7iism`kL^NOZ$Ia^Ga~cXK!QR;?FLUD4iW3HaFu4sX>F%)Rok_W1Fh1!tU!^ zK&U4_c z);(VOJ~2|$RE>lS^sq}^+V7=21>S^y$33wpdv83_3jYiF6nOyGi;sFVs($?k8|{5L z1RY6gxwfQ(?v-mjug7XcR0F=JBldrHj2JWKBxv^T4H$I&OX>o!SdPtUtx7vojj@tG zmMsVdF5*^KV(!26v3?l;8?1z#c8+y(cS5#GvnbxU`3p^tSajeRPZhm{5EL`;dp?F< zM;dQU0LxMKxGY$>O{fTU9dAk5WE}ghvTtXUs_WSO1!YatFh)OR@XU4F(48bYqkE#C4vc zn}?q19v{cJqm6?AO9DVd#mv#K z#r3b{Mdq-8EQ>1xy{S)$GmV6Jq5l583S@!k<U^5Xrc6LK9$1E#iv*k3nTRxb zsVM6T05(Y^1eU6y8ie>Sf=dxyL&lMgTrW}&oLChV=pUY!m4A z?`nIz#-j+O<~z3r)RLXM>rDwR;-;#!3{jplrVp=s|2^ffG7I(g`0qZVTWo#)VF%%+eTO`Y#Ygwym^>Uui`9Ul zenu*#CLd6prX~N3?z>F>9jOFO=4z|OOBW}3SIB+Fw23)p%=W%H+(^{F<{Sk}oja`D z!4JyvC0$bH{|R;Md}3$ayyBXUq(ewLcx~;Q~P60p`|<6(B_NlIe}E7B*ry zcj_d7RV<+N>e3hRhAW~Z2CxRiJ;s6S;%nji!fK!(eDpGMJG^fFhy>h(PmgTJ#)8le z7aCGB(;!w;+_?a)06ucDvMO7IG;<6mplL(!Kpo!cjc1wWb&bU6nG?HT`z-+$GwkFi zOoe|5(D4?H(S3sRI3)WXVo%uj!-*~>H9aj>=%!xi2;Uc$8I(^QAaRyzmAvD4TSzvr z-UjSRMW^dJigTlO9p2L+7Daj@`hfY$JV5XHYghKiaLM$9A&e?acaN)L+=z*vGQs6x zShgV-DL%F{h=xal`8TwaD|`(1LP~E=tH=RpFg$jlcatVPGOB_FfE)=>W33Plz#azT z?tr(X&93N1virPYNl%z9wP zf*pU;Li1p&VXNlrl(n}@lwIl*z-e#^(D!pFlR}kN72RPMNe1;`=9xV9r;K?Ofn1`I z3U^xPsF<;Ht};qfzwI#`>D6bT5MvBcTgvJI<<&8 z!A#xvm40<9>_gjZG0KeJjPYiScn%{L-a5=`tv}b%;M0q!KBCR=MM^dFD@tDwwVVi> zsF;rIU0tc^s2}G(W50-%_94Be*v|=hTo9Fo5>DURY&~{^?o_|Z-s7~;0ruL9dK-sk zSZWh#7k`18{BZLeozYsz1YMG9%h5HJ^m)ac9&Y#xl3~A|5yHr*goKGm^62T@_jl`0O|~C*JL1 zOdTIJAWy_ieB(l__(sLh?L4Q>#;&&vc-F&=TQ;MxQbfkLPQC*o*@649?L9?XYtQ~4 zbbAlDFY>6DIX2z4yc&7S1H8d#O=do&0?(IUGq;LKacs(nRbJD4#5o3b8_YW)i)T;f zqHH`TxIXedlV96=L{7&pcKCKBVY3a>(=LW!VZLPRanfo~xX&@kyc?n|DX+$+YqJDE zIWmhKuMu2oHbPXVP|0J79$gi(9$+R5aCiWvsfiB2ZSL7JH4C{@`@oQ>;zPd%v-fA- zOQ)YmR3vu2tcm1_oy%WoKP5_1?(AZU2P~zL5&lXjk^u$%N6R^@r~u~)EcV4?xk;KQ zP-6)EY7XncGWeq;H~D`tmp{Ai&cm8d$+rd40A>!@3cu6Tfc=oeW`M)#VTe`>7l2={ zmWzH^fVPy6jIn%Q_)t;t8yGk9M5LrT!X{W*M-`nb*kB2mKVtyB1;!bABOzk7&U zCBMWAh)!IppI@9ITW)zOh!cLb13G`o3f`G)hQ1+?z0RTVl8KrF%}|~j2k;ha0f63I1}1GY?9S{#|j+9 zyNl9BTZ2i8utX0N>5hg{=?W7Q!`*Vfx*iofNrD=ZiutiUYt=+1&JcfFMvD?ER{(Qe z=r=xh3-7IC9g@7etj@cbAZ$ARJ>?Aii{JIFUCiaQGJ8&vSiOyU6Nt~~QyIlk&}9n} zJN9sPV5f1tpl{5$=NVG_{;R(DodgLVF9l%vopCtZwy`QV>pK&(cUS0~&D~xgDwujG~7KJv76& zSJcr*2v6<@;Y0{F;#Zq>ZGJvO)^59HS^`RGlS2|drlh7pY#m~htCRtjq031ey6i>axzhy4nP8*oq^XxRW5$#iaSa3mgVvQUC~%>Q z3ffP->T(mKOv2gq3xz}Er_esn8UC3=yR6eI;K=_F>F!{_ks3IB0mk!-ef+TfDHC3( z^y6-)fE(@bUZJDK_;t#rpNj0;031tue9y*7!?M05R6kAX56ahNi-Dk16HT|FVe}L` zK7O#2jpdQ`?hkUHYM~qLcr_6&P!J@T82J1(KtG=3PQRUb`Mg9ESLN#ul8|ryg5-94 z=lBsoc~89e1KyA6jbgn{ZAH|5lCUvrcs8BgU1ILE>O&wwBY~|<1c->>bd}9Cc@z5H+r%U(baP zW;Hl)QB%@~5#{4`9zS{)Kdn@k>c|iC+^rvATn8bIhjO&$JS3)LTDKo7eGzT`f9U!O zsHoTOT~H(pT0%-fKt*5#=}__@B_iDo(p^I+NQcsm0)o=rDa{Z9QUWt{!_Wf^ao_Pf z=YRj}p6|YE39jV~qyF~0_p_hH?IC(U*rfs zSj;@b1uSS|_B3WAO&u{%G(OtJq_qwI1>|p98=&tQT%AoQS7}aoUr`=!PrI)Y#$l$x zGd&gS@)sn1_BG>>X_cO#!;oM0Mr6C7H)W1UoU^$3Wy=t?+`D7Xj zJ=%P?**?J+1u9K%@^X_fK*KE|6zChx&6846r#0U`5#_dJ|{x62RicV9$E<{nhuekefGbh{50$FeHOTE(*tAIM{^hk(lmknfP5c(M(Teq1)K* z@KG9HB7s$~vipwY6l`qczD?sRDja{jFs#Jw)uwLG8ptvy8;r*(F&3TnGf3)1B_!Q` z{)+M`u>XQSVK1v_nGz66S7a&eAdTA z+@J){-~0ODe8hvtZ+i2JI|dAh9L+owo%-)Ts6Q3AXsjJyL|-oYoKFokeRw%P<7)`t zGJ_t*67BW2T-qum3~qn^Z7_?vJ;dpHy4|vOuWzre$v}GP{Fj`Q@4kC;Z|3>0n#}Fj zoR(ZgM|GzN-(=y-%T&+KosB6@3l@00@&&vdx-UNjUV@3kgWf2F-&KNeF5DNr?Y<@T zXB{!dnEpAdS$OmwU{(Qi_f7bN!8(RUphL1l{3nQm_nXpqisSR_`4Vr1n)J~&c+;^chDeAlf8axMBf&RMONYf*MMfQWgy^YBMtAU-^?dvrvQeR$w;d|Bz ziaVGpr65l`ka5J0jw&c9LLkqiiKTH~a3}q6V8%g1jSC+bQu)&3Xky5b$@`x*IaO2B za$Xl;f6RTj?Uw4{8vl8;jg6qoyXW8qzJOsA!8ODN{I3`sgv|&N1xozn>KX*?A8R#1 z!^f-4l&pzu`tO4HQ8!&Fr#S0ia{GZSGzv|Hvi$2KiVZHYobeJLLPv0pjMKr_R!@|( zALBk8m>91zK)4kXrXUncI15x!Xzp;v#=PdB2vv~!{)#D#>6$PVzR_d6!q_0oOzvp! z+l&adsY^GTA)B+{ckChGg47)%d_q)31chMr=fxMdB#NVnrHC-7FcyhV#*PPi+`P-r)?g_dbk7z%`Z(^}R{L+gv znImJ{NowiZVVynaZYszCF{=Iwy}ldUhS@{t%ZsL&V-&pqPQxRN>+4NhW%FB2Jzo*U z8+3b!F^$zGj9CQJd#wSp=t?32svzZm(b!8_N0Ii>0PxB=@G3a^kMW4L{2dQL96jEJ z6G@~6J0nG{Vm=V zunMa{*V-Td1N_bhV@KjavGWvA&{Yq;e_AwXIqOL|^L-lp+ zYtDGc_^Xgx9V$>=tdnmq5IS$&>tXhz$1>V(qo|5b(&Uhrx<>Wf7~Mwb4;-=&1RIX& zpx#nW@{XWX^MW>{=Y}-n+*8&~Hke{fZr9xVBq-1vnAx|o+FCXRItnJu+1$l!O{J{O zrq5`gy%t`g5UY2FyZ`+$F7_O5l&{bink(lq3m_qihAzDD-IO(uq|MN2sXaNF#XG4R z5|Jp#1dc=IINn0t^N7p$li$_6#=Zu^rFV)`R*LgE1G*`=&b+w4p*T};`m63wzypI- zONe&l`M|`UXi19j^m5v-*TVC`VwYGoe%9+Yi5OdQg4298*#KBctmc1A0|S`;oV0Ly z-xH(ev$2wlw`IQsQD4A<^~GrSELIRJF-MRG&d__SH~8JGC(v^}1dzzCM()g~(HZB( z^Dmk#@~R-bF$|9SX2!P%W7M)>Yyry46y&rAFNmv9G;O1)qjDncfutt5qr0wD(wNqr z*P(!S{qn{b;H1+g@8sF4@b5rr790B}Uo8wYrU7|<5Tz8>2~3MfnkWce_KM>*sL-XP ze?@H0r)7hlG&@X%4hSnxuBIB$_vJ=9ijj!b-U+XgjUCVFH~ zILgi*k0;Z&_Fp3(Fsb6T`s_}AzSyxMmiX-CigPXi zZx;T}JXeBj8XVpak;yL07~y?TPBN~YwMK3`up7dJAhPlysw|$~X=xVd*zmK88wu07 zy^p=By}I^Q6x7mXMn049Z-l!T9y;G=8lsbKUEX_&ix51A=09Wp+m_5x4~`e!eotF&!1zI&vezb|Ho^eh^`op_7yl??Y~oOha5 z%gXyMSTwhaUup;|d$AKOIjHY@U!JX=P8rOuaGiTIEQto3%Mqha83sGYQ3+?NY-{^Ge-SiOpv23J&gP zB@0_7)ldT(2KZvSx2$2xSj&@{2>+6-VaJTots_hK1{b{RLQV7mMNjw!)4t~w{ZR+F zHAH=|pg!hpo3uz0r0#qc#5-i=Dr9403kILck){+;$fD7-D}tIj!IP2S8Lsk~UfC}a z{}5{S&3oG~Ts`X8I_sTKL7kn=9D^BXRi<0+xN~PN z^H|ZK7g1!?xX%HyWa!m;>5|#hOAoB-m<_$9jFO9ugBQxWk9>`Fw`92!!_F9~IwIgR zf*8ED>@od;SW{iTD;(0^`ElO3=h!l}X`Md!Kr*QFqt-KK#x|)SUPZasO5f(%q73Sd zvt!W-Z-YgszxudU*TLsaA?gc4oZCSiEJwb!szP$XcE7)79#Jn{|1FowG5A+@++>&6 z;N4HF2~2bQRAUoLH?7DJEq}T0wI?}+dTwfj7>7gVr2_wqXk>&KO5DeZc8+?xc=3i( zJYrLiC1+slE8Sfzzj5ffe8YKt<{7Ua8s(eB&^YPIWbzF<$91((b5i2Bvq?MH$M!Tx zb{_0XP2v=N=P$EA#4W$-f!Zn=bMoOUF-JL-!MF)0`Hj_ghQ zo@tz9`mUl5f>!X zVisblkjw#g7%9*|;baN0!kkw|AF63RO;r&1jaap`k3Kd1Ve{+><*oeu_r$w!N&LVu zoSJIY3&#+zyIA}xQgOMw!gOakIyUK|u&yc4=EA>z2lo(sCBk(%yAZ<4$Yrs5Nh^+! zdtTuM%^K^rN*UR4BVZ(EBZxGQZJc5maE_=tI!+$=me#IzR}KH@ShKVBj;r#@NzRdQ zdL8X&xLbh^k~aJ_ZO;L}t5laGX~?`bKfgQ9tn#;QzWOa1=?=$;vSWy-#J-3lT;tj|wUwsQcSvO+UmvgYpB<)%o<)ku#bL3B zol^x8e}hV|zkH+tdC0n@rL!c zj6bZng(6#MUTs93?@Qvx1doZ)wBD09Ce@Y;cl(`tw}xuzdUc8prr=Op7Ud_)x*$d` z1DwU+flmjQ@;l+iFm3ss-)~l1h$?7Jy7>*=LXK{*mLqG2dJ|onSTQ|R=`%;R*BL+& zI6ETW@7?~7;BSLI42;(As!DyWH8P$VG>gqoT>auYu<%8r_Je)5d^(QzY`c}AR*B-5 z6$Z-&dNktIu3}2zBL}Pco&i_eqZ%jCVrOE$3(Uy*hC$xU!_x6b3@2Yp7JxwN-f2O^&JFX9Vec2B)Xl3UtQvz4i@FD)-8J;PVq;dRQaupo_|7|(4DWg zEH?;Ddp@Of+hyFXXsI8_JeexlkDQ$%qyE#tcOb*|{|-S2NgK2-Y3j-ozgX9KZ|FYf zf3>^647);^{AVvBfCVC-V_P;E@aof@$)($j%M68*x#=VE{h#4l-&P_2)B#y!&w6yz zJeDB1p~+c7Kz1M1;$!{-IFT{0wUYLL_c z0U@C*_OLTYx2QSV3@`6gHRx=in10FTQkdj@stUq)46?1cJS@`xXaOYgIVf+jW|NHW zQCUB+${4k&S+}cvx@ziHkXvF_9doaAQqrmkpxUwrmsj#*Ml zTKZ_7sPC!e{L|Sk58Bs1-nzJz=DsSI6=(-9LbXpHyLz5T;J+!(`gW6I`Ta1oW5*-$ zaj-_MmrH!p6uo>)P7Vu|^zZ>I#Xa@cAJ0ymjqsP{(;h0JO$reyA;(VawmFipGntw5Nm`Dxgr+-e zhj)zX8H+GVQQfBkYe)gjduS(a$31^y5`7SqKh~{xLOga#G|vZjKhP&SZVnPLIvClL zz1m4UeSEd_TVDG0vt0RZ({=iFp$zq}x6bP{;J{Ij=zywkWAN1>!b_YIeQKgrbMUSO z#Z`QO@HuyFJ~=+{oWG5U=4>zie>N+Ak#}{dUva~vp8>iYuW>ol{h$587(dL-CRy9P zXOD#xRZ~-;xB**^=`?PGih)TLrcWGcC(5?fu%LpOJao|jk~!Aa$f_lPSqf@u%7e2b zqQX%=6F!w>!&cUz3rXy98xIw&K-K8X2N&a2#fR#`DS=Dn)qZksfOTN3$S0~DQ6mgD z@1iQDpcyNh;DuRMPrp%mmr{EOLJ>1SY4>n@8gk5D5TR3~;ew}wz)q-^6SO!rR;sWgcrxkzVWBQt?Ga$HY0GAKkEX3yf@? z6b}BgIk=h5d7tkW$?hE8prC}azc^|(4sl@;2>&paCe-JV0X;nnM4TmF3W`I&!x+xX zQ2Pyj+nvD_`M#TmgNU>KXO}DD4SoD>7J1Ex%(J?Z*v>qLc8y|X_`ojxErx4cerC~$ zE#1lqWMfl42KUj3vIV(FPv2nbPYFXI@I1 zWCp*NE!ES#E+d@6Pjk1QoqSgd@~Pa_LGJCYRhbCp^~Tv%USohdhW4*3|Z{yMlC0gv&ho<3e{{^V97VhJoT zuQ?e&G=S;bu3UT5ekUTc=kqP1C*W$Hv|OG}pQi(??Oh37gZWXx={a}M78Y8fbrWBN zPtjKkLIw?vXA`MhjiO$G*_i9oE&boF4}bGsr0PZb4Nw>MT#j!!rV9E)Y63JuG-rx4 z;jN61jT9XeY(#mivSV;CZpdO1$I!z>`MxYeNcwAl3{*5x=sb#R#Gwq@1yQY5Zc z!ly#xrPtyK!HPmpB1cPHW^X4q4 z9>Unj$tY~@0?%}3oX_kx%|{=~;^Fbu)X43p<>yB?TlAwsk z`#^s4){S43A+@Jz#2dd+03mNc#KIg-^w6`YmgXbpg$=pMd-68M#$>URfl9x>q`Cow z%(s6B$b)!ag6qZdvUH`hjy))(aT4SC`yKWtzI?293_y11o^c2I*X?^c+!$|g#i#x7 z$MMJ65&5GH_pAao𝔥`cm?jc4C#`hF&II#$4Z**XOMBz}x)`C)&ap?JAX zlrhimgJfk8m}Ux9swr~sx{>K^-LqV>?R;vDKHrEZxfFv72p>~&ws;~?o)qNqtMMf} zdwm)xtR6C0N!{dfJ92%$?UpU)ku&G9GrZ!Hb91T@a-V_o5yK=kR~7H>IIZ7?`*1CoAs z=li{(hI#1RYIA8jxFUGgw-L_8ozaaoFrvm^^CS0Hn*wl)II>c^rN&FyMGr_AIk5ROGJL&9GiK%HBIE|sT^~_&$YFS_FD-*|BX62878vX{e=8I z7tHDE@jcO5{A$2cT|j?2c^_87u&>;a?LR%?Z6K-HOO;UhPI7m2vItgI{9n zMgSD`nBt7-sErbz%4HfZ<|v!UQsb6C z!E6>n0OUk5=aUoJAqgiV`g~UOihI|v9`QJM+Z?~ujuHFf38G=!V*|5^(T5)&Yq-{M@vT^ zV@lmd6}B96xx#9uf(1xC#~9$r$7-uCmRJ}>q}5*4zR!9jkVNNT;t~J?%Y^KNU=joO zch;nypVp|-PY)C~LR=C|Jy!R=cF*Ipa=SZ&G{97rI=*D>nU@Pq0lP;w-e;d(MtsIs zr(u0+Z<>v@6{e_>zeaO1j?KL}+G99|)^hbyJTG+Zik460=6$oLT$#^F0-Kb1t{VPw zOf#SDRykNqaAGw*`#T4!nyQrvpc$|Yn|SHbYt@3fkV?r3iE{S zajShU>*Fu9{8^qh`W5t|GOR}jnSN{ae@^DsS64`kvQpU_Z+kycoku$WV-q>EfMp#* zj|Z5=&@01qEg4clZWOU>2{NQ4{@Gd=R1AZMn&CY~P<-f7S6~S|No4&?BQZet>k~w$ zhnvCA={g3!Il1%;HNav_ zknD;KX({B9!yd#Ahg@vi5*{BX-40feVeV>Y4DWoOpFeKosE)n6`0N81r?og#C^6@# z5XWLVz`E_58ChW==)6O#vpU2xIg>Mu9Nj+J!1riStiLJ8(A{p}(nS?fMRorv?xv_# z!tjn8BhCWL7Z4Y0szOHNu;SD@O@%sxvAT%EuBGY7wi?YY-PoC_7lj9>Ia66bgvG3T z=*o5#ef{<*A^e7!mT?5*fHUA#zB@~e7o!3e=W6l&52AkD?GK}_Fzx~Xe!G_sKpdx| zwMRVs*;zk2_?hP%$;rAQa&f;XA)i@@zkN%pqxP;4)pdwiHQ_wubbzO`MXJ_Ea^ix; zzw*nE62@Z8s!SWHD)?s?fA8MYh$=4SnKD{W1O~|~FK7EQWn7h9+TC8mXBro^{&)r{ zbbi4pfk2w4*OUxtH(YAl7^gVKz7R9~cn3gvpa8WS|C-DzXCq;nEp)GVR#Qsj)Lh8T$Mvzce!(g?4%{ua9FODiQt7|2kvSnV1#R?UL*9(6*Tq?qT5)yR&4(W}nf zK>&ff3jsrJp3=qZiiG_3b-KkM0(;x*B4}1gRVF^WdbTTMPuJ8*gSIEO`8;JgV#B-6 zSHHQM+asfCt(EfNoj*~=oFv_yOtlC~6FY~1k$BLnKCw0?&V?IMFGs{d>@aWM>H{Lb zFnqah{%&&_>W*7p1L(O=m{2XR|0qe@No5T$D;&ei(?(uI?1`B-BOOkz7hQFnjZ?~g z_VtahRd{R#>A_92&&_a;@|%jx|XEfjyA?daa*s#F_Fv9gZ9q`YK#p9Zwg>F zNBIlOs;PmjMuprJ>s$a=F`dd0uvJ24ytE*qbc2TBMRk;;nU>$yjF4=3vnVwm#5L=e z6bWBcXhj6aQ15=4dX2ojNx&aZF@KGcQ!lHf>_u8`4jZev6-DQk!#F4A;iBuesvSXf{N3lw6;y34U8kjb(t81<~r%Cg>mo zaJC*#zp&rjmkDqKAH;1amO5<77rL0l9yP(Z8*7qC8BNsOyo>eDN~ODnXa#Re`FJXM ztCW9w(bBQw8x;u~B)KaMAV?QE>)?vSz3vsC0?I5PKDV z6DKG=^c0G6vl)4c+@(FSo3)zlN=lVeG2#9~=-181T1JqbBgw!0v zThJ_ z;uVk?NiE$Vxwd&$Be=KXe+PT_jdUn%x)y#T40*{92&<1j#hi@^ge-wB z@i6f7J*w)_rjULCXlY#zc8XgGum=qjB^Az#xb5wdxuXxw)aEtbSutGewy+JHw!33k z^dKzj$Tlt4rCv`PR3hyX)oWl~;}omo>~-YU{u%K`l7|+l z|0#6PLtx3!K3b+iF2)Qb+kk2Ze5X0a5wR%6q;3xL`F;^Vvg^sI+$Arbb8zc9_V5t5Lx(wl#QxiDBq@*IxZ?Jgr)F!wQq6Y?ad6UXJ+=*vc5^Gbz#00 z%50lI?Trp%uE@J-<=%s#hXO22;qa-z(#aV5T;Q1=j<1+cf9!@1NhrWM(fzN;p!rWUBSG>g^tt8QvhcXqoB zh2??#p2kdmW6+xd)J^6;cERc8QjD`hmW^N7bAJ}60!9dXnpHa}aL>eUN@MwSHNXN? z;O_FQbf$r#2Zm-5YV3<|f2;s|c=v7_uGcm_5QBZCmP?x%Q4}GB=$M4s;5c45nmu}? zI%Ysr$UHYF7*xT?b)>%lMT%IZjST+Yq|-*v&3+(uXj7?uFI{I?o>nS6g^3%*^m=CA zdQ@D(vD5q1V z`Gxoqc)JN5)>I1sKxr|U zxw>_Fa9e#32}}Vka4iGO2Pso=fuR^t=7pW~_I^kZS={m@@!xS^Vm`0VlM#;VpE=|y z4g|ZXURpac`a64UC`A&u=9xEfrE5+I-QMw`3r5i|(jH7j>^b}ulZ!zZ92B?0vi!#c zv_aEC3jB7&W1LHgKeY=0C@sZ|{mO?Thwl{A>d&X55jj~|05J5>xX|b=uy<*rqdp#j zad=M-z}%8wZEumHs{CJ5)B&)pp2~H)>qtI2&=BbMts%k^AspGK#sPb9;529nF?KJ9 zjb#@!Hlu|2S^0awKU!YyAkKUQC<`2Q?PFC5YOW629wieAUtW|h%(0c^8%92;h7{#U zi*Gs?dqxd(v4Ym}RZ+d}!Q>P2Bv0!FNUO9&{XKC~NIKBt|7kzVbqs1fvSkJvXDWLNz@($ln z`r?nT^18Jym{`!Wf1dDADMrXxk*+FXw4#ex{e`XdZO;rz{G5VaH-IQPVBEj3fl2l4 zuHm=*rc85wqxM0ZB!nM}k$8uEjSzcPloqMeRvF~o>$Olq&0j;a}S*>9Jny53@|mzR9y z+wF`-*-JFFbn&tBL5gan+19xMQsCp8>f!HMhyd6z+L?)FcH&G*Dnr97J|XWTwkn=5 z7#HE9&jjsmiL$qu)3GQEwl}s2PI8i?r7nDCm?f+qiIJpbFduy-+Y@_L_dMh&)WRQe zLYRNRkR^m}I@ysA%)#E|zeA2Onm^~0MZkYcC(_gD^nFj4b+Yx`kHrm|p{LQJQILPi z>g~=?`MhYgL1geoIu6dK7hG-A+C7VxZgY7$zqb3aDV+}9?DS#T_}yc9sM>t~TRM{9 z)Mqh^uMQo%`nAK$64;~U082fUGq#Q)KJ0BuK_+2g;1!w(KcMHUt_GAyWr}zhQ|D*I z*TwFEv=aeH5PMh;%^eUViu1X~Xp(9T&T>~ZBhwinhVki#)`sU9+ z0>)!{(YCsK8rTQ`d^j|g{L_<@BY)B4$b~`7>2&$>Z0=K=gxE-tKKLl{?Hb%eB*XC9 z=-a+Qm*A!QU%uV+ilm>FNwkB1H4*+zr0f7!ISm_$=O}p45UYm~egJMVeXCq_%6w;q z#Y&>v#gZ>2$EyA^Imn%4mk_z*ixisiVJHyXPTJu`>|I)ayFNEiEBDxH_@y?0k2;Z0 zytJa-ezPh&k){^5A2Tt%20M&0#Mu1g$`d}iI#{$s0};o-ovg=-{g*UJy@agf#Izm; zR}!va0fW;-4_z=~>wS-=f{6uUd@*s;o$iAqe2D0VL!+4~qB-GJyJDlJn9r2n ze;Wsh=f;1-4O6qT%V5jm(tmKn1gAmsd8SCN(Ld%PSsCR*ql)JuSxb%WPN<>Aktn}X zK@DL4luI9!&t$dh4j~GatiZ~V2uoG5vNo#XC@e}fV;d*)XO9ZiAVC827>NVr!4gE? z^yV<#Z7LfZhsy>XOywNev)kpKEB#)=L_|c? zbaW6QAtt5KdRcd9CNX}&Pky$n{q7n*Ff$lhFa&y~^TV>(LlWcx!3;zfgvThWYHd(I zZ$YrZoI$PucJu8w(w7_utVTIUWj#s)xM4XhU>*DK@{D!6bwn7+-Mdmh?W#d8A~GPi zkOODf;kjuW(I%4+h-3X^P~cJinJ2dg>sa9II_ID;Yd8UAJ*B|v;3p}9?ZPJg%wy?q z(9Ux0^1=j#1TrAqXcUE})(|3$0g&t;&^)=}cyClrILGQ`O3q{tyh`Wpk9F8IijJgZ z)Q7=o4c*-360F4xwy7g4yD_i<319;-kAWOH3NtA_rYJDl1*z*F(sS!2AjxoXTIY09 z11mou^;mxUM6PYDem^$oR(2;SW{Kk9i!wZt@Y~PV2BBepOW+hPdtolysu7jHPs|p0 z%xbiFQ7bPVA&eG18K+>hr9~_fL}13T{W(js(+I@ss^8_Rt8qTyHU9VM5#2%}Gmj-U zuh7e|#49YJDa>RlaF&u?Xp8SK0z?J(evcAZ{iaT`+w0M9DWI#2ZfKyTr+=ERz#jG< z3j|*H1fzpB1Wu;@Zmm?ingE+dI!8+;#mv-GY2323tg5qXW#!DR^vt8QPOe~?gh;U$Hqv zqn=cx;BD~7LGd^7Ys(UVfqL*R?9Ta%43(*L7>nhNZjWpqVS!On0>z_I-RNQwpyDMj zHmpy3svk9#y5$H+(#NtI9tU%ZVXr{!!7Kt7Vv(amMrEHQ;GfKf0}iU)9%APFzrVUX_!POuSATSA+d5NZc<~;eaqfJ;AMF7#{|}geIwMnc z8T8nC$zpgJdr4EQDw>G{i}G|5Tp1ucXaXCAD;yosExvnZcjZ;PeCz1I;Tx(TDam}s z^dphLvkg!-0AsRvu9$dbg4GsY)Vr`v3f#vZBferf7fA(emF#xNwmX;wlu|0wW z*m9Hkg}BSVjHj`OkdRR6$ep4qspS&0y%_~soD0r`Z~YUmemOpmPrqLGj~3w6RO(b< zd<&y&0fd3+(|Pdt0-8jRQO5!^2n!dN4pWg_j+^*L)7Mv|a;7!C<+08LJ{T`1vA`@V zr+GoI(JW`G#gNnSjNo9JaCdTr#T1}Bfr8;}4G?jedPY?pk1szyKi{RU@J;i<2h@AI z9p!a!IUA-y87wB}q0wDr#?UIDH-u~87LCqFeBy$hM7cY^sQt%8y30IO$qjD<*Ec^* z0#cNsulpIxPFkR=fKiTAd;2()(OTSN`~&fB8<~Wm%9A7xHrjz`K)!=y!VFjdki}e_ ziow0ktTN4i<$U7*Yhfv2dB)p}O}y~RC{m9d^uv+xZ^+Cu^pGh^j^a0SX(!X1{WKQqU#fH zPX(0jm4QLTf*8=>{Eo__M>Q?XkJS68`V5j)Xq#;MgoT)od-sGX7?Kbcu=V z1VQ*i2qBFKu5v4}y2hRPlftSRC4Wng|z8^r+;pzT^?$Qw^y{^P&Fy9Xc`!d zq`4g(m86^p00oc$tS8XV$*+MuYoOmKmv`D0H#N1x>LpfKmLXpz&%MZReKGm@ z-}*>tq~Dmy3BY#>uxe`(Ua2LG?MK&SqcZaI0Y6R;Tw*o}U)aV`VS;T0Bg`2Xl-JZN zWcz%_{?gP!K%UD3P|m53$v!0!UZivD5(a85pv-#uNCt<@@|lhyBY?dE#Wfd?icOWK zUes&EO;JgbOS3RyU;lE`V{z}-P-v{v4`3yS_rDgttoKZ`%a-Ryj=a>_G;739bAQvE zwSQMytyFy0!lJQ#rcMgGB^dlCKfmYpRBXh+1xARGS}NKT|NdZ|Rf zTeB`gWP^jZklSTG7eb@GOXeqa`Q!6Q*YjyA%@1v&hLLT-_0Ovb{oNZ5aj#>fC>f%# zsauo+?t4stPBk`hcBVV$D==$fH=1QzKG_qc)*dR45RkLvO+8Vg62n@4ge8`&L`@hR z2YVo`Qiw`6yxmr!&Cez=*QNdK5x~YjN`wU9-VRY%7`@aYgem})(P{hw{~fO!DAgaH z`Sj&8X-j{;8{}8*i3E~90CcnK2afGF75UHQV%?V&n28hi2~#kmv)hD|bNc)<$Q@NW&a^ zK87YyADpB^I)R_6L0IBo0u89k*7AISlnP|a7mdooR-+*_9V!Z@*_6iOWF($7psa2orAc>f zrm^}CmgCD1Rf%j3*%zr6_!r?P^R8PbLgwYc$qYu6WDz>X=cJpD-@6mHrU+e&`krX1 z5w7Ph$FPY4Y4Uy=enGfZU~0+Nwh4ydv5E7&%@W87J0lA<Q4|SE%4J1PT=yj z$AVDn*q>{&j%NG@H5#`t?Pq_EXV{%!NzC%sjN^_se{@`b@Xz00mOebAB|M$%7VCnF zwM-OVea_EETzpsd$@ijN{D*Oog$dR~aeE^%wK5HRq2dOb`wC>ZEYa5GDg>rCV&6V4?r+-rz#~!bob|~=Ef2nOcgdW6i5s_x~WeA z%5<;EZ&b7I4uTO}ZdK7zjtVik9dg&6YpDU_0xw=v3uzv<1QI8(nHFe?V**(eiPsmL<*woIx(Xs9jS^XhT9V=@sb4u6*+v%GO^ z{dQm*Ui1N>y=d%PiDyMrL)}}EC}2pFT`n}ULTfg5U1^!_@dZFaW!_l`cN-Ngrqf#l zbj}i}@HyTi%Y(=zd}I?;Auq}s_0n`idHY@vX8KaS*c~lI9$Pk6CCJQtPCOEr7J!+X z!~$&|fJqj%`vTpDrCrV3=#-G2hA$wH316dSkib0{?6I&sbcm$4+q{@`QsNcvp!L1w zeL``(dr!fw^gwc9nb;tKn3j0smh%Vy2ZjTWaO`fkQHva@CF2Vv0ajk{uBvR^6Ks>~ zf&N4VYy3g}ZQc%4+$4N*-^%HmA^yi&GjpWAyZS%onod@*GI@7O3DvuAV3R57)=P3t z{10&x_uq&c5G_tly2X7{S}IPava_=hM|DF!N`8O#Ph)U>8a`ZAFxVNBhf&9up$k+9~f;xh1=+pI=8oV1f9z677K)Ztb_CxA?j zmV{O;cR=2rTBMje@UX0j`eF3ey2->)81csTN`M7GW#nWs;Ust!0Y`2PK4sYlku%N z#sQfHG|L#?->z(I5=idA2k#58MS?cMB{;@)$q0xEXfyB>5`Nr(Jxo7&-zNL;i(qSq z;2|QQPN2O%SPI7I>x*-6J&9;99FnVTn17>M+gLaB=z)g;ml)3buq^PrQJutgm#^)g zz*z&?+q!|rB5;fvYWTVK!r32&t}T?cJjAz({m9E`O=?rFy)ZE0VdovdQYh}TulZ*I z=^v23p8emr;it*FU{Phvl#N@7miVXKb>!L1s+fjYl;b~nf3`-j?)Bn)_JXi-c1;cn z1y-{Ea5PbbMAY1Gf$s))73a?oMvNtChU*&o(thnhJn*%Q?yz#C55Kg9? z7a_}BF2WXN5>W+o6KZNyCV#~&P5a*3ciDrhp2duejRIcRyK>;THp7jrf%Zw%?)az; zF9F}ro_je~7((a`pSu+WT$%Sw|3Dj54WvjXKAjp$ijp|AK{&f@l&gWL*sLli))gdq zE(e?gm0Hn9f}Vs0y3)&!!Q3;oHn{0s8wO;l@a%He2`(9b8*74Ffnvoli{j|f(7}a( zs|Px6dhZvkF?w0Fr(Obo^S+lU(>+JJ6T2=&0HAmxc@7W6(kmsItv<>;3{~8C-V_p& z76v%u2yT911nbQH`fppjyL?QOxQtd-s_cE>OU8Yp^Usk>rmN-KGGl=Yqx9xH$35iW6VcW zYM`ktdEbUnPy!|zMQ{Bin}b=2G@`1Oc;kW?)P>C}JS$Atl&hX&`qpX?edQg^NJQ0m zbH?M|`ojpjgr&6wU5?H&6MTpb>{DS!85va>3C=r)_a}@!CNcaMM8hWjjV#Yeaa4%! zL*D;2n)3R{@@YL_x65SiMdl=DtjoJeE11m7#d9!C1yBVqJ@6O>DnJNPy5Mi%Hdqe=afNs+@eu|@{Us` zTdR-Ow9vt+^5leE2ONah*Q^hOPYDlf2JPx#@e4P-JLyMl`q=3{O$K(bf~BV+y8gh7 z&qAjCY@mmf-FX)h#(a*$G2FjDoJdBCvEfD_`ABvtp!`sdpl;+#;I-(HOR@!Jh8)9R zr4nDnkm%i#v!>ICOK~w$Mg>Zt)}ag1g<_-GHrfazN4p8C7nv)kaG3X7xL})fr+3_zV=k zQcw1`t0a|(Tu<2hVSwH&f}097>fA1bCiwS|o2k<~aCm_j?LH3Mys`76z6?rGDuiSx z;4|K4JSDbF2^xFbIX}-RD=Q0hT%T4Y!3c@6apQ<7+*Tj_N=3;(BpApgwSurysvlH7 zVZ^Dg?$m^N)pa}|fOHwrJ;iB-4Tt0w@4>}ML&Ze>PM7c@KaZaPV{mlszgWJo#W_z8 zaMyH`2SZC?Py4c16i4Qv#LkChBLp1Ju<8uz0CUSpSS_SiqgorZYCd`sDh=jjw zYuoo1J6w_*EKIv|z)ch|R3gkETEuW|2WH-TG3H}OH@mRyZGW&c+`wY>UY<@agx$Cis7-ogem&kP)on7eg#@>Pg^en+AP1~^ z9$7F^?6@7tUt8|kSkVA8#Yk6Tq&%A^k|DSaT4W$5ffo$B(s9aF>(x6sCi5Sh%G zB_NzIkXj(dLXOj_$oGx zpqI>GH6X)rB6MMI*kqwpec~dezDV#en6_RrtkO__aEb<5rn+;R(Pr^4-S<8#tiKAJ z&#J7?g3KyRfg>pOZJk}#+u_*RZCkhw9=0)GGQ?GNpV#6|6qXo8ag^jKdJ%oPhR5~s zYop~~=TFBwrH`-5@S%VZrwDhBnpsvTClKx=oanRGrO`7`r^|n1N5_~sHhAf&aRVq;veF*j*DFz4;25Q z8ueph@oSOZ_0?aCAB`7`@#RDJYm2Q@a=#z~Q(}3+Fv!BHLp@o9Yo%>NQ_VQw@jO-L zVgfq^-AZ)l`^E}%>)dQ>Tbw@hy7am5P0OS&A32j=i4ou=V%qugtaTzFe*iS_-^i`fzD3Vi9+?qKmg^b0;poS zl&AM10oUEgPM&-f7~+WU=iZ!siw@kS^hMzrt(mE=7KUF$YwOhU%wSFtxTK>-k+#=h z47VPNTluZx3mEY3L(e?BsM1_9rKzC5SW*~cW>YhyYvzs@_(J8sHKb@kOtck%>Y=Za zwwc1Yxnx=Gplvib1CDZOUWD({yC=E_JD{C1i6|M$*C-}C0QC+&YoEiqrdbrSf2 z#B1n`YTNIdDfRi9oQWLK(OO07K(MB##%n8&KrMMHrQ`zW2O11)VO~{Po8DeX@Y+W9 zp3%5HP*xBz7oo3csOg5o>Af{d%H5Z5dV6~>0fB77v}SFiz7k%9a#pox22c7xYtr^& z06-fIBKJG~(wjJh18tC2!ktZaMeOP?4*6klZ;6QMIcUb}k``{)?M*%zFQipN6tALI z{IZ)ZXuYl{L|zaVDaY7)Xy~UCU)NjHtg+57UT8bRu8FpH-dv+#p!e&!IP%$ewHTSl ze$(Nj#VKF8&w|$b;Y2#$AVn;M7HODE}|Lfu=E0jMu$rN1e{CU03(*EH^M#h5b_Mtw`g5IgIZO zyB&>29UVwb8FZY;Pw%V~r3OP>0)Ue>pNdF_2G1HNK3=|i+$WlQ8V8cz0MJs_}3SxEC93zphpKZUtm*cBezXZ z7Dy9W+63^rh$XRF!9b{t7K$&+$_-S^wuo}O3EGKnjCZZ5Z7<5!X>{HtlpP?kN{Cr` zXr>jDLl7$OFev)W|GaR14cwFUJvQg^F4C=1xbeO9^>vdWM|XvmEv+}V=s6fb{7r@d zoxsX6E!M%X#4%eOQAVycFcS6cFmwTWMyS4X8iiOv6E#Q6({Z{=;xwiamZZ8Wi6v8=B~v=*P7!0*bS*@9+m45Y^ss$m zn)~|^{QWKQ`G1Rs)76cqE2*pC8Hy{!EK%Ce)H<#_|L6AkbW-iX7n|}ng;MHs^B<|h z9>B)_4`Ejw)^z*5QBYAqKq<)=1repYQ4kO*m6De3mKZe^r3D>G!<3YkZU)jh0RhR; zqeqY2eh+WQ_qu-j1BXnxKF@j1Irq6wh3?wQ8x9Mq$_-;_!SVo@<#ost-V`;yAuzrH zr0iI}yEC#V^mCd?CKr3|-hm$-qen*GAUr)i<1wqeaHR2WEDv&tHP7!*nkRI+3=RO# zcdV2lszk3)Oj7*YGi8iat5|XBbHR9C)CiD_pe1qVuu!X>3UMXtNJOGq)*JE$TA<;k z>2~^e>_Cwat7=i=;@2_{dU8ygnJjVBq0mCnrYnTclp&|>!$Y*h&{~3g$<%YdhEvzr zBJD}-x$nHmlIz&gedX0^>TTd1i^jZH{Zm91kE0!A9H3+5qA}!z(q7?0UMm30YH4i# zB00q?#;WcHh|%1r+#iNg4~p}f;ttjh**hopx8nWF}` za2VTKLEu)#YdkS|pYd1sTX=k@FJIs>IZgJSzP2vu+J*34IfJ2HI!vjyc~&qCKu+)n z&aOC>EOTJxfR7r|8!a#^diGtIlvYlRt_a8!)Q*=_w3V$4pMqJP0wW7g&sg9htp#s% z@xxTV=t?K6DK_SpH6_F$b&cyDq1?kyaSN&-qq?97tU+P#;m;gcB0op=>a={A!H&yt z*kRbth%&CHJW4QwQ@LM|@pX%Pk9XZIo=c%U{-EVb>1vXjs9jO-bmToUpT_HMKN^m3q|uh z(F{r|faW@UX;O(%MY{NOugyC=jeS~16=nJ@FOH8ZlQMJv!P_Ojjh*^7MRjKH^+JrB zCnUBetY(!5TUA%vQ><^AWFj8_G=@z#!DJ#k4)Vr&#>^OTIS2tKCx;F>q}Z)q3zSqZ z9e;j13U-47l#{R~JNvyzo^XwYNCSU)8}|A~#ElRIJrfn4vW}0UGWS3D>~8X8fD?P4QC0whr$BQEHly=6yj5W z30lA`nmdSIlAmQEIxI+Ypfe4pHKTpkMrm=;$EVxVqtbQvj!uDr38s^3p{6F6*qcrBE#4G6lIDk~ z)9#|%ovy^M=u6)5=%ax`3zE8PJ;@)=+e#Abdf5Mho)B3Q{$iT};&S6dxl?v^XilzZ z-jymh-yr><3NQSk-<6>Ynx9ieq~vwMt^~=hpt#bqNPD#8k+@mIwiG^XcDAie-^^u* zB8o*5vq^N8z`;I%cpcT_tSA?ew{{qYyD*(sG^~f^?ekTpQ z!SS=hGtSD*V~epMqQEty@*5|dPp!>dNx^nNy;+=`;-K^~(XY$g|8kDkfsnuortHiA z=^pC^77npVk7%5z@kG)cT1_4y@IZpe2N$mYriM4*=P80&&Qh2Kx>^a^-%N>xp~9OK z%y^rvdr4sR_UxZ6?MOaM;}yTGB!Gj}q5?B|oNjbNQfB2o0bsi#dGc$ zfS4A>+GJ-jag$;r(gAyey?>wN6(;K)v@=VsH!EA|qVRLx7e$1huu_U^6m=LeBWAZs z@$}1#z<w|4vW=s-}i8ZFViEw*jiE6V6( zwlySq-~;$jZUqYG-yPy_e|)fVb~RbX;c&Wg?*G-*Ob7)IT;U$$|a0CcS z;t79`N~O61r7J)Pxi3W|$s^Wat5!}EG*yX>tvNxP=d-m27XfC<4>cf2nmZVpQxNph zHGw}_Exy-s#}65Bfei2h1uKA71?Q(56P-p;lema|A#5g`=zy^*86gjzXpW0|z)`PW z5=CCg7f5^4LU%@(Z)3^6)!Qn_#}jk)Rdo*dFRBaT)w0rcTVH^L5?n4E0HhKF&P5Qd ztT^|YB&X571HJ8lxIL`5sxvAvDy*>csxty1F1OOdaq^E>Snh?3q92y54l<>y7ex{H zVtkhCEk`&ZkENzSL~+#R=g5p&2$&@kwT<{0zs}ob6~4_UZzSm^jMfI` z5=1QBtw;(x&hr5w=YwuuqA$Ha)Bep}iKeSxgv`_|+?XN@9^dcp8QUo#r>DhV-8A}z@AT#YpcQDa3U+lU|rYD(zhA?7MFb6a&(Ij<5tijWO57R9?cPh z=7kq8%pt9U$-g5=T8U2RD(RLYzer?C@}vB7F=?627Zp|gogeawvDi6zg_!ho z?t^D}l2`fStbCGF+;FjFCsrvwlDnAA>BL|5xykiE1?1R3oNMRQBkScv11ovI%dK8- zT`Xlq-fm^VtvNhuS7OM*rqHcRm55j$>pap(!p+S7EvEm_6>8zj?w`XA;SEJNx^ z6gij*AnT<&R6}7A`={1h?ALYGAS%*mV|%WVTJ#cf=8SU#ttpXgNVnHnD0Js{Lw?;bD7RQh6~;1m$f`R zJV47^cqeF-RT`i~8##7sgA~7FV=~B4bl3~eE)V7sVL%id-fFg``pKtE@62}}^#lu0 z5Sv%_%@PGC4t$fn&Rvc^mt@IC`kmbhL5Vlbw7zr;jjzJ1F`StuE(?EgC;F(rW9&0BW(D>NO zqMe8q8(50I>*FIA4XK-K{osQEJ(q9DL1Q#%ToF@E#$wA`mE5RQNn z2udyLDH9^e)?oJt(EE65`y-2Dc5UCfgZZ*73ZVIlR&IkSmK9v7&OTx@5+&Gs`?HgV z!=z?Opdz4H&_a^VB)^62qGL%z}n=e(y&jIm`NM;yo*w#!zJpCtGKCfBA`)h68u+v z7Sh@ls*JiKdpED%M4_)A{XohrXhb$6XPpbeSia}qP4H1(KA~EXxSMccaBqlNU~ByV`OzvlyOfFG~x@5mgA9DKwd%FMPwpGRuStjq~K%r*KG zkDb1mWB4zaZa*-X!f;NCv>qP=w02PUC)xBtJ)O0URjhTC<&*VUzG|9si2?1(Su(zQ zh{;hU2s@^}l*LFQ<5jY}K*d+FUcPmLrH|cM4DC&u1ki@C1V*(06AaQ;AW1ba5)LeH z`Nfy)Hlc1j>v5ec(=Y5NX$6RC!p_PhPUo@lT*}$?erD&OJXQ|qK!W~LMeOej=2Q*h z^&T$L4iS&Jh+w z-0tZXV9`L+A*qy>wR5YPVe^@S3wEzWiTsQeNF;BO7mJQ(Q3$9P`EV@QhWg#SImU6l zhrN42z+*w8A^R)7g9y%x6o_0qhp0z~ddgTr)#>q^W1-V?)EmiJ`ksP{q`49Mj!X6lY9%}y#g=m6q8y^qoi0XdO zk^49168K-#(?u5N?FH3IKkP(F;G|3M$;_!l_W(xxEj(^#4}?;^N>~I41#^->V%(PGxBfU-jIhM-IzhC)0wW4H>jHe5D=XP^Pi-6o#ny7x5TnZG}d(I`C;%H zX{HD*^s`M$&%JSmJ?ooA1RAv8i0w_BbzF;c&vh87iSxvTvr|Gg+p!N>O?lOSHi|{A ziIL&mf)Fyrh1=mWP6Wq0c1&i?!%}{O10swkIa#B|8q9*FZHyDuSx#p^2a%IL(?ZN2 zB>N)>%>q$Uq%OfPFOcE_1!L2p&! zSD?8WmiZg-dKCU)cGk=^90cYl_h+EE;7y-(Gk|d7r_*-2T3&-FYj_%PY#>bm09XR+ z$ob{`GT^w0r>U4e4(kNJnmvq@ubb+fxx&og*8nI;Kt=#!O4Yu7izJcMN%(!n$W5m! z0jBk%qsc)66_sz-i{WEw+cppX@*F06kvp;dFI@tR??HhE(3wxm$` z31{jn>l>oM)UqbL8e#EzGe6$1&r|x`3{B>n?+w1eJaf2y^YgJ=ODR%R8=bPj?+d0NdtIwEh;*X(W@*ZIZ_~BZZGsW)um_uesO$Ld=sT#WnOUTe~ z6*b*yo@W_6LSYiQBE?8y*i2-xyh*{oea_AHqSy)M1 zNisRjqLg4HCTI;4;}0dYX5|##c3gl&W{Mmc8TpI>tO$so0W0l;^sbvM&_Xl(I>X)q}>4uK(E}sbX1bA064()`+OwBr{Yy!AE zACf3y%*TFrfVRPYxS;Vp-Nr7(3dT1XkAt4jF#OnnAHSBJ+8X(fG|m2(?LOLyMRa>2 zj)3W&C>g@lfGCOvKWEXc^qU8tb0;@^q@pa#$EK+`CDEO!Y{%_m+)6^BgSxtYd=9#! z2<^t>YVdauJ37$!$xpmHd?aK_LKITod>qR(0b#3N{xe{9$=gANK-3f#Oy9J!3hH?A zNH-=?G!GON*sBeF0*yVV^Kd{%MlZ<7+9bd-Is8sl9*~rB4UVm7h+6SQU$|rh-%Jva z9LalDkUV&v&*+#nWE<|{bD3qT4yDjB@9Vn(XpW#k7GRO3C2{YuS5UL-huqssNjCg| znCIBu`hZTR3aNig;=AAA1{uZml01ak-(hBU3U9oA!T!efdHdyuozbk!vRGBrJ*y?c zID&G*JHeLQZcD}0eYdXmkP}35G+*s*HuYdMP<`m(8k!8-wEyN?FW?JLU}0rormjNH zr}AykoK(x`kR0DU3bUU<@yWhiB&^>PR2169B@AA;JSwkTVZ9VVf9MV^>IgM>8L~Oe z^EE3r|2obj`5fw702VBJ^ACC9{|<3HE7NIw(8$r$+TE{pIM9-cu zfQv^nl2UXY&0wRlX`>)U*M|g+OXk8iSs6vud8J&aK3^CMSR%b;V6FE&@V)50(hqU; zvKJ`>pUD=-epp>dmk{fyea;{Mc!5o6YjxyD)V;l`HluHGUEb?euQw7UjIsNpv$-kt z%ep9|rzrgaCgB%dR}kyO`Rs>Q$#v}`B%9fo=hx1JpS#S>*L(!+jm05Q(@mS|8#2e+ z@YyUG{IWj{73BKA*<>;K|5(o8BxDCl*Y{`)C2hAzv4M4(tUdT!GNACfoXVw{9r5XP zPsnDKaZu6uu{>u_gxukz4&MZVu=a4nlnB^M2YtXef{K@d721z%5M2=e%Rd3(3`mB} zi^+o!^FX-4K73^ILGOxrk0`o*o1rGeGqTML7}*?(!7#;1BBa%S7$?5=AS80_#t6=ZXGk!f-3O7THccv+NX~ z>z2&E*W-iQ`wQxBBn%C7VI^0twwEONOESoWv#1W07Nn+q4m*SKwm&EMoG{M0XnU2M zAmYJ=K3UF}AuMWKDkP3PX+PvpPP+0f;TNoJ71s4f7smIuFeW{S9`)mPG>?@PO>!dN7_lqL z9Uu;^(}LgE*g0K=6bk@f0kJ^)PC*pytR!1prL&{Y9pL6je^v%?^$ZLQ-^;k_u%J&9 zFuJDGy?k`<;*e-sv%pHvVF$ClA-&)HmmnL`ZMk|fu*EDq@M>ERv2Rd(9XZ9rqsOz=o!9u_vSEPkcngy+ z^WlOP^3mK|&@TIr7?J3|c{5iExI3L^%d+BMYNc^f`g|`(z3c&9a ztOWD%gV~|)+D^+BES{kQ6ZtN&c3q}2YZeDdXu$5g;AaVZSp@hNP&-flO?ZE;u8lUJ zEQYfSEa5;i41rAzpfS?rlxP=zB-I?j%;>{!)XU!bFxZ6tY~+JfF)B&n*lW)IA2%`R zi%^-pgY$XUhvLni`8;#BkrnTJ82W}>D&Og1a${TY#q$G-d3;TgQI`W7D$Z;WnVwN0 zv21G`d}GeeKE^?dWbZ~xjA34_L2y5oaNTAu3t7ev(I=2LsNnf^dUc;4kJohaq@R6f zECZ@BkqSzwXhvh(yG+jvbGx)v@EWaXN}v4OCf)xZCTV!Meov_WpvNgi$lf9RAV|b< zd_O;ykNtP9eHeBfM-jy!bHY$G9xz9!Vtg&RW`|hxo}gUmAZ@_Kz(xH-PyBoQwho@` zuzVVEsE$9Q8)JlvfP?6&7F+6Y`Cg0#sGfA#cb5c|DJZrv4Q6wa?P%2llbGJ}Cw}*h z$pl3_KOZ!jJj)6J^Gm+0(4ogYq*C70N3lX!*ZqoB(G0pV4$N?0X(gD6!(C^nNw2s^ zC!_CJq^;+SnZlDHbm}{ebNUW7jsC-QO_TlVys;ZN&LG=m`3o47{YUXoO6521P{R@2i zE-d|zDvyK1VMH(UNgs2vP+lk>E)5jT)$U%+{6iz?=a{Lv^9H>_PW|o zISU9X$;6y315JJ%Apdhxfq1ZX6F(YRcV8IMO0VN_u*5uClXL5rKWu)^O|20b zOTRDeHZDfEMKdya>xlGT@GII`XZ2>LdVb zvm-mQJM{uCGVad2r-vS&fgepH(upg5b3kj{KRgQD=6^sk-+J6`;WpSBGn;3kN<0l8 zuZ4hhiLFV$TRtNwMIKw`Ig>pxS-v(NM>Chm2ak;+A}Uv_vLD=L;QYu^KfU{*Np;l&OV$-(!Fd!8M-A6-L@h-c#Cj7(Nb5Qd;8>HK1RBv z7h+)q{Zp)p|XlK8NW2K1x#&@p?pRpjF?M0{f(%iE2+KyM zqjiMcXbn}*1)&KSWuNiyj1@1!_GE!rMwkw$$-eKt(kIhqC`ix|X8#a-|6gq4fl775 z+iZN%f2vA9Ad6*ivoZ@?uYHZM?w$>sK^9|ZZHAR)H=4*$UhS;8=g^dv-45=(JdA!B7_Le0$wZm3EFHp;kz-Jz)CYo+km+8)oaCq8MIV8C47FEB^9|+sj1Dzfh?v0dKH2J zITaS_z-L!PY7${!vdK1yNY{1sHcI(d09f~~d11X~uwwKr<>qtVp_!+IMBhxAwS%0|NU!Zl=B;-kc%GTX zOGR;4i(zr*Rt`Jk{`<>sZm2#?%2<<96&crKUi51S3MP9+euG6J<@*zA2ut8XT_arp z-+3!8T~iJL#dtQ#?2PWfytK&k%#DhRe&c!bDVb~5)hX3$UIyv`VxA)E8>yy{sEE#?;le| zYv1UV8+~Gy0~hhrs1qCib@l?pGDk@5<9`*s zwOe&UcvQ~)H@)MV31*<8X0ZMkY%kq{SvY>R^&LIp@NeR!HoPBKd;jMV-^{Xf>oAWM z;%5-vlHKTzDxu@(L#K1wvG%%jqQsc=ZBYcOHnw#U>B zFACPPS#sFSJd7eja~h(>^f-Gf7W^XfuM~w5s*p5CWf`~lG=` zwAgO2tZr_M)+-^M=A<6Q>fpda;?lnST)YD6omBN8KCHupEYiqJ-S z_k2ngT;xb3EkC#lGAPID=CGQ)ZB$eznKA^E5X^4gQc%I+OFRo%VEH~N!%*aQp1y%V zNwK3YBzv@mM|eQhQ(~v|rW>7t^@j8>i@^e+Gz!L|;;A=o6PLgKg+KTP|Gw;b3JM1v zr}J07P0EYx&|kRnjdw51%oFa{8^1m~QsZGU#5P+zeJ|FiZgh?U{b7&s=pfIkz0qFuOV3bZQG!2SFYRVe4gT<@mx&{Y zjg9Fh{DEKh#Xo)u{+yEAIl(}o`2>~e(9P+lApC$&+|^%yuJfb#&N3^rc|hW$3V)*| zb_5Tqw?;M<`UGPrs4&m{%c75Kt%jL5J38R?YjY)A_Ts~MO5+!A>Lf~ns>=^IAMzpR zlQhDga459UTJUwY-7ew2z0yOun%a9Q56M+8mgF|!5yL_KcDXn@RF;oNbJu$rd(`P8 zwR`Bd>n-&$%IcDOgt=l+sG?#H8JV$IJ=TbuD1-b*;HS!cqjt-ZGQ>j71ocs7W##r< zlvfGbzu%QO7Ir)xNp%Ifvln2*i>BVhyjO-D${WKd4IYC5_}n_z=owWb1mQiqwGeJ} zvMjYG^?dv+qGAKPweN=O_L(@CGza61&Ygp7yJkdftJM>CCKyOx4yD#=tD>xfsc@%r z6HF$^E@ix$6An0DQyH=RY@1ft*a~XiNiB3~@E%V4EeFDdYopT`8qZpP{IxS1^WwTs z9~tgQ=xN&Jn}+6&<*v1OUq2T)1n7T~S6Q>#9?{WEWshVWEYzb`M@%6pLkTxGJ}X&< ze%7RQTp5rsn_yUom13JpzH#=-pE8@$du9~p-O3~FVshutza${2+^ff*U{-#$4x?Q0 zBZ%WuX>a~6?UySz_R2L;hhlGg7~dAMZ>?!=8S)p@u+F?*Misg&cV0%<%v5Y&GI5Dj zD?|;MOUEv3U%Mvy!PwnVi`|pPOKnOuKAkl?Z?(zQodAqa)K+cJ_yd>o!-w zAX@Zz{MCw3n_F*(Pa)?Ej8c)U7OA(bh<--2Ci?AD#K+xKd-8do_)z_iTl62dTrzOh zpK^3KctW{-5yx{OvGwi9Z6V)DJQ-SSk{Vi#ucpOTubA7E<();Liv1xHy0Af|Y(Cw( zpZ*LMK}sH!A5#=;OpB|O)(+~0Uv{}}x!oBL^D&=)SYDO&UT2GD_o7I{g@0(<-N?%t zXZ|LXq3sLMjSDNsDQ}eyhnb~)_ho8>IDY+rbKTs>{>Ac{e7IHuQ>V;9QIax@>*~*5 zF1smAq?;>uZOJrZ)86{t453voM@L5ohaL@A!Pu9PT5aj%4l5)ZX7_kRKs8gKCsCU( zeh$@#{lF#HpoGaMUiGc;ovOv&DS6uDS{bT_oHgKcFWPN<@yRC1HX$>i$1;@rP8a`2 z`Rx9WuG2{}?^ov&ovzPGqrGUVQFobKdpX|xBF4dUSt}p~#@3_= z&R|g6c<^0)XHSZEKuS(=7H5|cQ3H*evnvfVj||#pK6{g98k1fc>cg)5Xi5Hy#L|P( zqYR*3l{%CDOMC(n?(ldHA*DUZ&InbHB=g9qRToX~s}@L@rm}X{`T*fevZT5fX_sHK zb5K^7xv3+L?;=wD5uRdEgp)UKO#OAL1%liv=l=SZ;2Dz4eYF;mDK}?SjbFZd4zYV{R z(L#>!5uH8BATyb!X2uq$P6`^e|1~HIZEVH8HzThPMY$(=altZZHl371si`z1>&m}G z_lK>u_*;71S+6@R`Dq0Db^Nl1++nJ))!RynN=v+*DYurCU@3`tLfIcFQQJYU37k5U ze+DaY2#2O69&SU|hj;X$yF82QLmT{77iwu9H2ig24Rj6SF8%FTzozii@5>^NY7n{6 z{VN^!`5`YD`er`m3*ve~JK zZ^JiVk%b9Fxs?-7u*YA1bW*gA`-Un^B=g4=XI-cj`NtJglG$%08yW$5v2U7xofU!e zME4vl<>AN4-iBLhj`GXU@)sB>c$XeDqO%-~Y;4 zkLN0T)bZnr(;fdUtKDJTmP`R+gY2Y}P5p`&^dFZfhMFc5hmMsZ``d}UBukDz34%j$ z2T+fZ?O%T|b-0-GN&6jTh0K#0yqzob*fV`raSQUyLSB7A-WZ;7j^H6IN+UjYt3K?N z)vvY+4RlP)XsK`Y!|Kl+bMN$4x{T=RHo04vlToy|dV^20ACG;lJK>;Rc!jT2%&VRE z?q|T1>=FL6{w&-0p&DZZo*$R|<6J|Ud<*5EUaoLiD90VW)p9O>yVWss{t~CWD5E!s zSZv`Yt8pH^MnXFGp`Uqi8Y?5)$N;O9K(=tUknYS06LY-0GYU3m@VKTZtMwhxbX2! zGaH-%_Ye#VlcV(1hrM3V5ML_yB(7tUHZksd?!6rscnZ1CJ6h(NP0UQR=N}ZjSU3Q_(W=(NGOOHy;wFIQ zTscZTVQj*=zj#F@Xi*-U6CA%=@Evl~Rp?A)JvG4{^^f|aSbc2!2OQV>!%k2e;SE0X zG0fIxnZinauVsa_cbDKpg(nL#*$CV)ZbUhS1#lQ=F8nEW=LzS3K)MFHBsb{EsY3YY zJfy{YRm1OI@nH1}qS)fAe_~yeIrBkIak4KJfY?Q>YY4TvLt*OlBeZwjkV$@r5KJg+ z_X$iYB3B+*QcNbCPBN${<=IXCkAtMvRj}} z^<~naGe~?WZU>1m+|zuee4mKnPw6+fH@?mO^E>dy&bjv_7I@qdgwG!)z}pR0B7adc zbPV1u(zd0JOX-h=-qvC6O3a`6q;Qjxpw|J6q;{` z?l%{Iq8q){d$)@p^e0_v(*2Ct4$K@T4T7)y6#40y{B?g6tuMgf&rguT*(c-3`ufZMmHm^6MTJupA=Uode4*J-q$Szo{ z9#2Mz+;)S78_aydGxV)&Htn4&j!KC>hi$kS_yF{n2H(wwB(L=Shhu>J3wtmL92Lso zkGG-dV)Snig__!Bkn)bun9R+ix6lW+_?VqR=0`o6lk=`&=hx1$J~}g{w>g>nA|o{K zeS9|YTUHKiRnBAZW%S3gv+I`w-vZr)4zVmrq?WGx!afbfcWI=Tm5i?oTEcD}Ej=vO z<|8&Uk*Td}`=ePw)mAghyKEwJPm@4WSMSPJrwh+$SJA$U(--~On$h0%MN1DI{R35p zw+;?-BBk*Tcijx1Pj+;ONzW59*U#%@E5Wvl-*?DzP!XQYoFvAI3QRTqL(m^v|0(Dd zz7oVHh}NLWf=$0(fPLP$>YP-iEu(CP+`5AjS1h#7XDS!dm7%~bRyD=rSwOJy!L=Za zt4qm3+xFR&!B%blY}I^AmrNUpLCN0TJV+)da&BG-jvOp~Cri9Fd3S#!A1x|yesb{3 z@K);wTc46yl*c++3|<$PZhz2blov(ahmmiW(0%&!sfr8L8JQ|0$2Q83J2P?Ht;5Kb zdFKjGBQ5Rhos3Jy)>f5i>cY}}0h@$=)tlMtBpBNQ-z}ENe)wXBI?^^K(01d(Q?02RVBLlU3(mYowq%i&eNi zQNc3sdGnpaZogiE$#ZKJL%8wx=$cixQ)zN>4iav&XvDgv+up`l~f0!8~a* zn3fqqNV`yX(CBU9(kJ$dlN%{}ibtc2YqnOUY5BIwv#xplv0D*jy96(Dga7WZ?skY_ zMG)J`m}5KOu*LoX0|{y;q4;D_K2&%-f4>M^6#)*ab2BLO8Irf-WAzeQFLY5Yt(ke z*AJzylZlMj>h~X!z2vz$#XVd}yW)W_U*Ex4dsgP2Y}R`O)l^H==01^r`cdbO9EWEC z4--K{+v~qSb8hfIg*x=y60iIy1}gQ@7(u^LyY02E~a&99=6Gx9o^B<(VY1=Q2FjFw}fq%DPj?HK|L8HMv-Dyq|g|Cd3s z5-7o+bVRX3mwZr1ObDxAEpS6yC#1zyPJG`z!!`Z!iE(Ho;{Ad;8-!zD9yezGrs2%g z_-nFX-S1ENhWsatcEAI98Yyny?CDn-5FNA^j;f8esw$S$m<}DZ;;nQ#xPJV(1%dRd zcWZ5q?Q>EJ9cro3c$B*q+ccRwMm?ChjuUpTh;nZO(TK~YvfIoLpq!nGbTnq~!iv^O z*O#9AeyZzBS%0^_WQoZX?j!}br*=D5#EPK7NAB-#RcjNJvoQa9CIEbwW zmAFE&QWU?Q#>OpeEnQu04o9Z;tw#$121XoGI9Y%1+wjy{Rt#I!C%00)GX${O?VPPg zy<$|K!@RRV0nb~Wo%zjJZ$U`x&fWPE=g-%W^!~GA$lFoToj=XlbCy>haBdBHiD!oVk8w z-S$)?`|9@;d`=CKLB!x?sgJrGn2?u*4es~;@st}Askd>L{$+f?oKk!^A1)VlvhE2Y z44U5_GgAdX8Wn2(mcED?T>{@(c$uJK@E^id#DJU!zTXMI=hW7f@)vX_AZQ4R_`~{yieC42 zhb6_zey%*prgY8dGkgm_ma&cWXH`YS2)&ctaGg|M-)-!hZ#P#ub8l->8TR_MH$;8b zHZL0X`ZBO3x)NZY6B%zb4VS^RdswecRLqWY`&~FrN-Yu&8HzD7R~AwHc%O>Mo2KMxpDv09$f(z zH`#VDTf1}}ZU`Sz7g8N?j8~fv(221E5Sd$Mg^+gW=uAzoKRU$HSo7t$d9HIs2c?E) zX-n}>M-52Rga<>8{onRavJlXVHi`**%j8Q(0 z%Rx(j`R%EON&pSb_~mbe_FtCh&v(r4hJ(!K-7*?Ug~)LCTj=4peRqQ{LARh?QaHJc z*+O&oG)b~cja?m3f&A*)raIA&T*B(oL49y}f!JoT5qVuV1SQ=j5lnhP+(No}E#0#M6> zyMHGv|9q@J-#D|y%_Yt8>&A09thR@y^gmZ#+9Z72#M~iuaIIy@OxKN*CQ*KREO!NV zxV}Gc?O{82jcS8Tu=A3Ea;6iP3}V2|NT%_E79`^aC0#V(Ip(=!oprZeS#=BT92y`vY4Aqes`lD_7)VlX z$h(9cQ>7SfGe3I}GRl4)pYQZ5NE}q1SVIlg^+~P0+dK7~zuj881vwBijA)!EFyQ}x zq)PRS1})^db%i}X`cS_(HLKFy*ktP&Zi%^z8TSyk82K>;$|fT9R9i+TG~ZmwgfGx@ zf_!3)`y|m6JEi#3@mxWsIcAf-zj|BVpMZ!)bN-{k;KN?A!J?tk6RjQ+)YrvgM$9g_ehDzUdMt5~K8MHm9Nnj+JEHI(PJ`45mv0 zIx=vMz?b0fcIi(!|M{kY>ba}lTvgef#!Pu)$+_b9U7a6((BIvym}~W%FGs{k_;bn} z=m|?i_oQ_6z`I7X4eZT}KB&KoPE9X8c53uE;L>bjGR&YchPAPH*^& zuGUwMJC4AB{pj+(#BH$m;tT;Z0d9!s&nNsJZ)SuH)d`*+u+2&b|4qQ z!!zgOen3HJ6oaJ-Ym_HBd~#X(%ht!x$JWmY--6Xq8%9GKAEY92OA9l+IuLcfDU ztzTbWM*BHn%gZFj2XWTM7t#pVBC%z_|0@+Ti{eQCFbbU5hw@`E~(mVrp z`O(3>0;tAlin0S&Y$~PQfd}_+Z^q9TSlu7|;#a0%LK<%sq3Or$P(|F5y173Eqx1w0 z>J!6?W{u6AIH4-5L3p1D@E=cdb9LQn1Q}b1G5ug*x61wd?s@J8%qt_u@hK|s+tpvD z0t{S13QJ;A0)n2eGnOwlF4q=3(nK8fm`;IV8TM2s!tT=;b0r5`Dy}=3U&IHqZcKIU zd!EKUTE#n^Res^G$vO=(CFj5w`a#l(^@*Y0=ZdG0F=j*n8dSmVr=La=G&Y%j|m8p{tg}g$F<(D?Nx5%F zbnwgF^DyH%wu!r;C>p9W#t&M#Fdd2qMLL4gJEJHV zFd)5ybVHREdYN$qrD|vrN>m^S2uSY)MTm6iy+|lhLV!R*O}-uH&K>9eoZtQa{+=(- zbIg%&$lhzO^{#ild!K#$?Y^Q^s;A(MqGR>}^ZLKvu;dKMp=aCdGE8sI4NkqptYe1! zZS~0v=F&5DE7Zb(Fe*+vS!`susZ$3rJ4D+^QhQ!X$!iX2>_4^I7)Zz|I7^a27|W&VwLY3i22{ktb; zYU6ZS4ioJZXTc2ifPdg#Wn^f@^-kICDgD0BUnC_caOV?)8YYN=%2lY8(8DkW>u-7JTeZY1&m$~Na z-_g!5bL?Hnf_4b*nd3}c91VY6ojq@;|KR%mo5Jf#pRRH({!yO;B>oZ?tyK!Z3E^hi zX#Ki9&ie=?HQMJ7*85#6(tkL0@CX-}m`zPxe+shuNMCCUAZna2PWtQz3ZAjxoGaX= zclJ>&#U!)ZQnq0D!nIX5Syxs_EVJeB^)?xD-tUNC%W9w?aDNuy0k5S2bGJRmu!cGk z;H|Fl()0k*3{l(72;zvUIklBW@z@FHpJjpF zE}dO;2ud){ksFXxQ0klUef3IsCRO+2Zys&HW+~0sBpm8aOAi=IXNg$Pj*;X!_X4?r zyet?YXFq9ewWQPYoUh*|slGh-3Z1Y35U1cMoA>a)aylz~0`-)glIax?GO(R zI}i)$Za2~g<`=+&K68%x=AP3HoEu8Eco8p&ai58Hr)tX# z=xi+S=$7~65K+JR{x<&+VJYv7>X$VSYvj&ze0jI^tJ3h^P5Fl$(XGz_PxJdI8c+=h zjXm|h^KTFl9H2q1f&lNZUxWmp$cVeIlQ!cOTl8=y;ka;MJ9Poj^i#jB?=5eYwj{Ed zf073f(yh>0la=Pg?0~{mEgA{Y72)E(M_87%)qa`5-;)eQH%g6N7d2@yd1`jb*L?}X9`yl>N^&Co)gn<9Bz;KW0Ah`3oC=@l?9a46 zw<}d+(d{;$Du(thEc}z%jbiD_$x1BI3Djo5m~?@Mfsp-S`}UC$F&$NEwv`=f(Dfg^${jq=(G&bmxs{|JGS^U z<80#~IRZ6m?9BgVi-7ke8P3&6e6e@a6%+7G&bzl;kI0e{*(5BS>~zr?*8F3j7EFOK)r zeOBa%VzRi|fU5ycf9Wi}!^Fe?HDrDQ6~jYAP7i30eVKp;=EVy^J(R>5#bl*!ezqL1 ztUDN~az~rIW=W(eo8RD7(PuBIuVEwsOB@L@zlZNzokAAo*YDI|Q;7YOACxN^GI8UE`3(fx>w{ z6)2p_!DO55YzvZoK{i1*SvuMI+@T~dMVl$!gqMAl=bZo!0L}&asyO8PLaRclA2?V_ zKSnC|1n6ie<=Y9Mzku?av(*DFC1w)=vlk5~cO0#`iM6?JdfuLImCZI*?ESpvsl44zJAUh3RBiXQtGpRLfW9)qPF}xcJqn+?Ml>HaQ-EOqp~4?>Zp_ z68K9kY5iqnsD_UCmrGN2{QX_KC@EdV6vf`|wP!Kw-2DXx`6kg9BnP}6f;CI_2x!;z zxM!z#VZU`tP=UMB09}4&M9}5uiTheL8FcyC%fWa4YgpU=S9j)mt1z=TtJoyi+FmL? z(Vdyhk9n;yBj*_7WyH1kTDGTzoZOx~)1N<{|Aq2hz(-?@d z{L%eUAS*4rYd*BU9F6YZ@7NVo$q`#(hCn8y|9b=pZ@rj$csZxo@!WyJVtQDOQ~eBlbCDL>DBy%{8V&$SJ|dhmG_*1 z#kjv@Mb|{9dIb_H-=bdOG1hx9^!p+~Dz8f~#%1Jki>*Y<-SARa3b2=#L`P>J9}`-s zy$0{&iLFEXB|D`1&3V^HgI(JWjkyrsla&o}ot& z-oGHtW^3s&?^E>6Xki+bq)-dUvbb#igZOXLfcr$A&7Od6sx4 z$6%m`8xF`A|C5oIP$IqE5-_-qdP_o`(6H%pmH-Ts0iT!%mM1hy1w_^<5YQMYNl9?hjAyA&d;jZ_=jNS^)vwc4u~IH+{gq0p8$DYNaZ z$!5H@44_;%hBM(>Xn*d!sX!WppbJg@}@4+jIRAfHaw(rptvY|*wx^Qh^u>w$^6 zHYa<!ZIsNV)=9?6GS-c46)a8gVyl~K#cwC#%#W9#aP=M`v)tK&0fj4aLS zShSUNQ}h?2hdS_wWpYgptmAH2rXK=nBkri0>|OFEdazi^q75L6-$J`aRnQ#56W*-ayZa(`x1l9m zT#B}3m_DV2`L>5=^5X3d*TPXzqwcB%{>b2G<#2JfEBKKNM0{P7#fsZxS0mLbOfFM` z2TpEWXCS_`x$hi1Vs|*uvo<+@!JwePvO^<9bhba=kTkMAC`P~}$0RZ|JQ3S~Vw3um z+L(GWwohHL^IJq-&Vmki{pKkKCe;6D^B}3JJkVYqSc&Dqd}HPYCRsU?)?z!k4S~q< z_@1dU~GV^LLFkE-4p^o{ik{NXK^yJ(66s7EHt<1|a)yFZ+UT3y@c8eL<*N#!a zk1Um|rjrm-5MQiNTx$+DELO7Usv52`OEqt&qji0-;=jU-xXT%OCJUXttO%P6Xt{d1 z<8+`Vfk=@wUg^pjFZ|6@=O0?E4(o~0O%aiVA(0s$B?onM+Mc#kbjY09?G>^2&c&#I zjmcr##FrJMxAnMmt|w+JdNLATjvKggggt!wWt-8s@zADH-TOA@gR!*08%B zLA}7u>?_a~`Ek=5`F`=yn;1j%z5;|#o0Y7C;KBfR@izLQI@Y-eIZ~RF0d@5JeQEXC zKQ#0LLoyK=j}$Y3!c_$XppLDlA2r0G7=uu0yKn?2d&@EQXe1I~kh6k@E(%0X+;$uY zn-NUMPOJZf|AxUt@E!s&Uo*T!0jcOEV~z?erm{*A@JRV@o7(d-`u0egwx&?ApS=*ORi0POm0aw zv#3i20I=RVAmq2dw`9ywXfK7blR`ZSImFj<*Qq{;2%QL;cOAj`^z>~%vrv9Hu6tQ(tjRg6&Ac0e zwEehRPwL<4p17A4?{JNXq^IDK`&S(J96a4OtqTgwJ32a2=!ikj(k{LA!~lpUYTNo_ z$R;HiY{;r%d55xcOI5> z;M2CIx}(m?ibEE0@jaRF6vmp-D$0N~X$ia5q_8J04d%4aQatpO1aOM({>yWVbNvd* z$}NCS;XkW#c5=;q-m~IdR{Xf~7O)$WL}Gqyu2XdsO1qgLlVKmy<`|~q@u1^(m8!7o#++HacCVqM z_UB>ZQ4UZc@gU?j;X8l>5C^Edyltm^<)MhMcns`hbxXMMK`kT(HYdL@SrbPn47%n+ zq}p;4%sO@=YG>g+5-@;}fS$qNJxoCbt`;5EMu46S7!0hFGb%hCb~VACrpcmntgTNa zpo+gs>l;>sbZ9>=T+%I^WFR`*JQqEt6d+G$O-*HyRaa}C_OCgrtE(GxLioBnYrEu` z(rwqq3$tq}`F&})miwuhP?)hrD*hCEAY~nMoUPo5ND8EIZ`)g_TK#^@y879%t3R1`b?o zr5O;K_rlODQ**hlsH?*;f7z&5YfQ|S1JihO4%M4rTU{7+%OV6-n56s@$3^v zWEbDTT0RYK#6cG~?l?+A)dOxvKKQCH{MD5|&or~>04KD>Y9Q4!n3)%@&lY5r;P4qd z*D|hn2)Yu?ZMnB;*~NygNdP`4m=zy2q74QK3W7%<%T^9$Z&Uni_XhutZJo+?1HIlx9zO=Xh+nt6DV>@5J2S;*5&R0;Q4 zX)zF)2kUjD&Yt=!*?+DDsM%J-ZU`;ZZ>y@xQ+g#_(#@}YK1!as%<3o>WuH@00+ptI zWO10f{|~Ti!sA{1OinQlW%s(qmZs@(-|ExDQ@#Q&t)H@ot5R0-C-3a8#5$Z`6dMt~ z;V&qe)l$jf0D9zEo}5j}uB!Hv91R!+qhx1O{Vbdm?pNv?A0EI|BE6ioLfgJRVd(-- z>Rz*F<-}I{Uo#vmoLd~}H#5hgk~-_-BlB2F>WkAc5(lRma;`B-`t6NJ)l=Kx69M8K z6Ru(x6elB@df!2vI_^3x-cOVpRd=b*Fp5^W{9S_mU{Rqkkg2z$uRlM&9Hx`5?5!u1 z$UFX8qmI_G*NCQV?`^iIQb)jEFdl^Ifo|dUXM$OvrYey$hV@DqZ$vs1U9!1$B;du@ z#y^h6PIRW>e2V2KI|7xoP{NarvrHi+-ms(u1P_R!URRVxUXq6mUey&{muBkVHrq3j zWoCknFIyWCJ1Am*JoP8q(&T>A9v5wX5*je?(+eggM(ac&79Jl>Jz!$CRg+qS;&06F zprpcsXPHhWe79g}5HQG2VKwOD!^2zO-VQ@agtH&K0v&gYO2lMB;}n9P7X~dv`n^3r zzsWXFD%|hWnjvqth1ZCv6$rqZ$G3ti{uW3GdLT`Z>l9eiGZRr4RUG$!nIH$$5=MIH zBzwg73L8Eeuql$N#jrn5VOq!)2aE%Vz_vwSZ`K2%m&zMj5VY>Nz2>BPByE?t9~ewX zqPbTSe2}j3@pJp43d^x2CP`}2nrUe*ZxKpm&z>tS?1lXqJ>R}-rp?=RTNOXEBHSo0 zPFAQ((wWc6Qtazr+)cV8z?0?D;}RlGp=~R7hU`rC2|KoQ?KLTfyk7Fy0KB>^1H={5 zc1%QN3S?Hcxac=tLc__#nF)M=UrB9pc{yv?#j+fMvdbM5<&Z%y<3HHefY*}o;l0`X zBvNuDnqE&}-~bzR@k^8b@*xE59-2gU+q16rsZT6l(n;YJwP1e9NyZsNb(~s1@d>4{ z+RyhCTHHp7gj=%BU;U>bk}Tt}Ga7Dx>wcwi0#RI%(!*(e7_1=`O5s#UP}W(RJc1EQh64pNi_QJ?B7*LZ>pQc~Z=5r) z5XAUJ?;THlz?8l`>qdR=Ha}{)>#-6%d%TMD$WlFordh2Mhk>Htgw;4-3 zb21XREuJ-gUn_Zlk~CjzRo%%?>KUUMv`%C+GCd29t%P6U$r6C~WCyL<1IGxyhTX|> zvv((H&8^?(i{vZJHcp=1bTTzYYn}|a6mwgb&hicT@_^g`>R<8%V&|n6K>EPSWcgU) zOebC*WNHj?w@*hr{$kkxsMGWMmf|t;lHKb8EF-Rx_gDHiD#V+0WL6Q}@ z0q$TK?Bs(bF9rX)|61RTfX=Px>& zFPd3LiQem=eU9E+j^=7v?BHslZHb47D6cKfW^nwj(i_i9FN=+v8#DxxDI~zI7Ve|^ zTO0wk1-y__PPEHjvHkcI+`xq5h4B(DJK@XTXbpVjP;M4oLZ*c?WycHY zMoC#q?)xNB*NK((CIh~cpRyn=k`=T!-nWe?<}#xCO2Av677xM7CtCvC0xvd>y4mgZ zPqxr>>XWe{o9c_ci6bzbQSF|Y+*E_KH(2U9F2SSMT9gyN#wd=ftsC8j4ET6CP$C$ohS ziMRz9);xXDy&?)7A3WjV;2whvD;5}V#PQpm6vVb z{|6plHIkocSrczXG6|#9CnM%R2jAa)%-xn{%XFn+HQ3c=iK(G zEV>T!Iu53+yiU6pR}r+`ScJmK>#RB{w|Y8tM{g}|!53Q_`x0=h2GzF3sF6+RAYX?%>wbml$D0@3L$5aM07@AnDnb z09JwvUl6+7Nf*UiW*i*TUyVHx%)WEc+YV_(^52OT%84tBg-SiMXjFF>MdX zh{bWY%z8?P1Q%{mGG|vP0okXc)04@XU^iXGm?Q6_>$BqEOJswi?0%8V66PEHRcTvY zXB1T`S(cw8B-!YQwkp#yXA^tFm?NaJn2FJJY^~KQsk=?uf}#jgb~R8^DRkIXCtX6I zOd(+OVCq>OXc$UPSkzv7@e+(#!29+HFFYkao}!O+YQMbKS%zXm2QOxc=3x01V(mz)@>)wWk{pblyWXQD3{My45+WgslWb*H zxPF*oGGL;P5QCBsv_|68^f|RU>bo*UpxrPAg>_%v-^pqhtxuOTHb40#;#l_gXFVGD zZerbeB1@!u^FiG*)nWTZx7rR-6MSczK;eOE#KqhDk&51QY8$JL$BppWRbX-?8!xdk zOWM5_D6_u}8y146$9u)1N|{>4sOBY6Ar-p}4L^G8kaLk2;YdcwGE3X%<{zz>RGH_& zUWqO4u{fr0?;!gNmZtOqE*g&@a#9S%!9v0vLJgcHR#zu3z7LfdANX_c3FTB&rdBb( zKn~agIzE#TYHZ7TU{XXN0J>1Z7#h%aU~fttn$MHf*Vnh9(&IMX`hePR2dQOW-X(AJ zet(u}N^j@hUI}kj%Uge?{j4tgHF8p1I7wpPLLE-F)R`P)qcl8h)Wh;qpz!t2OnND6&;fSJU!D8r zEbuH*RD`LdB-wKB&fL6ZXJBo5uu>)_^K7^4$?N+K*Mwtx`0R>mJ607f7#g^8<1?2- z?vsN$6f%T6C)%f{off1E>Q>dc3bJqcjD1h(fvl=|-`y#>W6QtgIId8t$cR?%L5}P_A!R1?YVqaow%I(BAP5tvUR5w2pf!~<7 z?0E3Gzpw0gP7us7Xfki{I0IyLZ8v@QL4MBuQ$T$_j}bPKLL|HqQf*%<%y&z_U+8Y# z%z-X|?39h&;5Ig+c5jqro>Wmk$8;n#E;kb+ptAF_%bKJ*H>iXTCaEvpuXYagT>Sp@ zRjU8&Bm9(W9JRfpy^!X+bG#74)gi{Xzk6e9Gk_h^&@DUU79QveZZ!H>tF_a?W^A@? z#+(##d4adhZ~(jD`EX4%;X}Q0>$7rUdw@lBXHAx%6sPXUx zu1Q$0qyP*m&~lf$>Is2_&)-|Rvdc1i8y4n=mP^LCns-f;(VcHMd#HIz@r?6lpFQ}V z^tg36uY-SoWVXFUM4>KZHHJIK=jK&irGLoBTD2&v+Qg=&!8p0gmefZxD}%bs@&e{b zXCG-pwkrFBpIvm>=`R@$*v>AgTsyPi;D9XVf`l|H1(|%Go(4`Y<8HJaKhlk9yDFaq zh5@5cRlyiFv9CT7oQ_2HND!Bz2UzMq9c2jR(#$8)cADx+86_L9+TO3;0Q|~lA6HyS zwpoxaSb&q~$=O;gqTHWYSccDSNX2Z=g+ zQ3tZcog)bqAdYIZ-HnsWv}9Zu?6h}ZC|jBJg0?l6O; z5bE-p_2jl3%EX(Q#Us|C>XH8W!}( zho;IzVi|*W)`TO6n-~X`lBmsEnaVVEF%&1|HT&uB=Q^!4l$=Qmh}y6&XFCbSl%C6x z(jh`HbD&*Gz>^9!Jf0q6fCOL7x|}s2tUIL=7JNHjWvA@8@z|bjGM4Nh-d>JG#4FT{ zh3%97iLC0*{(QBXG4ABJ1W5zk@hKli zy%t);yE^&v^is0rc9F11h?KWKFPwa)yX;Fy$c=v(WmF%F#{>^_LCo0753 z0bakWirRI{;wbNB3~~&M*FmoDAI}mEdtY|vz*gp#6{SLsF(*fW$Jonh!LZ9gW>;s2 z4XqWju*t|~n2xThe_$H?>72}!@3S|h{>1)nIe;+h4&u&cngJ^bURauz7_F0-sZfU& z6BfJR0|nX7!LMg0sPh;E&D=$9GKphkWmaKU0S5crL)eg3LN|3NKeIxJc$a#tF5+1e zWB;M*&V~wvtl|m$jmyp+3!8mw!i~eA*4cL)0osw@j_aazIuccIW%t_Zobmfo&b>0{ z2xaBgKKpF3X?ou#e_mKPALtn>yV#r(OI$en7>;0g`dm3-JDxcpvnV#oO{eAxdxHy@hFAZ;KPDdu*XR+s;ki?wVE@aN&3iRGp;ogGHPbHqpf5=&wl+`3_8d5a_CSjqEcai~2vC zA72>(_hfwu?=$I@h5;3^ac8zKf7IB__e!K^1%M584pROVAnJ?CX~BE=9^IrUWn9gOSQo2$b(2kH=>-fx^3&TqCfr z(0I4E_Q8OTBg*4Jvz=L4edW&(_KKb9^3t&%onT_|`-LaT1;}_Q6=|q>vb~XU*IR!n zZ@fp?W*)0lfjvMatMUZ7bVA4=iGv)lQWp5?@4?Z)*K(=FFgD=mzcQI7dfsjYnVI-d z25zi0=#`ThW+BL>f_2!!o@QCto#z? zGKbyL222t)PTGBXn|!^PuygHZ9^GOQiNMzV3$2mx=B`c8?o zZiPkbTYr(p`#W`7sYo3(U&AI=S@9nNYV+ic?BUp7iIcMTe^m~6l__PulMp?#mnV=i z80Vzb3pC2l3w07&MBdm*SdfRP9Z|b=500wKhVRtH2dDQ?a&o}zOTi!ChrH8Vlc~-qQsCB z|LpcTrM0JcgDfF?Q$58-3 z;+$s)wefn}AqjKr1+mrVij+&oAcS%<;9|xaX|5Q}0r4mUUA4H(ZIz$8M8Ot;_t3C( zOTUNzP#8njYxQ;-!=M_A_ff$TFoO!EJuhXg1&R)HK-;eO?Zws4g9jSi1$oLOpyKKT z)f~cQxEgf(Go^``7fj3Ew*5P?3)Q`M+jEQ?k}B88!~xV>`fKX8gt?0{$Q*v^T#HMt!$G zNODWx?{SYk_&{)v94F-GNojYF{d23ZhHN9xKf~^ic0-h(W7qPP(P>s*V>XafUln!g zjx>#c=lqjuhib|G9ZO_*>bGVbspHaA^%W6&oZ_*DCuQTYBqG?HY?e4l1K;-NURn*= zX8%dql`GL$n!m+*0kvY?rnjO;ve7;E@PkW?WiyrvbD94*(BeBR%zDD?zPdy=>eQ{LzM-wGtxr z37+%7`fN4}$tl*2lX4!C-P~2b%lGerqJQ(0&0njr8lGG$bfLBy(samSWcskK1+Ua8 zC(@Sc!1F3?enHMCZ;e=f%n0`QYI*F&YX2U^CwQ?E_wO!1AWFP{rIS>C+LzBl+u~Rf z*KDL#0VjnY!qEG*1qB;i8c7vfjGIeu=ZDh~K zhnlcgB}xlVHe~sx)1g|CE0zD|*`Z83G|tJ^SXv3~a$!MjoM~JDP7$mWS_uShp* z>ji$2(GX5|t?dQTeViXWP_*z(Z3?Cj&-vrj&7mCg`pTdyu{)sf{l>0=?SJ8yOi{4g z{0(rtr~BpJsrn)xsmUSv0APe~UhFkLixpM%p-t?y5ff{$cu|FYKKFM9CtuNM6M zlc}eF&j5dY+HmpvYac)pRCxa#h=2Y5*R$|D-xVLhXD5^Yo(uoFkX`KWA@^uOH6jeswUye9hwcYvq7L8zzP0kx6;4 zUKpJ^^2|a7_VeXmZuoQ84H9N43=u{@$~*WVN(u)_%Z)0CuKC^cv@}_VPA;P8U*-a5 zPp|S!{p|<;{?GsamA7CVnbD5&PS*KW>F#wDY*C;NVqJke2v|3&4^g!Y-;MO5+LQOK9hbGI% zg5Cyyd$gC}tDmJg%A&8FKJEUZUf@ECDfcC7ADE3)2J-FttFe!5P&H#K*Ryk38TC0l zCZ@EV)IrJen=Uq<G!Lwb}opF`#m`AU+!E=_=r}Min z1URBz739b|vYA+G5sp)edLgfj|6B_&K+KJv_Zht9so|8!bz~f-DR(X?U`9>f__|&a z%S|G3kH59;$=;Y={0wcAylqKEa9=|7OMDmzI#Fb28RR^s%OZI~srTR5_vZ;M^`})$ zd#_2PjQ`DB?AqoR8il}<;sr%pmvctkUtBbBDSXl|Z?Wa?+V-oj_4tHQJ>g#IqQSwR zRko`ZWM1V;G*d*Qf7}oF&=B$d{HKzuxvj^nf9ZP9FBE7uUlimGD+&rxS(f>9N}fro zx%1%(QCH`+_l7QShPBUZ!mbcD9{b8>9g)3OkSh_kArkSjF4E>c@zwdBJpM3!W;Ji) z>u2ZZZ(3RGJhkU|?H1D!uw*?-4IA2-|EVrv)X92y;9*hV=sTkduwvQlEd=6qfd~98 z&--1^ua!DPeIX6*8a@;}#?6=JNE!>nBpOxZNf{7d`>iPr{I@KqfQ)5)-1{4k7Rdf~+G^jcZK ztAcI^gFlV<=lhqH_)rIJFfwW<1Y%{m1*e~%KIgu%8u7)@;FE}xe&U>(9Xz<5eSqXf z4bpP4QK)tF8QUL=sSH@?^hNYi5yo7hjT+eE-(;-3h%#1p3T5nX7M=%!fQLB$?rwnH zqblGjY}`9%X>Dk@OY~4>wn(C@;;G{U#K7)vz(d7&=$O{G@P7-$33pDn3s#MSX6Vbn3n4b z$j}U|EaWgu3#{T{iMTgb=dL*!b)7fT9&%mU6mE?iZWOX6uST%Y@(YT1I4#QL!NuIJ zmc`u6Zze}wm;Nj-{B# zDr)zBN+lSXYsS7GlX1C$mT_~`ueCR`+YoMTLu6u$umu8~<|TY9M#YLNMzxB}Zc0xH zw?&=i-lne&;bJ-wQ6fvYSm(z+dwUBA%lQeWuBbDr6xTsXrGU2e%4sd3QSay&ug_6b z_wi9o>B5j{`UJBBb@j>bXS{>6wU*f`%>4DHJ+U71xm#PXwx7_W!_mvS>_YWhxz0H7 zcv(~!z$8b%HJTG!N(QhLxlf{bq8c+~IC>VK($@fZTO%b!$d8QTAG+X*2O4`T zIr&ATdn)DJ&+HcT1TiN>BG2ITnxEJN;I45Cz2X<;8!e(X_grC^-tkMB-q}vE?ubD- z<1Svhl)%ZRtWdUVu5bY2LYXk7sNOU#{}*NVdhF$|x;NFgJsfiY!j75n8GU}=#TZ36 z|HtTZ@JNpysE*8e*gE}+_0aSQH3J;L4`yd(4_CJ_KV3wMdoCu}qbpeKbvcU+Y!Qy|1ANE}n5ua9^)%-D>v3Pj8QVyW@}q z_qN{AX)@1f#%G=*Z$1qN&PX=m8JOM}8jVDoD|r4=(_Z&rCvr0h{vojyIdvo#8YWlb*HbUGL zXU>IS^@3gHG+8J4=tq6PyREIpSNZN8ja|5L4WHjD8dfr7l=&&%aJ&mIV&Dse$~JDxEJ#CF!f! zbUu!7#`!fhZwNgpOcj?>3fXzR)xym-&E`XgddFgp7VJ8I zeGr00P zOHe(7{@G^vdBzBzPS&$EP8aaa+2tQZ=UgHf43>4mG_rL8qM>E%ZU)XY&lhumyT3(S zqs93)osxzR2_3`#eywggJxhMnPKl6L%P;*E&B8VV*CxsRl1+_y2waDjTlA!2S0zq_y_qp#;EjL;T9H?tY>F1c)EA7#k`4ekXnf?9IFxx-uy6kU*|=Lk>E!d zjx}zl`H}b!ADm)eN4=^|O;Uax2hFeyo_*iz|7O)_r{w#J<^N?+??;m;uW& z0Lz+5c>WT&*!S#Ov6g!|-u4X$84<H|)zR*$TSVpH+ks0Hl0{ZN=H(fm-gTl4 zI3D>CDn7rzCH@2d0p+Opb92o(_}vfmgCcUCi>YAjoN|zt%HHCW4nTsC1Yht)8zT0RyaIG(Hw(Hvh zpR~cUr(wOjIJVeDF05rK&)2Ix0$}Af2cCu=P&|&$Em6fai8I`k>)&jnoz!=g+q5pS zH^={8>9ST{={kX_^y?nD?+EWe)FPh6X*Pjwe{j%bW92^iutVKKleYf8axc@$efUY^ zbU~Kur2@x_5>iV^=Hzv2pK~8v5h}p|~CtpOW zXY06cLmQ__*|8DRd#PX$a{=t7if0LSChMF_p$yZ+g!`2S~{1F)K6;XJa370@)jQTzdEY@I6_JbXD9&?wPVB|#BoxKZFXS${1*VDP57jYhdm_mNE9 zoUN`iVINpDxj1HTh0|Q#)hn*!!`)D)=ssLa3u~gM?BSRXLJvCQgV#oVwAv6+Cv~+` zS(HOYXJin1w*prOHEIk0lQ%S2T}mTB%*|cp&T)kh9vf}t*woxQu%$6OkHKdYvT}9> z&JD@9J5&6ZA>j`JWVqAp#PNCaF$D6FsgOdDU+Caw6f~PRZH{AXMWjZZ$mNe>n^e3) z-Qeo2u{*Fe$)=}$-Y{KOZotC(M&RxVwGS^q?oxY|(h6KRLR`&3{s)dP?^zFBN^qok zi=@lG*k^gEOD{k~(Tco@!PG6801vD)?q!_(t7-{O>X+rMfo(Of$b+j%s83k6G1_P2 zwMHb^q=GV5IZR*&}<-ZI~!jY?C8xdnW->(?aR*` z`kg^Nm8~K{)ae8^K-yjXiO<%sEU>7agDEwuu@gRHQ@+z@Jgo=brVqy;C4r9z#ImtR zDg`-LP!&H(-eEK21R!w^5LyTMZ=Y82wS!MDMt8V)HD}hZ^<~FA0c5(EBTM&o)+MEl zMXR-sY7V$n^;ro>nm%CLmdb8sd&|fcP)ba zyX?^1!P*zVvG>U1z0(Z9KX3UJ{K$PNj4TpS#g)v#CGY2(sWYs3h&J-Jb=r4z-PrwR zSx3Zw4$=!D-GdW9a0PCD+S(6@jf$AAbyi#O0&FXGn+tu0FNOeO8M2qg`KW5GhH@ve zP3uA;fxooGM%CcMZ(5yCbekzHh(4#ym9KgwP1?AX$Ow)RD2YX>5r)+2HZe>^fp_>z*YIYlg~hN{Rrl@lVi*{ zgXNZ+TtWmu!g!WhRcNp)Js*CoZvwd+xSf z^V7Nv33gW+sepP+Q#2*3mY3dWL6PR{Lp6OnQ?acr$PwPz6-F-hX9? zo@|Uex(w1nty4pa2jo*epVcPVB1UXZ7RM8(Yy#~*Dxs*=@?N5`zcs^u4Lj|N5X zCFQ{h2`@MC@Xe?aKEo#1@d{h{V}z;rwV-01s{w262i9n=CL^DhdSqv2Gp8Mr?!=6x z>d{&9aEuCr9LOk@+dUbt-dvTh*mt~uvY92LjH(FtmSu)c0Rl#^Dd+-&o4HLq%iJyK z_0C92QEuBY8@7E+_!4!=`a%#0Xm>LLQJ( z4bs(EE`SHF?b3@JckL{D8#iSL8cWHX&PTKud5R4Y?BwIxrfPKQQn(%arK@-iiD{w~H7# zJ9@G?!i53!qWZO)+=i!7ta8!~CW86dMt>IU>SXKmbGg^TVH<*uIJHmS01Dg*JaPDr z-d&$B)ohf$CKW*B8}oc{;%pQgs6C6Uw9F+cO6yuoPFwz)Z0F$nQ!nO4N7fYUst-NZ=mciBh^f zMD`eaZLyY3dp=>swj?1{(Og>=0Jis+$J2iiXcpGJ6V*~3t_!1BvrY7vggvv3#R%Pn9QVvVrX+V5e+rJCJqc3Rps-hn_;Dy6|kb9L}wGK82r#| zxMhrS(6+e4{)yZELbTg>jg&`E&U2~P!Xl~HeiljX zRuel`i|*dSu#0<}_~>*ekG%E# zyRaySl|rWoI_n1qEu6S1B=ne7rOl@KQ~IAGQ9O$`u`Lx_ChI2=xX)*-)so zHXK|1FjpD0Mm9>id)*pnZf{2Q+2|o0)J8M8i%QXK>bq{|zVSGMF44$rKW^n0TAt{V zP8;B5Q7lFzyP z{L@YdUJ9$i^rLx2WoeGAw0q)_piyI6>F{gwPO;6%4u)cmc{e)UN_0^in!__}3bwyK zya%+KX*H&NH_}>K2R-HzHDVnp2UmA6iIuYpE?-SNVJDw~c`5s>3V2}=!olUuxG`IZ zQK{smOa4hSxP>#j&46}(Sj+HN3n2eW4+cu$eS3CVG;YMqR&&10Ukx_42?Q!q6^Hv| zaavIg<{Ca3C}K7%t>)K!W(&4<%=0pUrqr2kcFqkgepU1Qxcskuv@g4Esi)|%EPv9L zI?VQ;4)Nu@$yv+h!A=e~H`D}nd`?=T>;te{6HRe1P@&l0rzW4I1KKN^_*=*_CTp$w z#~^$V?nKOBRGxE%Bo?t!IaFPE5m4l!@d3z`ThP?+^lEcto}K(icZpc-kPe`V zH_+-A6^dh}51gX%1fyA10?PfG=e4-bVN4op$onek;H(N=*D>223aca+ zow)X(fh_I;RKC6s`>r3!)hem(>H6AR%8x zw@p$rj}nEBWuUe>4bnvN)^a&0@uGK=h*9(-c5KTmDqoPU8$=Ik<;4K_FX1RO&(b+f zBhCHjPAy$TnBt#!2jGQ#3L=17AZcP^I_i?9qCYtF6FnHHZ|^&SvB84^2;YNez(H+B z-MHgAGs}x)gG=rK@qSfI31m9=u5kPE?X8P-5z}?R9o;5tq^j=P_JbG)7%ZQ({Ftcx zRx0CQHwj~a+jTQyXIPSV?LA2~fT?))Nl4&UP|Zfg+YQQrA-4-($++qjg0c-O;~h9D zmDG$)1!Ii&EMz-}-fJvIBx{iYJ!!s@#0fP1Qmt#`MGnceN2Z1!Hc3)o0)SlbB_ac(GTL;fZpL?X23TC+qG7 z*0k3HWIRuM#DFI#2UP1Olqr;Y_^{JDaMSU`&RG4?xGsG_hUi7p5Bg_$mDobDAo)y( zOekDj_t1ILF;-ilG_etK9KYqJGyp%=KugXtJ^8_qXvQHTk(LZvKTupIh0BRQGQ5?7eYrtIgX(kESJ zE6@C)t_{&_-bMI$znM>ql~wT=VbDwFyn!)0F6#a+uf|~4=y@NJ;nSmJ=~6#c_;pQs z;hGYgy`K+|UO6PtCN*I5w=a~U8vHsNI&!ndanvq9HeEp>My_32eZdt}$7oA2o@T=& zUZns_b6vBYHV2#Kd9KH3#qw);N2Wx}fQ(%4yA*Mrn!GzbN-1zja_ZN`QJ&DNz_qGU z^llS3cO!0glw09dpO|e@G{v>f=Lc zXA-iu{|{Yn0oG*O{*T**h=QoJL8pLp3OKAd) z$@=`+^^f2cKTi89(0epZ=CnDaFJhkHreEi;r|G-qmPwkX56m*-I=82aHO}^vNKc=c z&55od0E;F9c3iI#hW(u8?AT@{{9KR^273H9NV<4xBGx7zz{GuLN`9UB$ah;APnXB< zzXi1yAo1`ef))XwKrb_->zKKU(pZA^^xa(J<6d?lX*sF2ww_t2m~>@rAiRA*nj+_J z=s);d&{PfEvM^QdYN=TB!v5%Y)AqpVq!1$AgT^+DgkT|8chE@Z5T~>Qln2jbbFw$e zMb+7S{yU>>@vd`|p4$O1S^+CW1HF38o}vCy2zxosl?H4h#-q+?+5q%x2|w% zJd*TxzzmZ^0xUBtg6f zpzqV7;whv4T6$Q6XWOEbMI}<&cgsUzwvLYDy;x;fx*Q?BEH_SwQV-=>c+yxC_v31n-o0^o}p zon)SeBzDq-xVTRt0!sL_AMF3tZ%%#oV>x{y0$S2T<+M?OfrQ5RMi%9Roml{3(99~{ zd9`tC?{$s6=wofgKP*lHvV6-$T7zDgEb#p&=|OdrDXFc7yrg zx$3ddzPo0Oo)bU20>CR|G3_nlW2F^dP5Xe!&v#oz-uEo+_!_cx!gM)~HiW3yi!~MZ zBFz}kv)LY)KWnP;mx?2f^6`eTfAXsTTH1c6=)guutJ=eFM#{R*1J)E4>R$Cf|<$iBiEuQTaxSDZG`o4e0M0? zFTlSLJF?Ahnhw`Tg12l1?3JSD>(<^q?k^b+)1_Q1LM@T?@h)8r2VX76j9~%b)EvDq zvRIf?-1uM^-cz*x(wHll3){e2nt-6hh(u7TrH+aUPu=djLo=H%PnJ|=A*0m2Kc49n z@M_n;Y#QfL6d_<#{&1P{Q!R-HFnm0BxjTG&GgecvhPM}t>hCHaP95n~m>45xE5=?P z%zypePLz4?rBAEOHO|QCnAXc#{}x{RYe~mHk^YX`o5w}I2iAYfydO{_XNJI8M4?)w zEqYSN+XUxoH)msWs~GrQG_X;7d+>Km{3M@ieVQwl7mZWBbXPpq^r>LpR(@xKg&VE}A5AODjDm<>mZl4GkK>|XGS6u`u4 z#Tbpa1)%faJW~@^JWEtn{Nu~(iicb@X+D@Q=g0JAeinGM#pN%D8aG#R2tS>HByGUujFm_%o?FWnd9e}WGCM245&AXKD*2?5Xr?XqS|n+`WGSMUWy%f1>omT*(Eb+V21FA9$S(0cdFe*cE4jYW;KjS&Zd$NY0YByFHq-zaItCQx(;B6NvnbZv+5A&7zzV(L2!5Z{QA46`eX^{k;w*6AH_N_ zZC6Ue$0D8xtj|qow@!`c@YAIMK1^;Iru^^*&Am@$s|!f#_e|)M%`!Z0!F*?Gdwz-V zfGK_Ec^RZVP5BXc2NER^>o-QSxoaHc=7ScWS*jF=%*vSiW9V)`6jOPB?MT^UH7Od5 zWJ-JuX98M5ss)hh_rYhq>3PE>ol6>okgEQ;4pnkv9&Dih$W-qLa6+&`6M4xMgt!>S3&dr%U zGMyS1gG}Vh49hk1MHsT7hOKA0EFH8!R*y>&WH0rChW+Hh3bJM1?J1NJDME9Gco^;~ z4)Y<+M6SK7PPzEURPD8D^HMK(aqwZ|HR-?57?6=D&kdJ1yCo%cB>FNu802X>_l*82mw(;%H`MrD_KZ3&4jDkuVD6!aE_3^1 z2erZsZ*mkRz)+y7(o{3fefUU!MeJmuY5Ow0kSGxQ!d!~|d7w7=bv=(mw`XI-rCr*@ zh$qe#Tkl|Ju=#s4xLcSSx^-F+pbdAcwJE20(>xh~EoaOmb_H;`pqKK~^ZVmNzyhB* zYQO-15W0U-bIunWkFSasoR%;gpo`Nptyqc07LZu3_dFoOv5?Ryp2>KYJJ_y zB{BseqH}6)#2#W*4;s8Jd0I^u=ybDvuiiaNc3|nw2?xv)6khDJ#AZo2yu~iGsvQzw zVok<>ZU}nFYu+zk)2-pQv`+(fjrbEDdP5X(P++I3l+eP2}W%ej&#RrO3eKj#|b7`~mB$jIj z9<=yj&Bx$w@8_+>UpJ63!QIPO67}_FzteGrtX|}4w2b>@@#^{w$ReZY1DYfKOZtE9 z@!#J__$;9qe#+h2^<6CxxcSFsi z2x8x+#uJvaT`xS%ovs!#hw=11&V`KA zDTaOSx-vm9QGC|-DMza4p$wPm)U>v*P(y$P6$|^A?_GD=6>%zESMsy~%oo{gp0sk@ zb5n!8Pj3c>2NU;8n)^XS47BC>_ICfOM}MgItYdtQ_u7F@Z8?7?g|RSP@jm`?MH(2$ zkRqHE+30`V7Dq_Ha*dN-#3fDC{o!%ELJ7o-KZ>!OqfzTulbqaWp!NcuFi&bZ=%}0r z9pA0iEYNR~c2KPo#eTvcbr+P1LgX&nGGDrJV-s!eZ(JGB_v&2Kf3N4M)ogtMR4R9# zgQDW+iUr__uD9xIGk*Ajvj!Eji!BkH_d8mYwH%e*JFwP-mI9>Br#v$SW-Na-0eg{yV-Z!g_do8?5DrCr51-7-{88uxpOX!x7Jd{KFM|Bv zEE5#tGTS>;1YUW^%FFdJ{aB{xLL6imcFZ2Muz-vNaM?^<8>9GpmcSypNdIb2zCq4) zJOS3k2|Y;jhvTHBVrY9pzMQl{7A)|poq!tuC-oO+^3hrDu`>1g0?%?>zO_{Z6B-|` zpEd?@PtvX`nr^Fa98Z?3yhz3rUK9pO+b(ekQF!+thP)*#U2OI{1y{5cEr>tD z#LM}>nNXPAS=sqww?c_u1pz%vQPbJfHQjTg34VJmCU%@retABzYhh_1cd_|cqOCZs zibeb&ahf|lU_#)24G_?wVQx6&rUq=o{&`ae{W>vsT3f-aw0i%kwlMi`D%3+FP$V*^ zzW2m%42&UZfSy3+k2g`>DC=BZc@pqQAgsNf3`sV-bUJYo8O68<0-WJM+X(+&*KH&K zou-qck(p6_T&1K1@Q->tp<{XGuTT8`w^J3kGiayqt)Po&1~^+hshhv^F;2~7Nu;vF zm43_fa{v#Hs2W9&r42*Lh=r4{_x1Edki);B#8^@Jgw|-)3wcA0Qp`61rA9swdK zQDbK_S(`VO0Xmvj5U8cYJd7umCdk$?KbNlE# zz0Xj~l?#$qkSz}VJH{n*uS3Wc%HoW;pgr;yX81r5!jy@`VW0U&9a zh@`!9yZ6p@KY3oR`eRFZBIlWKne9jc+7XyL`cWGRt=ciS#L+L+x#N_c zLK87y)FJKW$=0999i`WRyih4YLNW;v40LSI&9LM3?OLs>B``vPrl3=q$p{)w!x6~| zmDrV<)uMFHS-bL!j64fvSn=E8J($Dqj@uE5du^Bk2=aAXDLWk#rO_Y&o=P`!)jq`W zVtotgjV}xS+ot{b*3|-oTw3Dby(n!jyg84JJhsn!(eoat^5PBN3;B?-PSHaFQW6LX zZ3++evD9Z}lDu^)PRWmuWlHTktW$>}kzOMpK?6>C3(z4%vH}mdfb$l@mBPm;zCM0q zJsTj)sx?D0w{Q-c+jqMduPxqy!W^E!6ArFB<^|;(8SiKjxi_5mV7A7KYF2-@Ft{~| z#Efq!ebLxxbROMV92Ab&iwD4|0*Ja~xnb`?f?&MDULP{7bCqc*;?f?8Hn?EN_h!r-V6Ol@6HY37j((0L6xo&u9Ke-nI~c<6 zcuN%kn52w`yhDR_xAV9AY$tM_fVeO`X(rYZNxRV}0E{?9>L~Tedj35-qs{vaKi|F4 zoFHR9t@2YZYDXOiq(qh#1i~B_1SjnECrfwrgbPk;Of~BkMw?U$Dd*K2o z$rBXU7jh^r%4@`1Y)bUaI3HvheD_zlOMjKOwn4< zFafc{ce^wcSpVi5AJcsH>S;7U>)v)qBP9uNb%%mpD0wu=Q;<5Sq7!=<>vz1j_dB@x zel8h#j7J5i$`@1ZkrCKBxSk?~PVA~67bQs29D6Qp?G5Uh3S&0av0I(;k|z`lKU3N- zn|il`kV)7A6#28A(od7Pf7hC%aFo1?YbtdhOeIyA2jDfv==X{#{0%A~TL`Q{wAgVc zQ9Ye;Et8f#!g@3D#*N#3-M&MY%Wx8g^R0-yMFTYQsHlpmBp5RTV(t+P2`L`e1h4_m zF>F)5(`iD<0%e(|H|NY7Zb;gl3F!K#6`Z8iA4YsCFGR!qdse!8ZSnP4w%+)p*Vpv| zUmKk}PkM9f*;A>TB%eR4`QQJMektUAYNnL;Cr0{;*RLN9`e5kw%j@IDF#7~>#aHw% zueGs+vHdz@gx@{xJ`XMnOUu-S)CAoBUAYM!^|~MdvAuiA*HpfEmBI%;zP0g|^{n+l z+{GylRTTslbv3dpZ>ZgjQvRj^#rnVjrq#4!e%{n|vcI3@^6*)gzo6vVp%<@c zS})}`rx#e>wwdU&z|G|C1Yi%<)WQ^Y1MISH8N!stf>WQjFR7nrF(PblT-NiRy{g2i zc*Q-LYtB(tppRn^j#gAnZueJ>V_7xa>7wH$E4&@|y-*=%jLXb!cY86lYKKzx?A>Sf zUgqzP_?44*XEL{gK3zy4I;THB!92uSgzvvtyBu*K*l2u!%g^K@IVlXyoqIbu&nPI2 z;YTzw{ zdTo*a!~gS>4JAHHnO)wS9H2m2iXJriPne?#15=6o^$q(UR)sdN9)-QKd+e0zesm;g z=w)l7a}%dT@gXZ)ptt{b;n(Lfr3@kinY;GPsLb2ps?K2|qfYE1COU~IjIaXJRRtpV z=s*|2ES&P4FLqUQxuH4poi`2|ITJ;MB@u?aPfG{VRnJXXd_L#99N5op6!~b4`CTt< zoViag5sp=JY}oqljX()qj}o~)e*+VETe!;w7O_+%>Q@{Ls3P7rJ#5Qj9^c$@z8uF%byufZv+n?WC&S`5#69pIUyR+Y%E<((!)eLzs>}?~(r)=L)VbRnP7O$*t;2 z&OR1QTkkt!M%dS%jUlBnVi?|MG4lHzv_$zS>G}$DY&T_8Mx=v~boslS3nC#mpnLlf z9vO=A35=?qv3TZPI7RR;rLA#{o)Jw~{o+2K(Od zNji&-ulLxcovcfqIP3IvE0~{KuCEwM;FkRF8rQDL`$56aTi<+g`Bmy9{`;3aZmv#* zq|#>lSh}lSVer+G7cxS|vGvYqbWUmggaqli?~|%K0<@bJcXS&1^ii)YqZ@8cMx*17BB@CvRschP23P zeF`7{W+oYY(3>#JQ@M{cb=%o11m(ic_E)*|cZ1>)Vnu^fhxZStasIRt$Ml9YZYUiV z0I%arOQ2g}Zu47+KVx^)Q7Y`OqgRrt!*3~7vnJvoRbu+3u5?H%cm;s5LD-e8=CK6R zRq)=~#r8uNYi<54OzpMG<;X6Q@kFQXmD8+>;oQ-ewAh)EMj7>ag}PK-iFSS`Zwd=Ob@_|ygv)5l8qBBd+bVA)spIHFR;H<)Ff~-( z|7$@4Kg?fo4{VTrsrIwdeP^*!>7DEJFKT_4`3QNmj1P`D`wBZ~DQPL(8n6TbscSMN zL!)uDbVblMFYU5xtIK$l%=%`F^ik&MFA!gL4+{)-7T$WdKl{s7aO)lLHJ?a64ik}& zG+Gh^K^QsSqWU}9?HHE0ljB#B* z8rlfjn83fj*e~P1eqe7XET+P34}aQVRHa^(Ca!@!?vifqaHJ36dBNx67&14TR-yZo zLrw*e*YCFw8Qo>Q`h>ohEZc?249CT`YWW!3rGTuutfnqgr6;^bSc6RFT8VmllLuH|CJ9Ktv(rhhOZcAH_7a1u>EW5LP*y9#}XqDRqRPP}(!uS_uf z1Vy{NgLbEozbSaxD9)(SJ!C!tX*@|OFKy9|Lts-sm(vn->hDc5`ry4DY&Czncu_?9 zn-KM&0~c+kU!@&*k#;4sI{eIHT3iO)a%4m+F$QlEv4*13czmIzxw>UPk1Z=4X?RB5 zQYuk;t_2Q%8k(*lNGZwlLNodX+^6@uW)oZ1MaQj9Dv_<Sc)gEMxjJqz zRY-92^@o7cCCwX}XT;qk%3fq<+V+g94HRy)T?0oS;ekZwqw#S=HV;y>s@3 z9gV6b3By{jTq7fxg0>xdIkjkY`K=mqs@37ZiaT>m?N(Cm$s1Air#oiBsaf%0v_3$@ z!qMrdK;KA-kX435dp%se z<-SKzhHk<-4)f#A)A`Q&3_qE!si@mW#lbNTKmBxLc_2QH3R9Y^n`Y9Wfps5OPiL(1 zU5MHW2t|&JvYw91GJTh&b|xZ|pOfpcwUcPX|KAJ>d=QtisOp{}(;5`j`1@p}!qvLx zSlZ9`vnm~()!;ILn3ZoB4%Pj))c35X({!FA`elR-hTkGk{cA&QWfn>$su?%uT&)a@ zUTLksAI4vm!7**VU5p{t9KZ9T_VE;t$NTj&jsR`!Nn{%78Ruo!;wpEZXX=SWHoO)G z4Lk2_l41m{#9g zLc!zWg4YW$d>**;CdC&){UdujMtXkwhZ4o_);A-W+q)bi7otur!rh9*F^4-w7`GkA zF5cdx4@KbN!o=u)7AVn0XWXMGjg1U&)~qgN=PE*Iz!&bcdKKDvlh3&>Mp;+acnlbs zCS3RYMD)qb6w3iV@T=2QGB#y9TBYQzo0<5iW-eW-=qTzc89d^>C{ws>xtQq~t$*L2 zCN8n(Lm1B!whOE5Q4Xm66XWEz0Td*vx1I6b>_)_LtQF_t9kY#sE}K$ zqQm)bk@h21`@@4{9AFrXE;2K;*J#93W~L`NQGTLAOwzkB45i&(bzWA9i%?$|>l(q} zNJe*sC>NBvQCz*$Hnv8Z>bd?W(~k)zV~=URzy)~lV9;!h=SbGfTU+y)eexj4T6G@wwvfBo8{QC0&;#3(oMI6tItJ=DHh4zL-RH!eF?_xCro? zELOkR@O`){W78Q(Kf!z45JT#C*FbE~D7eArNMerOi=77VDC?2NYrq7%le~~FTk%=2 zZ=)1|vicI#FrxlL;+@b zen#ogvy9`_X3X~T_Mx32LjBA&Hc(Y|K5afCItBm10{+>&lc}FuI)>Z@&$PQ)qY>>0 zlHK8@>PWV&$#Hpbe$I=~eg=b9^%Yvr0TqhNugIq_^S*NWl*Ar1Imq6KD!8i_I%mbM z6c24PU8~?Teesf@R{jhjVgjZH1uP|Gjm^=BB5CBjhr6U>of(>Yi~Iei~s;;*C!w0giFES#${d9 zQad*#lVPYF-lb5&mswOGqcB!@?vj2{idfBN561f!RVGJYJnwx&z%1bFJCs2kzs)`uG`t2TWyEbD}-jdeO zqk@%I#GezE-}6-*R-{*qp=wO@3@Waun}*r4zy0wH6h1|e8W`bF6??O1+?Kd*iKqrR&Z)5!(C1mF>jOl%v`QOMUVun4yoJF=?h) zIpxPNJ~zyqWR3t-P-9@!npyQ^H~r;(HL}*#bQ^v1Q2(Prck-!?REw#@kM;p}aj|Q~ zBFkqSmmHV+9?-3z!;Cr5Uq#}U6Zpu5LyUes*uc761nAq&eNk0D#AzwJfRU}&)UG{8 zWsfi@iI1^bw8P`76t0~sJax2*qOl!x+C}v9sn}_~>zmqj6{7L>J=S?(zBv6HJhHu~ zeLINfJzDpSe4M@I7$Ck-bCtAi@6J!z21^ly;L6|InG+fAqsY;@|qo4Fa$ zrhsD$@99+7S2#ghH?zu4Q@&X;H{( zt-;3C@;2-8{to&{>}vW?f>r$2`h!i%Tiu8ATcQ&Swg`J+Gsgc(0YV%1UJ#HtWvWl< zjRyQi=8d9qBu0YrXVpw!(LkT+yjW$>bgf@o+Ps}@+@gAZe#1i2`hIizJSUCKnwrIv zia82XXR==r&N{4Z*Phn(6L$ZB9T%y_Bll(fld8wy^>IfpFB054P8YFT5983vV1`y=a56Z{(+QgjPoMAxkM9x~m$ge14Bb(#y?g8c z$i6Bo$CSg_Tu;tFh@m#kDS-hdiY`vcfR3sRm%X~2UG2x}y$qH&a!5;C<~h;xmpmG1 z8|{7Ea#QPUU(HddU!-5EyFBJ?l2RRh@Ap%p5El+Qef07Wm3}^Pj!-vx7F|xKy*NI5 zK_}H|eb|7om%X~Yv`U9ICXAsO&AVvK5n?-h(2NV_S>h-(p&=)O`;!roZg)abM?bbY zle%VO^vQ%vDlQlI`0sOceOcP99d27(ziW=FbOV>)BWb45FE5wj%p} zox|apQR8u4hT<;gc)_ZlD@;#w@H5~w0KP{Ilb5gDCXyR;YbO~F!pD9Az5GXArc>t+ zS3e(%mqipwT}ga+fdWlEtO;|B8=U0P^4_8LBIs3YTw`#r-ql=^kxe+;2o4W>8V)KV z)mT5Tc51RH-25e1@#bOnMJ&g__*o_I*;;jSd~g{b7r(Ilg7OcPu~saFyyq`H5udF9 zx|pQ{vWt`{hm~?;!hW`I*Np2_NE#cBHI@8M?(}1oSStcj%hD@4BuGy+?F=tp!MMtQ zEDASR6NJYbO+9=1(Iqget=eroUa_kkR)u_Gh^fCoMi~0U)@2(LxIpjq2oTe$ahrxL z>UlxxL1HH2GQMVfT&j_}J@XAksyIvhWIx`L7-wb2SF&biL&m=qa9gpnwDK0c97E-* zo=c!WAGA{vC0~=TVZ3%qp11FvX*9O6!X0m6sYHC23GL3V3YJyAV(*LvtN`_C=-K5m zrfK+AsDJiUKV1s1xWWlOc^VwsN%UtAB$q(+B?;!QuHLDDdR!E_(9qJug?|R~PU8E! z9Kg-F=&q%HbndT3oVqiF9uAIO^eb~~I7Ums4+H)0y^#NQF{^bn)gnD`b9A7>;930IkY+j2oRd&^Z@81p z63R=`b%^Dux4C2t07<9o%j=QG$R?`-bS^;wTm0su&0gwWBsyzH7b|anRQt{46$N$J+V6 zQq=UZ6D`Bfduz$-W0VPY_@L&lT@=KP(xo1DEIEF8I5Jf|-E`m%=F=Vdn-q$L`(uRa zdpuG?GzUx8lD2*Ovl~G-$)W9#xL%z>4FcLpU{U08A{uHF#X;LN5VzXCm{d_(7+lE+ z?)CFhvcNrk%gDYf?pJ+-^^K-j8a(HrV3Co8W^FinhxyWO`qCe(q{QiJQkILp>FOWfF-<0W!E zgx3y_VBoOP8xSKe;wjqBRuU$Bgb*)(d}mm=c~8wsAJx`mfKr+0Y;8Nqr9;x+b}<|W z(?kce2BUy6j$Zemog z`Pr!<8~9oD4{_t$ZSywum6dvUTf}rTmVcDv>elw&SRwrxs6WkBHwV!?usZ%)_vpU- zH-;q$_)f2R_fST?@M?pagt2y9K{MK8!S>?|pjXbBD%ebHPp1k8Ss%w>xi}0ob0(Cl z{5f6z>f@e9B&ytN%ova3OA{{so5%iVt*>87xIEx2Gd2-zrGK6O9+3yoGxBYgHMBC? zH^M~Ef{Qy&=2g0eE+tV3?Rg)0zo1B}hqmxkH-J`bLTyFd)t65;7C?tW(b*2_>%+HD zC>v;XqtQ+O(QQwi>fZ%`itxPmt|1SHHd?g)DOYj9Rd*u>B5ce>2)fk=C>2zIi_5~VSk`YGXh(I%4xm8`2-8JSqk+TP39 zNUSlsxSHgh#pyjJs9Q2=$LNatxBa{s-dU=Bmz*8oZ^ADJ5x(Qz?8jWEPFgSyYe>Rq z%uhFK0OKWtBc=@fDqN-lhwm7Q)js1g=F@d+6n~1xJS&9ME6a#34SO|DG53r5k3;H7 ze~XP2Ew429P@Fn9#erBUaq~5?2`f$&`}T~|_l2xu%Aic0P_ z;RX#YC$OLKfI_l5tUUbiC&CkmmaQgbDF^0L9Jvc@T9oAwIOs@XMH9mwILS+haff~l%BS8tz2b=)I ztADWNQRQ{YRigP`AJ0+;W|q5pq!?j+f1twj=Wnqz;dr7iMLlX1>_fSXJ)xp%q|T$!EYhoQ z96&)->+RsTEOi<4#rf)|$c4#TD+gI4#LPo7_+9ewWGX$?spk&FT}zJ4OarFO#0Qya zsr)TF_^((l3}IL7Z}8x_rS<|-^Fk{`QKYwV zWN<7KFK*X(XK(Z#_?QkCiVu{TY_>NeP5>|h7~}av)t|!^u1o09T~OlS*e9C|7Ec0^ zD9LEDcy`S=oknvvBA73DQ%KuI>5!T}^v@?D-d|Yqf#lwL{%PQNWmT7B~N(y!QJFyhGZ{i}W{CXR4 z&kFpj%o@`*E}bK5^l?X+-`CVECrofqqe`w*^IphZeEVr7Ev~+zK@D*AtMq@Qx^E3Y z9`#MjE}GI3@qAe7 z#xweSI8II51Ce2fI-HlR_btxJR>&2v(*wBcf=K5LFCYDIBLnTcO-2j-)M-aq%kZwj zOuBPO(KP^|I!)IbHV3A>#g2?TV%hF#ym zx`N0r+|tQ{_H_3eqdO^FM=N3U2j?&v>_Z2)J>=~<>-riUOQ|4?VLpCw=^B3;N<6Qi zn3f9rom_YX)n|CxR7T9SYkb7?i4D_Qzd#*_1$4*@--GAR1u&o zQKp7~LxQ1^y&@Iq{HY!|6sksLG9BDIHCu{K049K8$0sVHtj#&uVmS&9RN#Z_HyC~b z<7k4Hm5SwA*>`;0H9ij(taMXeaGLR5AO(>mo%yYDG!u>y_IQG%=C66zOF=hE>If`P zh1>;QVI*(}*lyWhtKIk++e<4}ov(-m2153%3PsF~!MX7s8cd?=?mL^c#cS@-4>k^R zB$4vp-dVJYp{ z?tAf@IJ-yBqePXa;U^~N<%cA*M&^>jm!yuL8*5faQfi*7MNF!qlqX5+I59j3Spm_i z9>=mD<)25#tMgp|FC_#10I2im1kwRgxzB}r(e#i6t* zW#342Dwj20P#bBXj3sBZuX<+O{KQezz2gqCVrVJMa_O`kE1duDQSmL_AU?|+mYfdU z;DLa~3V`9Kw^RQOL_s?j_&{@DG!LkJe#d@f^_=0I!RYwObI{Fb-8m(y_(CZM$K`We zNgok)W(dwbf*#)+IRx}>8`s%;pI=-gDjiToT59llP{@)dmwg=tyO5A3tyg}?aabsbgZclOD=viPZIg@yjV^&m+4Z(kD3*2{~i5I^FB z=CYuJrp*c0ji7>P@7ep|jV^f&hg-MA>T?W;R~y88TmiV{sCKI1AuHT|0}Ysu_W=m3 zw?8~dP@?hkQ5{Mf#iVrL+&iZq-n@|J{VRx6zr7X=Q+u8Kgonm6A-d;dBXDcmxZ4h| z9ashr1{u3V>cILvnT~%9&`^=cs1;mVSKMR@c(qgr)Hg( zEiJF|#WQati}S1JIiUo;c{yt)G(D1;2O!1qP@KdP>YojA4PL3b}rUvS;g{WCN+LiLY_{ct$VG%4> z&Lzmr*(151k-*qy*Z8Pl2n`1qbh*T9LWt&?m%$Au?NxOLhoXUW3!mGIycd|LG!ZXFxpXS#WBH4mwkLBl#Vu4lR==n*Yxx=DI9H`q3*OW&4;j+NnO6r@1&`fq>K z!dGeA(uQ2fZMQkD5ET;-D3m|J2J88Bu@h#xO(;{y=vJ&`TBKB;%T(1zX`f0j$|zMQ zsn>o1Z_94=qD-KnjSNlyp-kZpBu-#hm_O|KXuY&Dz(%#=hXo-6*3OOyML#H+Aks^j zV^`IOI{(Qztfzi`-_F}Zrl{2G5<4Q8uh1S0&5l{|s0OEG57kt?1iu2^+<~@XNoIuvA#_ni0WIp|V)#tK7aoV*#|fz&<&1?AQK_ zaS=n6qkazBpd+dq1BEMm&x++vLK)OwK(;z#yik3J&bT4&W9%RbzVBKE%^EkW* zz1wt?&bO*%hw;p!zPrHtrKRmI^sGQMW7#OCMVY6(iR8O+MOWVK;^Zvg-XJYOC}p|x zO%m~67f9U|+)%Ic-ULB`P$CQ({$G`PPyp5wI`-uO^-pHk4Dw-q8u@Ee-~4WQxhmI9 z?X3Yfc`*#~$i%tsCt52;!`05%8@@xd?_8Dtc6N5VX9O9M#&cJ0jXBf~bJApO%ELjU zjTy|Ys?z1^zebL`#;+^x{^T^nPez(AIKWnHF8P0`F0a+rCb*R=2bfh}Lromwi7tY= z-Rg3Ahx>_PvYDPEd*t`bx#WT0W5o)>f*@I6<*6t7lC>(kb(LsT7%;X#(xKmn`l{P) zV0%2H{F+G(#DkG)vNFgTU#^7bewl9&I+z$y zhinlPVWsP6DN_ye`$#L3_lBoY5{|CWSl7~w(D|)e>^m0ENt-$QHit4{JB3ML%%Ahm zRZ@3HA;%hcF~siwrNsumM}nk7+=*A_+o_!fNDbLO_vNauvq@Ac0U_rs)Z_69TKVa2 zav+p9;gH5zPlKb}Xv7bz3>96awnlcVK@ks+Vb~&D%c?;Uw9PR9D?hjQkcYL2~PB-Ro2IAqFu@DaeRjN>1lTOW{2ue|Xevw@Hn+ zd;0od$1^fuaLwdZ*8rpNmIGpd#$g2o4AiCw2DuP!$JD_luPfJY(E2w@VMUw*oj=vZ zMtBHj)%MXA3y~B*N-hj2SAXT_`H9kp3O_oHTgQz>vOzeVy-(26Hx|?;pNA`z;w`<5 zEB8AbcmkpZSKQ$lyYXbJ_QPXQP`dpv23WSf0?$b-`0~k&;y4@RP175M_iHj zBQP$KC`2Kz(?n@74Wuk{CVg};gZkt!Jn0%m!e1?+B!!Pt0cdywE^xM2H2;Oe?`Fgd zBXOYMw}H36{q20F>)<80pYcgY-2jF6A}-UdM?ERL5Av+OYf422>T?Jlv&% zF%t^ebRbWoe8+-t-xt{01Ejxa-(|D#kLy{ZsFH%TORS=>T)Z+>z^T^_$YNT|dYe6ACxbiIGWpScC8kJ4bcP+@g-_eYlDxCv1VGUcUG;m$ zDvtW`w~JY;G|$jd(PVEjn&D2gqA3;0^$e8X(bl#c;5ENg13BqnsX&C~6p6Y!8djsz zSk~Qgp!vo4?ER8ninQz#k6y)Jd0nI*R(?ex1NJtk(N4a%9Ru>=|{MV zThhR;`b9O!JKUubKzhJE+#InUm%$JJ{wi^B@hYDe{i=3brDud-OqB=d%fP;NALnq0 z-}b>~2v4R9I2(bEUWY5ld92sI_5J-B6laF0LW?4y1e(h&@;$7DOD)g%!(Ht?x9La7kXfUd+D*egw*!9P$WBnhMyePWF7=~iDac3HU6Q(()}7$t`|g} z$a=mQdrbJ5^_Vh|!qThF(2@iV!1B#=bT9XZoH^1i$_|2bNdUJ^YlAl^5_MJS!Z`|} zkj(?P%bo!PYq)_JA_0)&2?}ToasxYKkbGNj-Z@dHG2^wE8U%2exRRcmnHD9+a;6X_ z_-s~JxIg^qEZ6h-qxth{ve`ztfjjes`GNA#MFt$;N%;n-3fuW1D@-vZ115(E#iqkTj((d-}u?zTb=tC3P&Qvj;t^ zHgYgYLN}mf47J`|UU>VNe}dc_8Dn1#xw&u}VI6FM_#JiB^VP=IIag-zJjugvW+(Pf z<1|4N2ky5*`#XK^P2kWQRy&qM%)Y@z@g-+UYVOA|i_l}qaFNb*x)f0zD5xTE;t&L! zk(JG>AlMmtra9Y@b_d}7{KZ^6klJ5C{*4`CZBQMX`rNB+_%w)NzCZ%HV*OC}WY$r3 zGjx-kuCca8iA{m>Dq~q29(I&5p`tM?0En$|F3?3#nScGc4NcC-!VvC+|0 z4;p?ntd6snsEDWB|LJ8FJvyZ}Y%olMbqH3GBx9US)mR z(+M{HEr4QJJD2+9nulD0wd0EV%C1jk?w^2Dx%1`S6q~BH0FL=o;P36@UZ4w=^N(`> zeL()YF}2aFaqY#6qafo3(a5jHnVTT+(Ho;Iw!L~8utgs4U*L|{*Y9VH)ii&**v@>q zs<*|?GUG0}u|4Lo&zq`d#kj!R^t!_K3SOZD)J>@20lWQCK%AQB1&1feS1$QM+C!r+ zJW`tA8=OOMPN4NhWEsb-1S9~AtGClk0n{avv;YS(qG;|5SBOr(js%8XNqyH6jpa4o zoeYHlH$_zlLF$S7Pv`UO6E2(`D{<6JD4I>V_Kq{brv5t3%h_FpNZ%4;vNb*V)1EMs zDyi{iuXJ;1`ESIwQtyBBfCQI=F-*zYX+V13@MPsyi0Pk~{&)n~{GbT`y!w_}*s#xA zg!-m>ov_0b_tKxA6lpkpjAjfC%=RG;D7vImI_|k0g zGRiFH60;fwi|UJuxq)Nqn4C2u-0ExhkQ*>ArjE>H`p9fZunwQQbl#3Xq?u=?=cdYZ ziEO};ZhfOF8dj_MrmC*svWMRnedDoobD!lA^XEa~e4!u7FqQ3+Hb;@XI`@81c+o;j1%zRDw&cwu#Ws|G?H_0B5 z_)6LPChxbq#9^} z$s+K(@BG!h1203llEJfV(CiuaHttveV&%{%WFY?gS9~Q9DJ@RC-*i$6hxHsC%bkVx zu+$6OM?%o~yoiMHL)BvI46ssT^{YqzyZ|LT1C&ft2uI%yHJ=JLimS8F{g^fY_-R-B zJiV7|YvGd#iYKjK>&|txw@ImAuqBOzoq()?9Q1T{vAfJ|G}$wcI}*hnY4ToRfUB8A z@sJ(JoF?#r$bfU9KK2MpEDb_g`1r4ptx_(jXQUDZsx;so#llbu<1b&~yQaA)+VAo| zWZ8eN;lir$u+77deni?akYwJ~9@!g=2I&pJBh4O?7k;r{8ssvXSM&-A_i;W<8mrFfyXl z4#3GraoO~LvH+*eQ)*}$Sg<)Qc1U)^G72-c;rV*`>cjK7#@k1Zc(T$tFazm^l4 zJKuS4DGFAk{Wa9<%7x z)b>j7{Cjbpx>O9#Awbjx%nx>cYkMa>dE9p2}vH%o{ThUaGk^xne-9mc|q{NOnSJtM(R{PJWURt;9t^9%sL=B2_q;g*a z?Y&n3EH`o`n$vi(CnvGgvsyrDtnQfNn&ir)zQ)kzTl%&Fgn&{o#{P|yz&P5FUIWRI z(Hr*|e(n%?@{nZ^(+4XiT;AcF8fSTSV)8L7Z zZ1BZrx{~jVCR`VXUBoF-5R5;*b#p;i99fG-SfXAVUG@Yq)TuGm0(I#e z{ZyxcVFS$8jJw-z*?nvrDvp0i0FOr-Ysa|wQJ+>k3gacq&>R{xzpG?cTI@h zr<2h3pynq&zh`A1z4Y1iT-zSNM<@TBy6d-&OIAMjCVa>qY9GaZ_Ve`zmwNq2aeRl& zDjFEOCP?wyXsPCdymaK=Xtd7m!ZH1-@o^E@S&$~(YAP1yz-Z?WWQklE~ZL?b0MIGvEYpIb6NftjR-X4fI0RnXuju5|xapTI8vJD&FV=Qo>lYPe= zU0j_Mh+pla78{t*c~;kC^}I>$H+1_e!%_7t?AMlyz~x4KESFi}<<7(yR7g>w&^7VW z`A0#4uE9BBC7y2D6P)LBVM^mn!ok@&Ji#BS>RiEH4> z>n#wbmmRj*bSms)lk8zYtXnk>s|fivELkI_;0*jrDdxvgPV3S2S$%3qcv{s4*kTimXA zGOubqvHGRQ?~W%fxkruw75cNp2x)2-NXLrGyaM@qBZBDZN+H<@Tn^u)pS1TucDHf< za9CChSEq9oKkmoE+6#~bd8^CICMfv0 zb6pcbd%~N!c@SB=cAeP=?q2P7#9$c6-29(r0c*CshWq!rP%@c^R-DCb^|}EXVVH^V z_OX&`1=#0ekp>Y&|7k4ucaP7RGJj9KC%PLS2yodreZ3geElmxQi(nxOI`*OIImNP9 zvvwl9KR^mY@1_ax_yYj?H132!a_SX~biap#PVTXvSq4zr`>%@aM*3%${Z_$za)lc> zlm)WpaF#Kdz)Lkw#C&sa->jpR<~LxZ9W;l{^8+Iyr;Fz3sV+-Sv4rJ=yzK5pFzQG| z)dR2lYtVV;_q8jstD1Q9Y1Y7~AybLV`Y4&P#EKKQhPJ%$D^8is z)sDMg?o}|ue;U&~_XY=&tqLH`zz6dHxg`L*q_+PV9lvIQ0&UR*FUS+d^?&hh=0SaC zAvE&iGJ)iE63_99b-oC?;REe$a3|k)Gu>pTe%Y3B(x>v0p+n7mXe8oyXO4c~`>feq zMpL}~FCT+6t4pMysXCBJ6#n}ZO@YsUP1YWlqPJ3t6OwNM@K*^RfQGi|S~(zx#T|FJ zD+$7;7g^)UYH>fm&Y$@-X8K!zc>L=Iws+TQJYtHVQqt^>XIhhM_4_^}pod&6hWDD! z#HdC-Kfm7sAXc7(zY?R8yI*y&7TBOBflR1)E>~ z!`v#cqqNW8yj=V+nFmrqc4qxWrUaI67)YL@4n<5}hz@|zzlBdONbjN2a@axFD*F0B zvh2a{5Gfoyv(rQTqJ-$SBkGf|z9Cv*oxB3^ClS^nkCyo_Gp9AH z+Q$0@|0&JS>n&t8dVdpI#j<8iDE~(e0$)v316gD!e7yE!6UuqsF2V?6of#SIs$M68 zx~sx@l*K4w(Nn)WUzR+a$+fs|<;2iKo|5&o6IW zZZmiWXE*DF4zwoE0~Qi+z_J3klf>~jE0RMQctHLH2L8fX)h1Z*GP)i1Aav}{ggSY< zzRqpV(tOVI5#BaW^A2~LxtnpZ-G8wmnDa04rW=bpbi=-NQQ?_%6U*T61sl(?$}!j6 zR&{+i*x##hX)eS*1w!ptKFD1iuy|X_OO;n2+Rz3Y_sG&7))-pqOO=IMt_YBx$iR}_ zq5=hW%seQ!S^^#vWy8CXPBe(svA0v5rgfa6m$t&+!-&jhIG~7nz|x?fqe)Wc%TMS3 z$k}s?5=Ng!7LjKJUC#*9+DljerY~PIhFvlieX%YzfG%Mz6D*L3uI<9-KpxiBpcxJ0 z|9m)QM`iZU>8pbjWYDz#w^<@lDTIha_W-qQQ%WX#6K@6I{{V8|CAc;SVJF+*vFkTpV}RXrqo8uD+pZJ zsRt;HRv)=fwJX9}tI1y#>9E8;4|&w1dLJBBx!lSDr0d_0$DUEZ@jmM{1D!6wgs3@T zq}h%eHe>W9`S60j4t;qiRgvpw$=L6)A#6FoMF+WmXf_xCu7Bbo%gAuBm4)rVU%Cj` zshww0_}dKZI~mKx*RLl%_w>QiFjy$ADa#wt=YXu|fF6g@+@vUyWaiWL8JK@ye`O`K zW!r%_2ddstoE)41?xFr62M_3}gdiL`7#dyc{czT$tOiI^hp%JF43OkcT>LQl4?+7? zUwW<5Re5L^13gkfjC6a6ULq5qNK0PMsi zlqDCdNGEx8>4F`;ZQ*7RGJg;GkBR69xb{(*)hs3n1#x&})VIlXr7{tF5~2TdzuLd{ z%m3L=I+2?yrh3&8WjGMlHCcT|*SCLXR=1Bag#Jt*iXH4JU4nF=vgjAE;u^JZm|55n z1%aP}&ZQyK?Zthjm>j#Y;n^|0)m#9A#0O440t)zdZ^EI`-Z5(X$)W`q$sJMf^dMG8 zhY#k9?w>xipEg{JTL_Rh1>uRHK}!l|J7T|7Tfo2(mBUpeE4Jf_fqx2H4%Y`;IN+vh zE7Weo=r4b2bcIH!Jud?OHeNqqLGuUWw_qYa zme*%8n%`iz$GJD#s(K?Y38>VI=?T~eGgh+-{_M(6V!Cwh&n0lZ^c1{tZ zDMbIhfLa+jgb9XA@42e(S|1e4pHv`_XS}2#D5{Sh^0?WDFQdOT+j=Z10K$z+Kt>bNmHBmpKcaDPXAO`$@s6%LOBdo#S==CbCz;W8IvE2!O|Agtp;#-9|Zk= zHt{siPL!qV6doYB|&#_~88slc|jOgx6|6j`4)SIJaCH<4z5L0(xV?d)J`g7IUEii_6{g{#q*-f1^S*Hd(v(o$cS(85 zZ(!5wAi?fvx@9M_TyPVlmKn(7isP{~lpB8Vvd&?34t_S2X^);N6)(A4IGNoqIgyVQ z7<}xN4wy8$9Gq5h-gqijZHmTdzLs7r(tQ2TmM}=}qK$-3e}Arf$gfPxU9mWLw9MM= zm4z}DYQ3g)&xo?#w#Zd_l2L`m=`zsmLMNHa;x%2kRT)vL znJ^N$EBtkhk3XeThr?3j{sn$zpOoN*40Fntw6H%Vl`g`=~Yb*Vh8<>pqkpANtIcEleIk@j&6;rdJOqB78YZqi{tclMk zK&C%(O!48u%mE0UKtPo;z4v?oF}I6otEqqX$OdV-OaFV=FomJ6Lmvw{V_DM^uDsv% z4Gh2xWzf64FjK1E$7jisFW#0Rq7IU!7_PVwy>-xT_d)7CF3tR;CV$8bUkP>vG1#6;vF%e4$Y^1HX0FDJq$!V%!%C9HpFC|O&5Y@$@hRAQnx z6wi@45u$RQ@H%Os<2(szE@onc-SNoVe$<)uonLm^F?Hl{+D_fMUDcf-<);cHY{Wx6 zFE=m15VY=*Pr-*@OA8Yvd^~&A8o9?8r2W||OUHRRSQOc%=8Yb!)ytjPy+*tMd&-vQ z(RTHLtY*PZg|n-(&sInF0xa~>0%YVnSbDd$MTJzrleI5gt8y?;7cuuO2ehdh{8up0 z(n^%0$WV;NS7(D|TavfYHBm*8r~)y?kf^%ND}q1HzIJommuPceV6eBVX3Xnrw79q} zNvVO2rPg8NtGu6=@(>qz0|YyP z+RK2tK~-AOA60y?Wm*(j%0*w*X9E9PsLds42EkdV71)foiNY&8CP%m<9*bVChNjX_I7x3l#@ZgiO+iYclrB4 z0|SPjuxhVm2OlfCMpa8y9=9Kr6=Y~7y&h@OsIjUq^v!?Vthbr{IjH7n?^mV$R2Bb< zNiMgXExto$yrn0Ib}LbMJ1Ww{Q%5ur;TuP1hu<6Z zOXn+@zUd+{!G>8K32XmbVcTdMgz1Q)DWH0D_=aUAov>TgOe02!lvz$`+`QQ;<01&0 zoixR6!~Q=iykk_cUopwS)wyvpUK|I2494WzIz(> z`*R{@rB+FBqhi=r_Oc)}NBU`R=O#v5*-L5yN_vC44Xyb<^e%<4|6t_^e4r^QMn)b| zSnIF)i*?v3JS_eKiI8Z+|1v+E&-pq5MUqsky`_W_39{vnJyBKT?7Y4zz)@}*eDh=7 zK=cawokFkTNd+eDHapYwjc9$l+!eWsGDw2_SA)x<@F=@`V8Zr za~%q$FA$?ooGVslZnjY6TUyl|gbzQ-nVs)7)l)fDaP*YYZT{*@6T&3lMPDJl+_TVx z|Nm62Y(Mus^H}frM1G1#wBaQH4@0mzk%myA)zXQr2*{V@qp0_!#OJM`_G3#WKvbc0S5aM!P$a?Nc|CS1ZH z5K+u>A5l~}Z7d`tL_>$BOPF}qJ*@R zqFYZ$w-%zg8$L3gUf5F%AMT(NFrHae_Uv!khGFEvZ?+7G^2Vq~g1^mhD2O9Khm*_A zA5ph;NN=iw&dHK}EnqWM0M`3(gpHvaYkWl=$)!R96x-pjosGPtjVxj%L-Ny|q6sHA zZNh{L@;GvC7_Jw7PnfXpu5`XVTgw+CY5yecFYta^sL0jQ;0HaMG}~uIJ!B2$(-^q^ z{M3w5n~ykrdb;QTsuN)JkxSbP*9e?Xa*D&q3Im1Vd+ctdYCVR)e30P>VHgGuwxcH|~AO zrS5^Evmq!U^VGK zXJza#a%0G#o^W2IR$OVo^o{mM&Ls|1fE#h=XHOc$Rnll1f(cpfYOiCB=tPsbk}bsR zBa=ugR=9c7w1z4;#X_m>w%w`H$<{+C&78)$R+0z zsAI=V`$_JYWqUbt$GU$=NC>gTWO!&;WboMHK*d#OFN030l&# zn+1;P0=pv#Q^~PKL2IVwqv3M1_oT3?-FgB#Mdf*T)FMKWQxj4wm;di7`*ibbaAs$P zsn9iMzy7)bND$-OrKjk&6~$74>^_ge(cS(F2WuQAJRolOP)X z4?Y>~@ZgB%C+O*17iccm@1i;6{?XAK`y!Q{s*~uyd) zeHMbOju-3(k@6pd6fSgAa@5|L{yr@#Aj$M?XE1;ZUc( zT_wakGg@v_M`+T?_O@b3-bNn>o77Sj0L ztpa$l#;2y$Z?Z11X9;xB6=ig7pHDacpOZ`+W|r1%@upvM7j&9!4ZyK zAp69LMXs*FF^F+3)g{m^pd+NmYTMBcXvhh&E%{)ld(Nl0eQ3!*Cf+4Dn8tY4%_ zbtzOKo|q$8J_-E7a^-%dRhdutJU9n7a8AAD8BPe77i{Bi5cpDz#q<;l#Wy**@5!?M4C3r~7jd-jB(ZD z*$eSFOPA{_6aF?<7@Iz@r23_f7JlPQbcJm^;Pj*oXWbxZmHapyMH0>ZuuqmZy(Hz0 zwzv@(ONe((M!L;(o}8sx)PWCWV5UMR8o+-S+r)7R@2SvlcGH!%xyq7X#v|1?m7(-r zJ9J9lJDy%;B$-s+l&ffYs?3m?Wx|ZLh;J~tTiKl;0`!@?PC}|~9rjjcq?}SLKDKI`Y z6LiIb$0TnO^A3SmGm&kF4Qpc3+bJuC58m7ShY+q~m}qe}PPS~W6hL`XmOpB9;Xw5w z!Rp)421rO_+yy^d*qp~|)o7&Cq7%v3O_wQ=(vfw;7nQH_O-%@ZJv@D&7iq3zlm%ae zBB5aN%gA$W10ko#4j5Nbes*744&-My^K8>fMYj*5{UdxIlR3!rmb=Xs^kk(Ib|pt; zp2N@uE_LT4I-U(9>G5io+jJjqcF>idd-hdY)(3*MWWGoh=|D{JD=SCj^s#I4>V%qI zVmk$-ZU7TK@82XOSg@DI$X>c5#-*oBkEMyV+o_0K(e;+eb?(u?ty}k8>7YV>E5o!6 zpM(dR(AgKx*#|iF>uK^g#;DJ9SC8w`V#Tc4$@*o~>DyD@x3vC-B{nn*eIZm_elWmm zYoPNgHeZSvViOQK+RhGb|zDyCUVRtsBS3NS`32$W@ zXteT1QSRwZJDNn7HXaFpAsp~02evf$2G@!J0}Tm-QBKF_83LEH-8%wYM`V2Tv)%|^ z9>H_1=dD8T3u1+@^3|xan~`A@wzI5;!>`#IF;4;bK{ZCoP#i52HzZ%~Bd~HVpa#G9 z8HE?8PMxFdUA@*u|Hh++0~-dbjRNOj`3Le;CizovQJDx2;ZS-F8UkaUXp!1)?9Cpm zB18;PcfGnw9Ba6H{xpfRF$degwQ(m6zH~QmW*y$&iTb#j+V|;#L8q=eC`|72j?~@y zR+Fa%6Rs2v?S(_{u99?fB@G$H@rV>gx|-y_mj!wNVDu1ad{YUK3jBGn2pyxg&nq^d!rkckY@^_Cgi~L5wwFb* zFSv(MX0vPNrfAsb`!Qv^8QZp8z*|jFN%pO#;~PIs3{Cl2cWV&|cs} zB;ZX2*480#;_1<1ETZ15T8FY+!#f^23|td~$uY_cp%H&*jpKNznko@YE^X*b?8N2I zMRuw_zB0D2d*43Niwpjy`bGL*L!!`I6xgKIshXG6F=;1{)ZJT^+kb3eCF}KtC7yV1 zOTJ#Y(^a=oGo`cZs%>nDjYl>TO~TJe8^WE=EGgv?E42@;_{N!Rv33up-_d8apK`^5 zgJ%@b$%x8$DXg}Yw&NyxpX9=*l6#0<}xP4XGtS9gl%83c)Mj` zhD+bEPgk(VTK(2s(@;m-rgP_*-aWGX1fg?k3=>8Aq>0viAx-QmL`2sp6;s8xje6St zq3=1bYo4EJZ^J<&LI5{=ClP3&`+EX^YzE3~J95;_?AP`lwaINYQU=Ox08DH1BLy9m zl>cSp_e8BBTv&97IPB3Y_y>FdNzF2>{IP=nva=8p@p)Z(|NT`fP(PXy=5&Ji=6aHGoy=SS_uc}+(W!6v)gGJ>_Roi