From c85039e413fe3a96502e0fdf6d336c16b9711ec5 Mon Sep 17 00:00:00 2001 From: Vicente Monge Date: Tue, 16 May 2017 17:30:56 +0200 Subject: [PATCH] Fixing rebase conflicts --- .gitignore | 1 + .gitmodules | 3 + CMakeLists.txt | 5 +- README.md | 2 +- Tools/generate_microRTPS_bridge.py | 191 ++++++ Tools/message_id.py | 108 ++++ Tools/px_generate_uorb_topic_files.py | 107 +++- Tools/px_generate_uorb_topic_helper.py | 30 + cmake/configs/nuttx_aerocore2_default.cmake | 1 + cmake/configs/nuttx_aerofc-v1_default.cmake | 1 + cmake/configs/nuttx_auav-x21_default.cmake | 1 + cmake/configs/nuttx_crazyflie_default.cmake | 1 + cmake/configs/nuttx_esc35-v1_default.cmake | 1 + cmake/configs/nuttx_mindpx-v2_default.cmake | 1 + .../nuttx_px4-stm32f4discovery_default.cmake | 1 + .../configs/nuttx_px4cannode-v1_default.cmake | 1 + cmake/configs/nuttx_px4esc-v1_default.cmake | 1 + cmake/configs/nuttx_px4fmu-v1_default.cmake | 1 + cmake/configs/nuttx_px4fmu-v2_default.cmake | 1 + cmake/configs/nuttx_px4fmu-v2_test.cmake | 1 + cmake/configs/nuttx_px4fmu-v3_default.cmake | 1 + cmake/configs/nuttx_px4fmu-v4_default.cmake | 15 + .../configs/nuttx_px4fmu-v4pro_default.cmake | 1 + cmake/configs/nuttx_px4fmu-v5_default.cmake | 1 + .../nuttx_px4nucleoF767ZI-v1_default.cmake | 1 + cmake/configs/nuttx_tap-v1_default.cmake | 1 + cmake/configs/posix_bebop_default.cmake | 1 + cmake/configs/posix_eagle_hil.cmake | 1 + cmake/configs/posix_eagle_muorb.cmake | 1 + cmake/configs/posix_ocpoc_cross.cmake | 1 + cmake/configs/posix_rpi_common.cmake | 1 + cmake/configs/posix_sdflight_default.cmake | 4 + cmake/configs/posix_sdflight_legacy.cmake | 4 + cmake/configs/posix_sitl_default.cmake | 16 + cmake/configs/posix_sitl_replay.cmake | 1 + cmake/configs/qurt_eagle_hello.cmake | 5 + cmake/configs/qurt_eagle_hil.cmake | 1 + cmake/configs/qurt_eagle_muorb.cmake | 1 + cmake/configs/qurt_eagle_test.cmake | 1 + cmake/configs/qurt_eagle_travis.cmake | 1 + cmake/configs/qurt_sdflight_default.cmake | 1 + cmake/configs/qurt_sdflight_legacy.cmake | 1 + .../uorb/microRTPS_client.cpp.template | 406 ++++++++++++ msg/templates/uorb/msg.cpp.template | 100 ++- msg/templates/uorb/msg.h.template | 7 + msg/templates/urtps/Publisher.cxx.template | 154 +++++ msg/templates/urtps/Publisher.h.template | 92 +++ msg/templates/urtps/RtpsTopics.cxx.template | 159 +++++ msg/templates/urtps/RtpsTopics.h.template | 95 +++ msg/templates/urtps/Subscriber.cxx.template | 146 +++++ msg/templates/urtps/Subscriber.h.template | 99 +++ .../urtps/microRTPS_agent.cxx.template | 280 ++++++++ .../microRTPS_agent_CMakeLists.txt.template | 54 ++ msg/templates/urtps/microRTPS_transport.cxx | 465 ++++++++++++++ msg/templates/urtps/microRTPS_transport.h | 119 ++++ msg/templates/urtps/msg.idl.template | 80 +++ src/drivers/protocol_splitter/CMakeLists.txt | 42 ++ .../protocol_splitter/protocol_splitter.cpp | 603 ++++++++++++++++++ src/lib/micro-CDR | 1 + src/modules/mavlink/CMakeLists.txt | 4 +- src/modules/micrortps_bridge/README.md | 385 +++++++++++ src/modules/micrortps_bridge/hello_world.md | 115 ++++ .../micrortps_client/CMakeLists.txt | 86 +++ .../res/basic_example_flow.png | Bin 0 -> 182298 bytes .../micrortps_bridge/throughput_test.md | 87 +++ 65 files changed, 4091 insertions(+), 8 deletions(-) create mode 100644 Tools/generate_microRTPS_bridge.py create mode 100644 Tools/message_id.py create mode 100644 msg/templates/uorb/microRTPS_client.cpp.template create mode 100644 msg/templates/urtps/Publisher.cxx.template create mode 100644 msg/templates/urtps/Publisher.h.template create mode 100644 msg/templates/urtps/RtpsTopics.cxx.template create mode 100644 msg/templates/urtps/RtpsTopics.h.template create mode 100644 msg/templates/urtps/Subscriber.cxx.template create mode 100644 msg/templates/urtps/Subscriber.h.template create mode 100644 msg/templates/urtps/microRTPS_agent.cxx.template create mode 100644 msg/templates/urtps/microRTPS_agent_CMakeLists.txt.template create mode 100644 msg/templates/urtps/microRTPS_transport.cxx create mode 100644 msg/templates/urtps/microRTPS_transport.h create mode 100644 msg/templates/urtps/msg.idl.template create mode 100644 src/drivers/protocol_splitter/CMakeLists.txt create mode 100644 src/drivers/protocol_splitter/protocol_splitter.cpp create mode 160000 src/lib/micro-CDR create mode 100644 src/modules/micrortps_bridge/README.md create mode 100644 src/modules/micrortps_bridge/hello_world.md create mode 100644 src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt create mode 100644 src/modules/micrortps_bridge/res/basic_example_flow.png create mode 100644 src/modules/micrortps_bridge/throughput_test.md diff --git a/.gitignore b/.gitignore index 4c35c53cbb..b0b4eeda0b 100644 --- a/.gitignore +++ b/.gitignore @@ -62,6 +62,7 @@ GTAGS *.creator.user *.files *.includes +src/modules/micrortps_bridge/micrortps_agent/ # uavcan firmware ROMFS/px4fmu_common/uavcan/ diff --git a/.gitmodules b/.gitmodules index 26451efda8..5f8d8ec431 100644 --- a/.gitmodules +++ b/.gitmodules @@ -37,3 +37,6 @@ [submodule "src/drivers/gps/devices"] path = src/drivers/gps/devices url = https://github.com/PX4/GpsDrivers.git +[submodule "src/lib/micro-CDR"] + path = src/lib/micro-CDR + url = https://github.com/eProsima/micro-CDR.git diff --git a/CMakeLists.txt b/CMakeLists.txt index ff3a62ed01..356a8fd20e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -204,6 +204,7 @@ px4_add_git_submodule(TARGET git_mavlink PATH "mavlink/include/mavlink/v1.0") px4_add_git_submodule(TARGET git_mavlink2 PATH "mavlink/include/mavlink/v2.0") px4_add_git_submodule(TARGET git_nuttx PATH "NuttX") px4_add_git_submodule(TARGET git_uavcan PATH "src/modules/uavcan/libuavcan") +px4_add_git_submodule(TARGET git_micro_cdr PATH "src/lib/micro-CDR") px4_create_git_hash_header() @@ -380,8 +381,10 @@ px4_generate_messages(TARGET msg_gen MSG_FILES ${msg_files} OS ${OS} INCLUDES ${msg_include_paths} - DEPENDS git_genmsg git_gencpp prebuild_targets + DEPENDS git_genmsg git_gencpp git_micro_cdr prebuild_targets ) +include_directories("${PX4_SOURCE_DIR}/src/lib/micro-CDR/include" + "${PX4_BINARY_DIR}/src/lib/micro-CDR/include/microcdr") px4_generate_airframes_xml(BOARD ${BOARD}) diff --git a/README.md b/README.md index cb8c9386fe..afe88e7108 100644 --- a/README.md +++ b/README.md @@ -62,7 +62,7 @@ The PX4 Dev Team syncs up on a [weekly dev call](https://dev.px4.io/en/contribut * Obstacle Avoidance - [Vilhjalmur Vilhjalmsson](https://github.com/vilhjalmur89) * [Snapdragon](https://github.com/PX4/Firmware/labels/snapdragon) * [Christoph Tobler](https://github.com/ChristophTobler) - * [Mark Charlebois](https://github.com/mcharleb) + * [Mark Charlebois](https://github.com/mcharleb) * [Intel Aero](https://github.com/PX4/Firmware/labels/intel%20aero) * [Lucas De Marchi](https://github.com/lucasdemarchi) * [José Roberto de Souza](https://github.com/zehortigoza) diff --git a/Tools/generate_microRTPS_bridge.py b/Tools/generate_microRTPS_bridge.py new file mode 100644 index 0000000000..ff79fe46f8 --- /dev/null +++ b/Tools/generate_microRTPS_bridge.py @@ -0,0 +1,191 @@ +#!/usr/bin/env python + +################################################################################ +# +# Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# 3. Neither the name of the copyright holder nor the names of its contributors +# may be used to endorse or promote products derived from this software without +# specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +################################################################################ + +import sys, os, argparse, shutil +import px_generate_uorb_topic_files +import subprocess, glob + +def get_absolute_path(arg_parse_dir): + root_path = os.path.dirname(os.path.dirname(os.path.abspath(__file__))) + + if isinstance(arg_parse_dir, list): + dir = arg_parse_dir[0] + else: + dir = arg_parse_dir + + if dir[0] != '/': + dir = root_path + "/" + dir + + return dir + + +parser = argparse.ArgumentParser() +parser.add_argument("-s", "--send", dest='send', metavar='*.msg', type=str, nargs='+', help="Topics to be sended") +parser.add_argument("-r", "--receive", dest='receive', metavar='*.msg', type=str, nargs='+', help="Topics to be received") +parser.add_argument("-a", "--agent", dest='agent', action="store_true", help="Flag for generate the agent, by default is true if -c is not specified") +parser.add_argument("-c", "--client", dest='client', action="store_true", help="Flag for generate the client, by default is true if -a is not specified") +parser.add_argument("-t", "--topic-msg-dir", dest='msgdir', type=str, nargs=1, help="Topics message dir, by default msg/", default="msg") +parser.add_argument("-o", "--agent-outdir", dest='agentdir', type=str, nargs=1, help="Agent output dir, by default src/modules/micrortps_bridge/micrortps_agent", default="src/modules/micrortps_bridge/micrortps_agent") +parser.add_argument("-u", "--client-outdir", dest='clientdir', type=str, nargs=1, help="Client output dir, by default src/modules/micrortps_bridge/micrortps_client", default="src/modules/micrortps_bridge/micrortps_client") +parser.add_argument("-f", "--fastrtpsgen-dir", dest='fastrtpsgen', type=str, nargs='?', help="fastrtpsgen installation dir, only needed if fastrtpsgen is not in PATH, by default empty", default="") +parser.add_argument("--delete-tree", dest='del_tree', action="store_true", help="Delete dir tree output dir(s)") + +if len(sys.argv) <= 1: + parser.print_usage() + exit(-1) + +# Parse arguments +args = parser.parse_args() +msg_folder = get_absolute_path(args.msgdir) +msg_files_send = args.send +msg_files_receive = args.receive +agent = args.agent +client = args.client +del_tree = args.del_tree +px_generate_uorb_topic_files.append_to_include_path({msg_folder}, px_generate_uorb_topic_files.INCL_DEFAULT) +agent_out_dir = get_absolute_path(args.agentdir) +client_out_dir = get_absolute_path(args.clientdir) + +if args.fastrtpsgen is None or args.fastrtpsgen == "": + # Assume fastrtpsgen is in PATH + fastrtpsgen_path = "fastrtpsgen" +else: + # Path to fastrtpsgen is explicitly specified + fastrtpsgen_path = get_absolute_path(args.fastrtpsgen) + "/fastrtpsgen" + +# If nothing specified it's generated both +if agent == False and client == False: + agent = True + client = True + +if del_tree: + if agent: + _continue = str(raw_input("\nFiles in " + agent_out_dir + " will be erased, continue?[Y/n]\n")) + if _continue == "N" or _continue == "n": + print("Aborting execution...") + exit(-1) + else: + if agent and os.path.isdir(agent_out_dir): + shutil.rmtree(agent_out_dir) + + if client: + _continue = str(raw_input("\nFiles in " + client_out_dir + " will be erased, continue?[Y/n]\n")) + if _continue == "N" or _continue == "n": + print("Aborting execution...") + exit(-1) + else: + if client and os.path.isdir(client_out_dir): + shutil.rmtree(client_out_dir) + +if agent and os.path.isdir(agent_out_dir + "/idl"): + shutil.rmtree(agent_out_dir + "/idl") + +uorb_templates_dir = msg_folder + "/templates/uorb" +urtps_templates_dir = msg_folder + "/templates/urtps" + +uRTPS_CLIENT_TEMPL_FILE = 'microRTPS_client.cpp.template' +uRTPS_AGENT_TOPICS_H_TEMPL_FILE = 'RtpsTopics.h.template' +uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE = 'RtpsTopics.cxx.template' +uRTPS_AGENT_TEMPL_FILE = 'microRTPS_agent.cxx.template' +uRTPS_AGENT_CMAKELIST_TEMPL_FILE = 'microRTPS_agent_CMakeLists.txt.template' +uRTPS_PUBLISHER_SRC_TEMPL_FILE = 'Publisher.cxx.template' +uRTPS_PUBLISHER_H_TEMPL_FILE = 'Publisher.h.template' +uRTPS_SUBSCRIBER_SRC_TEMPL_FILE = 'Subscriber.cxx.template' +uRTPS_SUBSCRIBER_H_TEMPL_FILE = 'Subscriber.h.template' + +def generate_agent(out_dir): + + if msg_files_send: + for msg_file in msg_files_send: + px_generate_uorb_topic_files.generate_idl_file(msg_file, out_dir + "/idl", urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT) + px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_PUBLISHER_SRC_TEMPL_FILE) + px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_PUBLISHER_H_TEMPL_FILE) + + if msg_files_receive: + for msg_file in msg_files_receive: + px_generate_uorb_topic_files.generate_idl_file(msg_file, out_dir + "/idl", urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT) + px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_SUBSCRIBER_SRC_TEMPL_FILE) + px_generate_uorb_topic_files.generate_topic_file(msg_file, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_SUBSCRIBER_H_TEMPL_FILE) + + px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TEMPL_FILE) + px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TOPICS_H_TEMPL_FILE) + px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_TOPICS_SRC_TEMPL_FILE) + px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, urtps_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_AGENT_CMAKELIST_TEMPL_FILE) + + # Final steps to install agent + os.system("mkdir -p " + agent_out_dir + "/fastrtpsgen") + for idl_file in glob.glob( agent_out_dir + "/idl/*.idl"): + ret = os.system("cd " + agent_out_dir + "/fastrtpsgen && " + fastrtpsgen_path + " -example x64Linux2.6gcc " + idl_file) + if ret: + raise Exception("fastrtpsgen not found. Specify the location of fastrtpsgen with the -f flag") + + os.system("rm " + agent_out_dir + "/fastrtpsgen/*PubSubMain.cxx " + + agent_out_dir + "/fastrtpsgen/makefile* " + + agent_out_dir + "/fastrtpsgen/*Publisher* " + + agent_out_dir + "/fastrtpsgen/*Subscriber*") + os.system("cp " + agent_out_dir + "/fastrtpsgen/* " + agent_out_dir) + os.system("rm -rf " + agent_out_dir + "/fastrtpsgen/") + os.system("cp " + urtps_templates_dir + "/microRTPS_transport.* " + agent_out_dir) + os.system("mv " + agent_out_dir + "/microRTPS_agent_CMakeLists.txt " + agent_out_dir + "/CMakeLists.txt") + os.system("mkdir -p " + agent_out_dir + "/build") + + return 0 + +def generate_client(out_dir): + + px_generate_uorb_topic_files.generate_uRTPS_general(msg_files_send, msg_files_receive, out_dir, uorb_templates_dir, + px_generate_uorb_topic_files.INCL_DEFAULT, uRTPS_CLIENT_TEMPL_FILE) + + # Final steps to install client + os.system("cp " + urtps_templates_dir + "/microRTPS_transport.* " + client_out_dir) + + return 0 + +if agent: + generate_agent(agent_out_dir) + print("\nAgent created in: " + agent_out_dir) + +if client: + generate_client(client_out_dir) + print("\nClient created in: " + client_out_dir) diff --git a/Tools/message_id.py b/Tools/message_id.py new file mode 100644 index 0000000000..75bed8accd --- /dev/null +++ b/Tools/message_id.py @@ -0,0 +1,108 @@ + +# Message identification constants + + +msg_id_map = { + 'actuator_armed': 1, + 'actuator_controls': 2, + 'actuator_direct': 3, + 'actuator_outputs': 4, + 'adc_report': 5, + 'airspeed': 6, + 'att_pos_mocap': 7, + 'battery_status': 8, + 'camera_capture': 9, + 'camera_trigger': 10, + 'collision_report': 11, + 'commander_state': 12, + 'control_state': 13, + 'cpuload': 14, + 'debug_key_value': 15, + 'differential_pressure': 16, + 'distance_sensor': 17, + 'ekf2_innovations': 18, + 'ekf2_replay': 19, + 'ekf2_timestamps': 20, + 'esc_report': 21, + 'esc_status': 22, + 'estimator_status': 23, + 'fence': 24, + 'fence_vertex': 25, + 'filtered_bottom_flow': 26, + 'follow_target': 27, + 'fw_pos_ctrl_status': 28, + 'geofence_result': 29, + 'gps_dump': 30, + 'gps_inject_data': 31, + 'hil_sensor': 32, + 'home_position': 33, + 'input_rc': 34, + 'led_control': 35, + 'log_message': 36, + 'manual_control_setpoint': 37, + 'mavlink_log': 38, + 'mc_att_ctrl_status': 39, + 'mission': 40, + 'mission_result': 41, + 'mount_orientation': 42, + 'multirotor_motor_limits': 43, + 'offboard_control_mode': 44, + 'optical_flow': 45, + 'output_pwm': 46, + 'parameter_update': 47, + 'position_setpoint': 48, + 'position_setpoint_triplet': 49, + 'pwm_input': 50, + 'qshell_req': 51, + 'rc_channels': 52, + 'rc_parameter_map': 53, + 'safety': 54, + 'satellite_info': 55, + 'sensor_accel': 56, + 'sensor_baro': 57, + 'sensor_combined': 58, + 'sensor_correction': 59, + 'sensor_gyro': 60, + 'sensor_mag': 61, + 'sensor_preflight': 62, + 'sensor_selection': 63, + 'servorail_status': 64, + 'subsystem_info': 65, + 'system_power': 66, + 'task_stack_info': 67, + 'tecs_status': 68, + 'telemetry_status': 69, + 'test_motor': 70, + 'time_offset': 71, + 'transponder_report': 72, + 'uavcan_parameter_request': 73, + 'uavcan_parameter_value': 74, + 'ulog_stream_ack': 75, + 'ulog_stream': 76, + 'vehicle_attitude': 77, + 'vehicle_attitude_setpoint': 78, + 'vehicle_command_ack': 79, + 'vehicle_command': 80, + 'vehicle_control_mode': 81, + 'vehicle_force_setpoint': 82, + 'vehicle_global_position': 83, + 'vehicle_global_velocity_setpoint': 84, + 'vehicle_gps_position': 85, + 'vehicle_land_detected': 86, + 'vehicle_local_position': 87, + 'vehicle_local_position_setpoint': 88, + 'vehicle_rates_setpoint': 89, + 'vehicle_roi': 90, + 'vehicle_status_flags': 91, + 'vehicle_status': 92, + 'vtol_vehicle_status': 93, + 'wind_estimate': 94, +} + +def message_id(message): + """ + Get id of a message + """ + if message in msg_id_map: + return msg_id_map[message] + return 0 diff --git a/Tools/px_generate_uorb_topic_files.py b/Tools/px_generate_uorb_topic_files.py index 311eaa38c1..0c8ba8c6e9 100755 --- a/Tools/px_generate_uorb_topic_files.py +++ b/Tools/px_generate_uorb_topic_files.py @@ -42,8 +42,8 @@ import os import shutil import filecmp import argparse - import sys + px4_tools_dir = os.path.dirname(os.path.abspath(__file__)) sys.path.append(px4_tools_dir + "/genmsg/src") sys.path.append(px4_tools_dir + "/gencpp/src") @@ -82,7 +82,12 @@ OUTPUT_FILE_EXT = ['.h', '.cpp'] INCL_DEFAULT = ['std_msgs:./msg/std_msgs'] PACKAGE = 'px4' TOPICS_TOKEN = '# TOPICS ' +IDL_TEMPLATE_FILE = 'msg.idl.template' +class MsgScope: + NONE = 0 + SEND = 1 + RECEIVE = 2 def get_multi_topics(filename): """ @@ -141,6 +146,102 @@ def generate_output_from_file(format_idx, filename, outputdir, templatedir, incl return generate_by_template(output_file, template_file, em_globals) +def generate_idl_file(filename_msg, outputdir, templatedir, includepath): + """ + Generates an .idl from .msg file + """ + em_globals = get_em_globals(filename_msg, includepath, MsgScope.NONE) + spec_short_name = em_globals["spec"].short_name + + # Make sure output directory exists: + if not os.path.isdir(outputdir): + os.makedirs(outputdir) + + template_file = os.path.join(templatedir, IDL_TEMPLATE_FILE) + output_file = os.path.join(outputdir, IDL_TEMPLATE_FILE.replace("msg.idl.template", str(spec_short_name + "_.idl"))) + + return generate_by_template(output_file, template_file, em_globals) + +def generate_uRTPS_general(filename_send_msgs, filename_received_msgs, + outputdir, templatedir, includepath, template_name): + """ + Generates source file by UART msg content + """ + em_globals_list = [] + if filename_send_msgs: + em_globals_list.extend([get_em_globals(f, includepath, MsgScope.SEND) for f in filename_send_msgs]) + + if filename_received_msgs: + em_globals_list.extend([get_em_globals(f, includepath, MsgScope.RECEIVE) for f in filename_received_msgs]) + + merged_em_globals = merge_em_globals_list(em_globals_list) + # Make sure output directory exists: + if not os.path.isdir(outputdir): + os.makedirs(outputdir) + + template_file = os.path.join(templatedir, template_name) + output_file = os.path.join(outputdir, template_name.replace(".template", "")) + + return generate_by_template(output_file, template_file, merged_em_globals) + +def generate_topic_file(filename_msg, outputdir, templatedir, includepath, template_name): + """ + Generates an .idl from .msg file + """ + em_globals = get_em_globals(filename_msg, includepath, MsgScope.NONE) + spec_short_name = em_globals["spec"].short_name + + # Make sure output directory exists: + if not os.path.isdir(outputdir): + os.makedirs(outputdir) + + template_file = os.path.join(templatedir, template_name) + output_file = os.path.join(outputdir, spec_short_name + "_" + template_name.replace(".template", "")) + + return generate_by_template(output_file, template_file, em_globals) + +def get_em_globals(filename_msg, includepath, scope): + """ + Generates em globals dictionary + """ + msg_context = genmsg.msg_loader.MsgContext.create_default() + full_type_name = genmsg.gentools.compute_full_type_name(PACKAGE, os.path.basename(filename_msg)) + spec = genmsg.msg_loader.load_msg_from_file(msg_context, filename_msg, full_type_name) + topics = get_multi_topics(filename_msg) + if includepath: + search_path = genmsg.command_line.includepath_to_dict(includepath) + else: + search_path = {} + genmsg.msg_loader.load_depends(msg_context, spec, search_path) + md5sum = genmsg.gentools.compute_md5(msg_context, spec) + if len(topics) == 0: + topics.append(spec.short_name) + em_globals = { + "file_name_in": filename_msg, + "md5sum": md5sum, + "search_path": search_path, + "msg_context": msg_context, + "spec": spec, + "topics": topics, + "scope": scope + } + + return em_globals + +def merge_em_globals_list(em_globals_list): + """ + Merges a list of em_globals to a single dictionary where each attribute is a list + """ + if len(em_globals_list) < 1: + return {} + + merged_em_globals = {} + for name in em_globals_list[0]: + merged_em_globals[name] = [em_globals[name] for em_globals in em_globals_list] + + return merged_em_globals + + def generate_by_template(output_file, template_file, em_globals): """ @@ -151,7 +252,7 @@ def generate_by_template(output_file, template_file, em_globals): folder_name = os.path.dirname(output_file) if not os.path.exists(folder_name): os.makedirs(folder_name) - + ofile = open(output_file, 'w') # todo, reuse interpreter interpreter = em.Interpreter(output=ofile, globals=em_globals, options={em.RAW_OPT:True,em.BUFFERED_OPT:True}) @@ -268,7 +369,7 @@ def generate_topics_list_file(msgdir, outputdir, templatedir): tl_template_file = os.path.join(templatedir, TOPICS_LIST_TEMPLATE_FILE) tl_out_file = os.path.join(outputdir, TOPICS_LIST_TEMPLATE_FILE.replace(".template", "")) generate_by_template(tl_out_file, tl_template_file, tl_globals) - + def generate_topics_list_file_from_files(files, outputdir, templatedir): # generate cpp file with topics list filenames = [os.path.basename(p) for p in files if os.path.basename(p).endswith(".msg")] diff --git a/Tools/px_generate_uorb_topic_helper.py b/Tools/px_generate_uorb_topic_helper.py index 9a28b8a2eb..7f55b0ee6a 100644 --- a/Tools/px_generate_uorb_topic_helper.py +++ b/Tools/px_generate_uorb_topic_helper.py @@ -23,6 +23,36 @@ type_map = { 'char': 'char', } +type_serialize_map = { + 'int8': 'SignedChar', + 'int16': 'Short', + 'int32': 'Int', + 'int64': 'Long', + 'uint8': 'UnsignedChar', + 'uint16': 'UnsignedShort', + 'uint32': 'UnsignedInt', + 'uint64': 'UnsignedLong', + 'float32': 'Float', + 'float64': 'Double', + 'bool': 'Bool', + 'char': 'Char', +} + +type_idl_map = { + 'int8': 'octet', + 'int16': 'short', + 'int32': 'long', + 'int64': 'long long', + 'uint8': 'octet', + 'uint16': 'unsigned short', + 'uint32': 'unsigned long', + 'uint64': 'unsigned long long', + 'float32': 'float', + 'float64': 'double', + 'bool': 'boolean', + 'char': 'char', +} + msgtype_size_map = { 'int8': 1, 'int16': 2, diff --git a/cmake/configs/nuttx_aerocore2_default.cmake b/cmake/configs/nuttx_aerocore2_default.cmake index cb5daaf240..835b762c18 100644 --- a/cmake/configs/nuttx_aerocore2_default.cmake +++ b/cmake/configs/nuttx_aerocore2_default.cmake @@ -131,6 +131,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_aerofc-v1_default.cmake b/cmake/configs/nuttx_aerofc-v1_default.cmake index af13fa6f9a..446bc8ce56 100644 --- a/cmake/configs/nuttx_aerofc-v1_default.cmake +++ b/cmake/configs/nuttx_aerofc-v1_default.cmake @@ -108,6 +108,7 @@ set(config_module_list lib/DriverFramework/framework lib/rc platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_auav-x21_default.cmake b/cmake/configs/nuttx_auav-x21_default.cmake index 52ded46519..29a042c168 100644 --- a/cmake/configs/nuttx_auav-x21_default.cmake +++ b/cmake/configs/nuttx_auav-x21_default.cmake @@ -152,6 +152,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_crazyflie_default.cmake b/cmake/configs/nuttx_crazyflie_default.cmake index 3d8fcb339e..b23784892a 100644 --- a/cmake/configs/nuttx_crazyflie_default.cmake +++ b/cmake/configs/nuttx_crazyflie_default.cmake @@ -100,6 +100,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_esc35-v1_default.cmake b/cmake/configs/nuttx_esc35-v1_default.cmake index 63eca8132e..b8a10fb25a 100644 --- a/cmake/configs/nuttx_esc35-v1_default.cmake +++ b/cmake/configs/nuttx_esc35-v1_default.cmake @@ -76,6 +76,7 @@ set(config_module_list platforms/nuttx platforms/common platforms/nuttx/px4_layer + lib/micro-CDR ) diff --git a/cmake/configs/nuttx_mindpx-v2_default.cmake b/cmake/configs/nuttx_mindpx-v2_default.cmake index 2ef5efb273..3fc342be42 100644 --- a/cmake/configs/nuttx_mindpx-v2_default.cmake +++ b/cmake/configs/nuttx_mindpx-v2_default.cmake @@ -156,6 +156,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake b/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake index 59f352a2eb..74b38b787a 100644 --- a/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake +++ b/cmake/configs/nuttx_px4-stm32f4discovery_default.cmake @@ -48,6 +48,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_px4cannode-v1_default.cmake b/cmake/configs/nuttx_px4cannode-v1_default.cmake index 3df9a3ec90..73f476ab32 100644 --- a/cmake/configs/nuttx_px4cannode-v1_default.cmake +++ b/cmake/configs/nuttx_px4cannode-v1_default.cmake @@ -67,6 +67,7 @@ set(config_module_list platforms/nuttx platforms/common platforms/nuttx/px4_layer + lib/micro-CDR ) diff --git a/cmake/configs/nuttx_px4esc-v1_default.cmake b/cmake/configs/nuttx_px4esc-v1_default.cmake index 6c146318d2..e5414a493e 100644 --- a/cmake/configs/nuttx_px4esc-v1_default.cmake +++ b/cmake/configs/nuttx_px4esc-v1_default.cmake @@ -76,6 +76,7 @@ set(config_module_list platforms/common platforms/nuttx/px4_layer modules/uORB + lib/micro-CDR ) diff --git a/cmake/configs/nuttx_px4fmu-v1_default.cmake b/cmake/configs/nuttx_px4fmu-v1_default.cmake index b0a1cfb46d..a1565aeb64 100644 --- a/cmake/configs/nuttx_px4fmu-v1_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v1_default.cmake @@ -125,6 +125,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_px4fmu-v2_default.cmake b/cmake/configs/nuttx_px4fmu-v2_default.cmake index 6e278e6cb6..a72f82defe 100644 --- a/cmake/configs/nuttx_px4fmu-v2_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v2_default.cmake @@ -155,6 +155,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_px4fmu-v2_test.cmake b/cmake/configs/nuttx_px4fmu-v2_test.cmake index e828aac415..b0671952df 100644 --- a/cmake/configs/nuttx_px4fmu-v2_test.cmake +++ b/cmake/configs/nuttx_px4fmu-v2_test.cmake @@ -150,6 +150,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_px4fmu-v3_default.cmake b/cmake/configs/nuttx_px4fmu-v3_default.cmake index f13544f8db..bbd1b5e907 100644 --- a/cmake/configs/nuttx_px4fmu-v3_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v3_default.cmake @@ -159,6 +159,7 @@ set(config_module_list lib/tailsitter_recovery lib/terrain_estimation lib/version + lib/micro-CDR # # Platform diff --git a/cmake/configs/nuttx_px4fmu-v4_default.cmake b/cmake/configs/nuttx_px4fmu-v4_default.cmake index 72c80de329..2bf7d52bfd 100644 --- a/cmake/configs/nuttx_px4fmu-v4_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v4_default.cmake @@ -141,6 +141,9 @@ set(config_module_list modules/uORB modules/dataman + # micro RTPS + modules/micrortps_bridge/micrortps_client + # # Libraries # @@ -161,6 +164,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common @@ -203,6 +207,17 @@ set(config_module_list examples/ekf_att_pos_estimator ) +set(GENERATE_RTPS_BRIDGE on) + +set(config_rtps_send_topics + sensor_combined + ) + +set(config_rtps_receive_topics + sensor_baro + ) + + set(config_extra_builtin_cmds serdis sercon diff --git a/cmake/configs/nuttx_px4fmu-v4pro_default.cmake b/cmake/configs/nuttx_px4fmu-v4pro_default.cmake index 7b2c72f0eb..49178c5556 100644 --- a/cmake/configs/nuttx_px4fmu-v4pro_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v4pro_default.cmake @@ -160,6 +160,7 @@ set(config_module_list lib/tailsitter_recovery lib/terrain_estimation lib/version + lib/micro-CDR # # Platform diff --git a/cmake/configs/nuttx_px4fmu-v5_default.cmake b/cmake/configs/nuttx_px4fmu-v5_default.cmake index 0886290320..6acfaa899e 100644 --- a/cmake/configs/nuttx_px4fmu-v5_default.cmake +++ b/cmake/configs/nuttx_px4fmu-v5_default.cmake @@ -159,6 +159,7 @@ set(config_module_list lib/tailsitter_recovery lib/terrain_estimation lib/version + lib/micro-CDR # # Platform diff --git a/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake b/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake index 1cfe85bc2c..6f2a1f4570 100644 --- a/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake +++ b/cmake/configs/nuttx_px4nucleoF767ZI-v1_default.cmake @@ -139,6 +139,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/nuttx_tap-v1_default.cmake b/cmake/configs/nuttx_tap-v1_default.cmake index b53f0b331c..2e3e24ed40 100644 --- a/cmake/configs/nuttx_tap-v1_default.cmake +++ b/cmake/configs/nuttx_tap-v1_default.cmake @@ -106,6 +106,7 @@ set(config_module_list lib/version lib/DriverFramework/framework platforms/nuttx + lib/micro-CDR # had to add for cmake, not sure why wasn't in original config platforms/common diff --git a/cmake/configs/posix_bebop_default.cmake b/cmake/configs/posix_bebop_default.cmake index 638f88a0b3..23148c25f1 100644 --- a/cmake/configs/posix_bebop_default.cmake +++ b/cmake/configs/posix_bebop_default.cmake @@ -88,6 +88,7 @@ set(config_module_list lib/tailsitter_recovery lib/version lib/DriverFramework/framework + lib/micro-CDR # # POSIX diff --git a/cmake/configs/posix_eagle_hil.cmake b/cmake/configs/posix_eagle_hil.cmake index fc08ae92ee..0d4bc2c9dd 100644 --- a/cmake/configs/posix_eagle_hil.cmake +++ b/cmake/configs/posix_eagle_hil.cmake @@ -47,6 +47,7 @@ set(config_module_list lib/conversion lib/version lib/DriverFramework/framework + lib/micro-CDR platforms/common platforms/posix/px4_layer diff --git a/cmake/configs/posix_eagle_muorb.cmake b/cmake/configs/posix_eagle_muorb.cmake index a04d645e0f..dbcab7785b 100644 --- a/cmake/configs/posix_eagle_muorb.cmake +++ b/cmake/configs/posix_eagle_muorb.cmake @@ -19,6 +19,7 @@ set(config_module_list modules/uORB lib/DriverFramework/framework + lib/micro-CDR platforms/posix/px4_layer platforms/posix/work_queue diff --git a/cmake/configs/posix_ocpoc_cross.cmake b/cmake/configs/posix_ocpoc_cross.cmake index 75ccef93b3..3b4056cc29 100644 --- a/cmake/configs/posix_ocpoc_cross.cmake +++ b/cmake/configs/posix_ocpoc_cross.cmake @@ -93,6 +93,7 @@ set(config_module_list lib/DriverFramework/framework lib/rc lib/led + lib/micro-CDR # # POSIX diff --git a/cmake/configs/posix_rpi_common.cmake b/cmake/configs/posix_rpi_common.cmake index 5804660d96..fa79eab85f 100644 --- a/cmake/configs/posix_rpi_common.cmake +++ b/cmake/configs/posix_rpi_common.cmake @@ -101,6 +101,7 @@ set(config_module_list lib/tailsitter_recovery lib/version lib/DriverFramework/framework + lib/micro-CDR # # POSIX diff --git a/cmake/configs/posix_sdflight_default.cmake b/cmake/configs/posix_sdflight_default.cmake index 3a0969929b..6a0e81f5a6 100644 --- a/cmake/configs/posix_sdflight_default.cmake +++ b/cmake/configs/posix_sdflight_default.cmake @@ -65,6 +65,9 @@ set(config_module_list modules/commander modules/navigator + # micro RTPS + modules/micrortps_bridge/micrortps_client + lib/controllib lib/mathlib lib/mathlib/math/filter @@ -78,6 +81,7 @@ set(config_module_list lib/tailsitter_recovery lib/version lib/DriverFramework/framework + lib/micro-CDR platforms/common platforms/posix/px4_layer diff --git a/cmake/configs/posix_sdflight_legacy.cmake b/cmake/configs/posix_sdflight_legacy.cmake index d6685e2123..8d98adfbcb 100644 --- a/cmake/configs/posix_sdflight_legacy.cmake +++ b/cmake/configs/posix_sdflight_legacy.cmake @@ -57,6 +57,9 @@ set(config_module_list modules/commander modules/navigator + # micro RTPS + modules/micrortps_bridge/micrortps_client + lib/controllib lib/mathlib lib/mathlib/math/filter @@ -70,6 +73,7 @@ set(config_module_list lib/tailsitter_recovery lib/version lib/DriverFramework/framework + lib/micro-CDR platforms/common platforms/posix/px4_layer diff --git a/cmake/configs/posix_sitl_default.cmake b/cmake/configs/posix_sitl_default.cmake index 77c1471d09..66e7ee796c 100644 --- a/cmake/configs/posix_sitl_default.cmake +++ b/cmake/configs/posix_sitl_default.cmake @@ -104,6 +104,9 @@ set(config_module_list modules/systemlib/mixer modules/uORB + # micro RTPS + modules/micrortps_bridge/micrortps_client + # # Libraries # @@ -171,6 +174,9 @@ set(config_module_list # EKF examples/ekf_att_pos_estimator + + # micro-RTPS + lib/micro-CDR ) set(config_extra_builtin_cmds @@ -178,6 +184,16 @@ set(config_extra_builtin_cmds sercon ) +set(GENERATE_RTPS_BRIDGE on) + +set(config_rtps_send_topics + sensor_baro + ) + +set(config_rtps_receive_topics + sensor_combined + ) + # Default config_sitl_rcS_dir (posix_sitl_default), this is overwritten later # for the config posix_sitl_efk2 and set again, explicitly, for posix_sitl_lpe, # which are based on posix_sitl_default. diff --git a/cmake/configs/posix_sitl_replay.cmake b/cmake/configs/posix_sitl_replay.cmake index a1878ab068..1ee9b97f01 100644 --- a/cmake/configs/posix_sitl_replay.cmake +++ b/cmake/configs/posix_sitl_replay.cmake @@ -28,6 +28,7 @@ set(config_module_list lib/geo_lookup lib/version lib/DriverFramework/framework + lib/micro-CDR ) set(config_extra_builtin_cmds diff --git a/cmake/configs/qurt_eagle_hello.cmake b/cmake/configs/qurt_eagle_hello.cmake index f8fd30f33b..bb009f7f86 100644 --- a/cmake/configs/qurt_eagle_hello.cmake +++ b/cmake/configs/qurt_eagle_hello.cmake @@ -34,6 +34,11 @@ set(config_module_list modules/systemlib/param modules/systemlib modules/uORB + + # + # Libraries + # + lib/micro-CDR # # QuRT port diff --git a/cmake/configs/qurt_eagle_hil.cmake b/cmake/configs/qurt_eagle_hil.cmake index bc9bfbc124..e085aadeb3 100644 --- a/cmake/configs/qurt_eagle_hil.cmake +++ b/cmake/configs/qurt_eagle_hil.cmake @@ -73,6 +73,7 @@ set(config_module_list lib/controllib lib/version lib/DriverFramework/framework + lib/micro-CDR # # QuRT port diff --git a/cmake/configs/qurt_eagle_muorb.cmake b/cmake/configs/qurt_eagle_muorb.cmake index 7f34764a32..bd8bc0fe8a 100644 --- a/cmake/configs/qurt_eagle_muorb.cmake +++ b/cmake/configs/qurt_eagle_muorb.cmake @@ -45,6 +45,7 @@ set(config_module_list lib/conversion lib/version lib/DriverFramework/framework + lib/micro-CDR # # QuRT port diff --git a/cmake/configs/qurt_eagle_test.cmake b/cmake/configs/qurt_eagle_test.cmake index c046420a6e..46f979d3bc 100644 --- a/cmake/configs/qurt_eagle_test.cmake +++ b/cmake/configs/qurt_eagle_test.cmake @@ -43,6 +43,7 @@ set(config_module_list lib/mathlib/math/filter lib/conversion lib/DriverFramework/framework + lib/micro-CDR # # QuRT port diff --git a/cmake/configs/qurt_eagle_travis.cmake b/cmake/configs/qurt_eagle_travis.cmake index 09a6538847..b6f4b58993 100644 --- a/cmake/configs/qurt_eagle_travis.cmake +++ b/cmake/configs/qurt_eagle_travis.cmake @@ -79,6 +79,7 @@ set(config_module_list lib/tailsitter_recovery lib/version lib/DriverFramework/framework + lib/micro-CDR # # QuRT port diff --git a/cmake/configs/qurt_sdflight_default.cmake b/cmake/configs/qurt_sdflight_default.cmake index 2fbd8c2946..a1b65c01f8 100644 --- a/cmake/configs/qurt_sdflight_default.cmake +++ b/cmake/configs/qurt_sdflight_default.cmake @@ -94,6 +94,7 @@ set(config_module_list lib/rc lib/version lib/DriverFramework/framework + lib/micro-CDR # # QuRT port diff --git a/cmake/configs/qurt_sdflight_legacy.cmake b/cmake/configs/qurt_sdflight_legacy.cmake index 24e0da9e82..25401b9d13 100644 --- a/cmake/configs/qurt_sdflight_legacy.cmake +++ b/cmake/configs/qurt_sdflight_legacy.cmake @@ -93,6 +93,7 @@ set(config_module_list lib/tailsitter_recovery lib/version lib/DriverFramework/framework + lib/micro-CDR # # QuRT port diff --git a/msg/templates/uorb/microRTPS_client.cpp.template b/msg/templates/uorb/microRTPS_client.cpp.template new file mode 100644 index 0000000000..ad902cfa5b --- /dev/null +++ b/msg/templates/uorb/microRTPS_client.cpp.template @@ -0,0 +1,406 @@ +@############################################### +@# +@# EmPy template for generating microRTPS_client.cpp file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@# - multi_topics (List) list of all multi-topic names +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ +from px_generate_uorb_topic_files import MsgScope # this is in Tools/ +from message_id import * # this is in Tools/ + +topic_names = [single_spec.short_name for single_spec in spec] +send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND] +recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE] + +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "microRTPS_transport.h" + +@[for topic in list(set(topic_names))]@ +#include +@[end for]@ + +#define BUFFER_SIZE 1024 +#define UPDATE_TIME_MS 0 +#define LOOPS 10000 +#define SLEEP_MS 1 +#define BAUDRATE 460800 +#define DEVICE "/dev/ttyACM0" +#define POLL_MS 1 +#define DEFAULT_RECV_PORT 2019 +#define DEFAULT_SEND_PORT 2020 + +extern "C" __EXPORT int micrortps_client_main(int argc, char *argv[]); +void* send(void *data); + +struct options { + enum class eTransports + { + UART, + UDP + }; + eTransports transport = options::eTransports::UART; + char device[64] = DEVICE; + int update_time_ms = UPDATE_TIME_MS; + int loops = LOOPS; + int sleep_ms = SLEEP_MS; + uint32_t baudrate = BAUDRATE; + int poll_ms = POLL_MS; + uint16_t recv_port = DEFAULT_RECV_PORT; + uint16_t send_port = DEFAULT_SEND_PORT; +} _options; + +static int _rtps_task = -1; +static bool _should_exit_task = false; +Transport_node *transport_node = nullptr; + +static void usage(const char *name) +{ + PX4_INFO("usage: %s start|stop [options]\n\n" + " -t [UART|UDP] Default UART\n" + " -d UART device. Default /dev/ttyACM0\n" + " -u Time in ms for uORB subscribed topics update. Default 0\n" + " -l How many iterations will this program have. -1 for infinite. Default 10000\n" + " -w Time in ms for which each iteration sleep. Default 1ms\n" + " -b UART device baudrate. Default 460800\n" + " -p Time in ms to poll over UART. Default 1ms\n" + " -r UDP port for receiving. Default 2019\n" + " -s UDP port for sending. Default 2020\n", + name); +} + +static int parse_options(int argc, char *argv[]) +{ + int ch; + int myoptind = 1; + const char *myoptarg = nullptr; + + while ((ch = px4_getopt(argc, argv, "t:d:u:l:w:b:p:r:s:", &myoptind, &myoptarg)) != EOF) + { + switch (ch) + { + case 't': _options.transport = strcmp(myoptarg, "UDP") == 0? + options::eTransports::UDP + :options::eTransports::UART; break; + case 'd': if (nullptr != myoptarg) strcpy(_options.device, myoptarg); break; + case 'u': _options.update_time_ms = strtol(myoptarg, nullptr, 10); break; + case 'l': _options.loops = strtol(myoptarg, nullptr, 10); break; + case 'w': _options.sleep_ms = strtol(myoptarg, nullptr, 10); break; + case 'b': _options.baudrate = strtoul(optarg, nullptr, 10); break; + case 'p': _options.poll_ms = strtol(optarg, nullptr, 10); break; + case 'r': _options.recv_port = strtoul(optarg, nullptr, 10); break; + case 's': _options.send_port = strtoul(optarg, nullptr, 10); break; + default: + usage(argv[1]); + return -1; + } + } + + return 0; +} + +@[if send_topics]@ +void* send(void*) +{ + char data_buffer[BUFFER_SIZE] = {}; + uint64_t sent = 0, total_sent = 0; + int loop = 0, read = 0; + uint32_t length = 0; + + /* subscribe to topics */ + int fds[@(len(send_topics))] = {}; + + // orb_set_interval statblish an update interval period in milliseconds. +@[for idx, topic in enumerate(send_topics)]@ + fds[@(idx)] = orb_subscribe(ORB_ID(@(topic))); + orb_set_interval(fds[@(idx)], _options.update_time_ms); +@[end for]@ + + // microBuffer to serialized using the user defined buffer + struct microBuffer microBufferWriter; + initStaticAlignedBuffer(data_buffer, BUFFER_SIZE, µBufferWriter); + // microCDR structs for managing the microBuffer + struct microCDR microCDRWriter; + initMicroCDR(µCDRWriter, µBufferWriter); + + struct timespec begin; + clock_gettime(0, &begin); + + while (!_should_exit_task) + { + bool updated; +@[for idx, topic in enumerate(send_topics)]@ + orb_check(fds[@(idx)], &updated); + if (updated) + { + // obtained data for the file descriptor + struct @(topic)_s data = {}; + // copy raw data into local buffer + orb_copy(ORB_ID(@(topic)), fds[@(idx)], &data); + serialize_@(topic)(&data, data_buffer, &length, µCDRWriter); + if (0 < (read = transport_node->write((char)@(message_id(topic)), data_buffer, length))) + { + total_sent += read; + ++sent; + } + } +@[end for]@ + + usleep(_options.sleep_ms*1000); + ++loop; + } + + struct timespec end; + clock_gettime(0, &end); + double elapsed_secs = double(end.tv_sec - begin.tv_sec) + double(end.tv_nsec - begin.tv_nsec)/double(1000000000); + printf("\nSENT: %lu messages in %d LOOPS, %llu bytes in %.03f seconds - %.02fKB/s\n", + (unsigned long)sent, loop, total_sent, elapsed_secs, (double)total_sent/(1000*elapsed_secs)); + + return nullptr; +} + +static int launch_send_thread(pthread_t &sender_thread) +{ + pthread_attr_t sender_thread_attr; + pthread_attr_init(&sender_thread_attr); + pthread_attr_setstacksize(&sender_thread_attr, PX4_STACK_ADJUSTED(4000)); + struct sched_param param; + (void)pthread_attr_getschedparam(&sender_thread_attr, ¶m); + param.sched_priority = SCHED_PRIORITY_DEFAULT; + (void)pthread_attr_setschedparam(&sender_thread_attr, ¶m); + pthread_create(&sender_thread, &sender_thread_attr, send, nullptr); + pthread_attr_destroy(&sender_thread_attr); + + return 0; +} +@[end if]@ + +static int micrortps_start(int argc, char *argv[]) +{ + if (0 > parse_options(argc, argv)) + { + printf("EXITING...\n"); + _rtps_task = -1; + return -1; + } + + switch (_options.transport) + { + case options::eTransports::UART: + { + transport_node = new UART_node(_options.device, _options.baudrate, _options.poll_ms); + printf("\nUART transport: device: %s; baudrate: %d; sleep: %dms; poll: %dms\n\n", + _options.device, _options.baudrate, _options.sleep_ms, _options.poll_ms); + } + break; + case options::eTransports::UDP: + { + transport_node = new UDP_node(_options.recv_port, _options.send_port); + printf("\nUDP transport: recv port: %u; send port: %u; sleep: %dms\n\n", + _options.recv_port, _options.send_port, _options.sleep_ms); + } + break; + default: + _rtps_task = -1; + printf("EXITING...\n"); + return -1; + } + + if (0 > transport_node->init()) + { + printf("EXITING...\n"); + _rtps_task = -1; + return -1; + } + + sleep(1); +@[if recv_topics]@ + + char data_buffer[BUFFER_SIZE] = {}; + int read = 0; + char topic_ID = 255; + + // Declare received topics +@[for topic in recv_topics]@ + struct @(topic)_s @(topic)_data; + orb_advert_t @(topic)_pub = nullptr; +@[end for]@ + + // microBuffer to deserialized using the user defined buffer + struct microBuffer microBufferReader; + initDeserializedAlignedBuffer(data_buffer, BUFFER_SIZE, µBufferReader); + // microCDR structs for managing the microBuffer + struct microCDR microCDRReader; + initMicroCDR(µCDRReader, µBufferReader); +@[end if]@ + + int total_read = 0; + uint32_t received = 0; + struct timespec begin; + clock_gettime(0, &begin); + int loop = 0; + _should_exit_task = false; +@[if send_topics]@ + + // create a thread for sending data to the simulator + pthread_t sender_thread; + launch_send_thread(sender_thread); +@[end if]@ + + while (!_should_exit_task) + { +@[if recv_topics]@ + while (0 < (read = transport_node->read(&topic_ID, data_buffer, BUFFER_SIZE))) + { + total_read += read; + switch (topic_ID) + { +@[for topic in recv_topics]@ + case @(message_id(topic)): + { + deserialize_@(topic)(&@(topic)_data, data_buffer, µCDRReader); + if (!@(topic)_pub) + @(topic)_pub = orb_advertise(ORB_ID(@(topic)), &@(topic)_data); + else + orb_publish(ORB_ID(@(topic)), @(topic)_pub, &@(topic)_data); + ++received; + } + break; +@[end for]@ + default: + printf("Unexpected topic ID\n"); + break; + } + } +@[end if]@ + + // loop forever if informed loop number is negative + if (_options.loops > 0 && loop >= _options.loops) break; + + usleep(_options.sleep_ms*1000); + ++loop; + } +@[if send_topics]@ + _should_exit_task = true; + pthread_join(sender_thread, 0); +@[end if]@ + + struct timespec end; + clock_gettime(0, &end); + double elapsed_secs = double(end.tv_sec - begin.tv_sec) + double(end.tv_nsec - begin.tv_nsec)/double(1000000000); + printf("RECEIVED: %lu messages in %d LOOPS, %d bytes in %.03f seconds - %.02fKB/s\n\n", + (unsigned long)received, loop, total_read, elapsed_secs, (double)total_read/(1000*elapsed_secs)); + + delete transport_node; + transport_node = nullptr; + PX4_INFO("exiting"); + fflush(stdout); + + _rtps_task = -1; + + return 0; +} + +int micrortps_client_main(int argc, char *argv[]) +{ + if (argc < 2) + { + usage(argv[0]); + return -1; + } + + if (!strcmp(argv[1], "start")) + { + if (_rtps_task != -1) + { + PX4_INFO("Already running"); + return -1; + } + + _rtps_task = px4_task_spawn_cmd("rtps", + SCHED_DEFAULT, + SCHED_PRIORITY_DEFAULT, + 4096, + (px4_main_t) micrortps_start, + (char *const *)argv); + + if (_rtps_task < 0) + { + PX4_WARN("Could not start task"); + _rtps_task = -1; + return -1; + } + + return 0; + } + + if (!strcmp(argv[1], "stop")) + { + if (_rtps_task == -1) + { + PX4_INFO("Not running"); + return -1; + } + + _should_exit_task = true; + if (nullptr != transport_node) transport_node->close(); + return 0; + } + + usage(argv[0]); + + return -1; +} diff --git a/msg/templates/uorb/msg.cpp.template b/msg/templates/uorb/msg.cpp.template index 86d151a5be..a6e60d9ba6 100644 --- a/msg/templates/uorb/msg.cpp.template +++ b/msg/templates/uorb/msg.cpp.template @@ -64,9 +64,11 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path) topic_fields = ["uint64_t timestamp"]+["%s %s" % (convert_type(field.type), field.name) for field in sorted_fields] }@ +#include +#include +#include #include - @# join all msg files in one line e.g: "float[3] position;float[3] velocity;bool armed" @# This is used for the logger constexpr char __orb_@(topic_name)_fields[] = "@( ";".join(topic_fields) );"; @@ -75,3 +77,99 @@ constexpr char __orb_@(topic_name)_fields[] = "@( ";".join(topic_fields) );"; ORB_DEFINE(@multi_topic, struct @uorb_struct, @(struct_size-padding_end_size), __orb_@(topic_name)_fields); @[end for] + +@################################################# +@# Searching for serialize function per each field +@################################################# +@{ + +def print_info(field): + print "type: ", field.type, "name: ", field.name, "base_type: ", \ + field.base_type, "field.is_array:", ('0', '1')[field.is_array], " array_len: ", field.array_len, \ + "is_builtin:", ('0', '1')[field.is_builtin], "is_header:", ('0', '1')[field.is_header] + +def print_level_info(fields): + for field in fields: + print_info(field) + if (not field.is_builtin): + print "\n" + children_fields = get_children_fields(field.base_type, search_path) + print_level_info(children_fields) + print "\n" + +def walk_through_parsed_fields(): + print_level_info(spec.parsed_fields()) + +def get_serialization_type_name(type_name): + if type_name in type_serialize_map: + return type_serialize_map[type_name] + else: + raise Exception("Type {0} not supported, add to type_serialize_map!".format(type_name)) + +def add_serialize_functions(fields, scope_name): + for field in fields: + if (not field.is_header): + if (field.is_builtin): + if (not field.is_array): + print "\tserialize"+str(get_serialization_type_name(field.type))+"(input->"+scope_name+str(field.name)+", microCDRWriter);" + else: + print "\tserialize"+str(get_serialization_type_name(field.base_type))+"Array(input->"+scope_name+str(field.name)+", "+str(field.array_len)+", microCDRWriter);" + else: + name = field.name + children_fields = get_children_fields(field.base_type, search_path) + if (scope_name): name = scope_name + name + if (not field.is_array): + add_serialize_functions(children_fields, name + '.') + else: + for i in xrange(field.array_len): + add_serialize_functions(children_fields, name + ('[%d].' %i)) + +def add_deserialize_functions(fields, scope_name): + for field in fields: + if (not field.is_header): + if (field.is_builtin): + if (not field.is_array): + print "\tdeserialize"+str(get_serialization_type_name(field.type))+"(&output->"+scope_name+str(field.name)+", microCDRReader);" + else: + for i in xrange(field.array_len): + print "\tdeserialize"+str(get_serialization_type_name(field.base_type))+"(&output->"+scope_name+str(field.name)+ str('[%d]' %i) +", microCDRReader);" + else: + name = field.name + children_fields = get_children_fields(field.base_type, search_path) + if (scope_name): name = scope_name + name + if (not field.is_array): + add_deserialize_functions(children_fields, name + '.') + else: + for i in xrange(field.array_len): + add_deserialize_functions(children_fields, name + ('[%d].' %i)) + +def add_code_to_serialize(): + # sort fields (using a stable sort) as in the declaration of the type + sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True) + add_serialize_functions(sorted_fields, "") + +def add_code_to_deserialize(): + # sort fields (using a stable sort) as in the declaration of the type + sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True) + add_deserialize_functions(sorted_fields, "") +}@ + +void serialize_@(topic_name)(const struct @(uorb_struct) *input, char *output, uint32_t *length, struct microCDR *microCDRWriter) +{ + if (nullptr == input || nullptr == output || nullptr == length || nullptr == microCDRWriter) return; + + resetStaticMicroCDRForSerialize(microCDRWriter); + +@add_code_to_serialize() + + (*length) = microCDRWriter->m_microBuffer->m_serializedBuffer; +} + +void deserialize_@(topic_name)(struct @(uorb_struct) *output, char *input, struct microCDR *microCDRReader) +{ + if (nullptr == output || nullptr == input || nullptr == microCDRReader) return; + + resetStaticMicroCDRForDeserialize(microCDRReader); + +@add_code_to_deserialize() +} \ No newline at end of file diff --git a/msg/templates/uorb/msg.h.template b/msg/templates/uorb/msg.h.template index ca22c4338e..b4d9d09e65 100644 --- a/msg/templates/uorb/msg.h.template +++ b/msg/templates/uorb/msg.h.template @@ -108,6 +108,8 @@ def print_parsed_fields(): print_field_def(field) }@ +struct microCDR; + #ifdef __cplusplus @#class @(uorb_struct) { struct __EXPORT @(uorb_struct) { @@ -118,6 +120,7 @@ struct @(uorb_struct) { @# timestamp at the beginning of each topic is required for logger uint64_t timestamp; // required for logger @print_parsed_fields() + #ifdef __cplusplus @# Constants again c++-ified @{ @@ -134,6 +137,10 @@ for constant in spec.constants: #endif }; + +void serialize_@(topic_name)(const struct @(uorb_struct) *input, char *output, uint32_t *length, struct microCDR *microCDRWriter); +void deserialize_@(topic_name)(struct @(uorb_struct) *output, char *input, struct microCDR *microCDRReader); + /* register this as object request broker structure */ @[for multi_topic in topics]@ ORB_DECLARE(@multi_topic); diff --git a/msg/templates/urtps/Publisher.cxx.template b/msg/templates/urtps/Publisher.cxx.template new file mode 100644 index 0000000000..77125c08dd --- /dev/null +++ b/msg/templates/urtps/Publisher.cxx.template @@ -0,0 +1,154 @@ +@############################################### +@# +@# EmPy template for generating _uRTPS_UART.cpp file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@# - multi_topics (List) list of all multi-topic names +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ + +topic = spec.short_name +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/*! + * @@file @(topic)_Publisher.cpp + * This file contains the implementation of the publisher functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#include +#include +#include +#include + +#include + +#include + +#include "@(topic)_Publisher.h" + + +@(topic)_Publisher::@(topic)_Publisher() : mp_participant(nullptr), mp_publisher(nullptr) {} + +@(topic)_Publisher::~@(topic)_Publisher() { Domain::removeParticipant(mp_participant);} + +bool @(topic)_Publisher::init() +{ + // Create RTPSParticipant + + ParticipantAttributes PParam; + PParam.rtps.builtin.domainId = 0; + PParam.rtps.builtin.leaseDuration = c_TimeInfinite; + PParam.rtps.setName("Participant_publisher"); //You can put here the name you want + mp_participant = Domain::createParticipant(PParam); + if(mp_participant == nullptr) + return false; + + //Register the type + + Domain::registerType(mp_participant,(TopicDataType*) &myType); + + // Create Publisher + + PublisherAttributes Wparam; + Wparam.topic.topicKind = NO_KEY; + Wparam.topic.topicDataType = myType.getName(); //This type MUST be registered + Wparam.topic.topicName = "@(topic)_PubSubTopic"; + mp_publisher = Domain::createPublisher(mp_participant,Wparam,(PublisherListener*)&m_listener); + if(mp_publisher == nullptr) + return false; + //std::cout << "Publisher created, waiting for Subscribers." << std::endl; + return true; +} + +void @(topic)_Publisher::PubListener::onPublicationMatched(Publisher* pub,MatchingInfo& info) +{ + if (info.status == MATCHED_MATCHING) + { + n_matched++; + std::cout << "Publisher matched" << std::endl; + } + else + { + n_matched--; + std::cout << "Publisher unmatched" << std::endl; + } +} + +void @(topic)_Publisher::run() +{ + while(m_listener.n_matched == 0) + { + eClock::my_sleep(250); // Sleep 250 ms + } + + // Publication code + + @(topic)_ st; + + /* Initialize your structure here */ + + int msgsent = 0; + char ch = 'y'; + do + { + if(ch == 'y') + { + mp_publisher->write(&st); ++msgsent; + std::cout << "Sending sample, count=" << msgsent << ", send another sample?(y-yes,n-stop): "; + } + else if(ch == 'n') + { + std::cout << "Stopping execution " << std::endl; + break; + } + else + { + std::cout << "Command " << ch << " not recognized, please enter \"y/n\":"; + } + }while(std::cin >> ch); +} + +void @(topic)_Publisher::publish(@(topic)_* st) +{ + mp_publisher->write(st); +} diff --git a/msg/templates/urtps/Publisher.h.template b/msg/templates/urtps/Publisher.h.template new file mode 100644 index 0000000000..6776562442 --- /dev/null +++ b/msg/templates/urtps/Publisher.h.template @@ -0,0 +1,92 @@ +@############################################### +@# +@# EmPy template for generating _uRTPS_UART.cpp file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@# - multi_topics (List) list of all multi-topic names +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ + +topic = spec.short_name +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/*! + * @@file @(topic)_Publisher.h + * This header file contains the declaration of the publisher functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _@(topic)__PUBLISHER_H_ +#define _@(topic)__PUBLISHER_H_ + +#include +#include + +#include "@(topic)_PubSubTypes.h" + +using namespace eprosima::fastrtps; + +class @(topic)_Publisher +{ +public: + @(topic)_Publisher(); + virtual ~@(topic)_Publisher(); + bool init(); + void run(); + void publish(@(topic)_* st); +private: + Participant *mp_participant; + Publisher *mp_publisher; + + class PubListener : public PublisherListener + { + public: + PubListener() : n_matched(0){}; + ~PubListener(){}; + void onPublicationMatched(Publisher* pub,MatchingInfo& info); + int n_matched; + } m_listener; + @(topic)_PubSubType myType; +}; + +#endif // _@(topic)__PUBLISHER_H_ \ No newline at end of file diff --git a/msg/templates/urtps/RtpsTopics.cxx.template b/msg/templates/urtps/RtpsTopics.cxx.template new file mode 100644 index 0000000000..8b433c90e3 --- /dev/null +++ b/msg/templates/urtps/RtpsTopics.cxx.template @@ -0,0 +1,159 @@ +@############################################### +@# +@# EmPy template for generating RtpsTopics.cxx file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ +from px_generate_uorb_topic_files import MsgScope # this is in Tools/ +from message_id import * # this is in Tools/ + +topic_names = [single_spec.short_name for single_spec in spec] +send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND] +recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE] +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "RtpsTopics.h" + +bool RtpsTopics::init() +{ +@[if recv_topics]@ + // Initialise subscribers +@[for topic in recv_topics]@ + if (_@(topic)_sub.init()) { + std::cout << "@(topic) subscriber started" << std::endl; + } else { + std::cout << "ERROR starting @(topic) subscriber" << std::endl; + return false; + } + +@[end for]@ +@[end if]@ +@[if send_topics]@ + // Initialise publishers +@[for topic in send_topics]@ + if (_@(topic)_pub.init()) { + std::cout << "@(topic) publisher started" << std::endl; + } else { + std::cout << "ERROR starting @(topic) publisher" << std::endl; + return false; + } + +@[end for]@ +@[end if]@ + return true; +} + +@[if send_topics]@ +void RtpsTopics::publish(char topic_ID, char data_buffer[], size_t len) +{ + switch (topic_ID) + { +@[for topic in send_topics]@ + case @(message_id(topic)): // @(topic) + { + @(topic)_ st; + eprosima::fastcdr::FastBuffer cdrbuffer(data_buffer, len); + eprosima::fastcdr::Cdr cdr_des(cdrbuffer); + st.deserialize(cdr_des); + _@(topic)_pub.publish(&st); + } + break; +@[end for]@ + default: + printf("Unexpected topic ID to publish\n"); + break; + } +} +@[end if]@ +@[if recv_topics]@ + +bool RtpsTopics::hasMsg(char *topic_ID) +{ + if (nullptr == topic_ID) return false; + + *topic_ID = 0; + while (_next_sub_idx < @(len(recv_topics)) && 0 == *topic_ID) + { + switch (_sub_topics[_next_sub_idx]) + { +@[for topic in recv_topics]@ + case @(message_id(topic)): if (_@(topic)_sub.hasMsg()) *topic_ID = @(message_id(topic)); break; +@[end for]@ + default: + printf("Unexpected topic ID to check hasMsg\n"); + break; + } + _next_sub_idx++; + } + + if (0 == *topic_ID) + { + _next_sub_idx = 0; + return false; + } + + return true; +} + +bool RtpsTopics::getMsg(const char topic_ID, eprosima::fastcdr::Cdr &scdr) +{ + bool ret = false; + switch (topic_ID) + { +@[for topic in recv_topics]@ + case @(message_id(topic)): // @(topic) + if (_@(topic)_sub.hasMsg()) + { + @(topic)_ msg = _@(topic)_sub.getMsg(); + msg.serialize(scdr); + ret = true; + } + break; +@[end for]@ + default: + printf("Unexpected topic ID '%hhu' to getMsg\n", topic_ID); + break; + } + + return ret; +} +@[end if]@ diff --git a/msg/templates/urtps/RtpsTopics.h.template b/msg/templates/urtps/RtpsTopics.h.template new file mode 100644 index 0000000000..5d67a975d7 --- /dev/null +++ b/msg/templates/urtps/RtpsTopics.h.template @@ -0,0 +1,95 @@ +@############################################### +@# +@# EmPy template for generating RtpsTopics.h file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ +from px_generate_uorb_topic_files import MsgScope # this is in Tools/ +from message_id import * # this is in Tools/ + +topic_names = [single_spec.short_name for single_spec in spec] +send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND] +recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE] +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +@[for topic in send_topics]@ +#include "@(topic)_Publisher.h" +@[end for]@ +@[for topic in recv_topics]@ +#include "@(topic)_Subscriber.h" +@[end for]@ + +class RtpsTopics { +public: + bool init(); +@[if send_topics]@ + void publish(char topic_ID, char data_buffer[], size_t len); +@[end if]@ +@[if recv_topics]@ + bool hasMsg(char *topic_ID); + bool getMsg(const char topic_ID, eprosima::fastcdr::Cdr &scdr); +@[end if]@ + +private: +@[if send_topics]@ + // Publishers +@[for topic in send_topics]@ + @(topic)_Publisher _@(topic)_pub; +@[end for]@ +@[end if]@ + +@[if recv_topics]@ + // Subscribers +@[for topic in recv_topics]@ + @(topic)_Subscriber _@(topic)_sub; +@[end for]@ + + unsigned _next_sub_idx = 0; + char _sub_topics[@(len(recv_topics))] = { +@[for topic in recv_topics]@ + @(message_id(topic)), // @(topic) +@[end for]@ + }; +@[end if]@ +}; diff --git a/msg/templates/urtps/Subscriber.cxx.template b/msg/templates/urtps/Subscriber.cxx.template new file mode 100644 index 0000000000..686943d93f --- /dev/null +++ b/msg/templates/urtps/Subscriber.cxx.template @@ -0,0 +1,146 @@ +@############################################### +@# +@# EmPy template for generating _uRTPS_UART.cpp file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@# - multi_topics (List) list of all multi-topic names +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ + +topic = spec.short_name +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/*! + * @@file @(topic)_Subscriber.cpp + * This file contains the implementation of the subscriber functions. + * + * This file was generated by the tool fastcdrgen. + */ + +#include +#include +#include +#include + +#include + +#include "@(topic)_Subscriber.h" + + +@(topic)_Subscriber::@(topic)_Subscriber() : mp_participant(nullptr), mp_subscriber(nullptr) {} + +@(topic)_Subscriber::~@(topic)_Subscriber() { Domain::removeParticipant(mp_participant);} + +bool @(topic)_Subscriber::init() +{ + // Create RTPSParticipant + + ParticipantAttributes PParam; + PParam.rtps.builtin.domainId = 0; //MUST BE THE SAME AS IN THE PUBLISHER + PParam.rtps.builtin.leaseDuration = c_TimeInfinite; + PParam.rtps.setName("Participant_subscriber"); //You can put the name you want + mp_participant = Domain::createParticipant(PParam); + if(mp_participant == nullptr) + return false; + + //Register the type + + Domain::registerType(mp_participant,(TopicDataType*) &myType); + + // Create Subscriber + + SubscriberAttributes Rparam; + Rparam.topic.topicKind = NO_KEY; + Rparam.topic.topicDataType = myType.getName(); //Must be registered before the creation of the subscriber + Rparam.topic.topicName = "@(topic)_PubSubTopic"; + mp_subscriber = Domain::createSubscriber(mp_participant,Rparam,(SubscriberListener*)&m_listener); + if(mp_subscriber == nullptr) + return false; + return true; +} + +void @(topic)_Subscriber::SubListener::onSubscriptionMatched(Subscriber* sub,MatchingInfo& info) +{ + if (info.status == MATCHED_MATCHING) + { + n_matched++; + std::cout << "Subscriber matched" << std::endl; + } + else + { + n_matched--; + std::cout << "Subscriber unmatched" << std::endl; + } +} + +void @(topic)_Subscriber::SubListener::onNewDataMessage(Subscriber* sub) +{ + // Take data + if(sub->takeNextData(&msg, &m_info)) + { + if(m_info.sampleKind == ALIVE) + { + // Print your structure data here. + ++n_msg; + //std::cout << "Sample received, count=" << n_msg << std::endl; + has_msg = true; + + } + } +} + +void @(topic)_Subscriber::run() +{ + std::cout << "Waiting for Data, press Enter to stop the Subscriber. "<_uRTPS_UART.cpp file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@# - multi_topics (List) list of all multi-topic names +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ + +topic = spec.short_name +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/*! + * @@file @(topic)_Subscriber.h + * This header file contains the declaration of the subscriber functions. + * + * This file was generated by the tool fastcdrgen. + */ + + +#ifndef _@(topic)__SUBSCRIBER_H_ +#define _@(topic)__SUBSCRIBER_H_ + +#include +#include +#include +#include "@(topic)_PubSubTypes.h" + +using namespace eprosima::fastrtps; + +class @(topic)_Subscriber +{ +public: + @(topic)_Subscriber(); + virtual ~@(topic)_Subscriber(); + bool init(); + void run(); + bool hasMsg(); + @(topic)_ getMsg(); +private: + Participant *mp_participant; + Subscriber *mp_subscriber; + + class SubListener : public SubscriberListener + { + public: + SubListener() : n_matched(0),n_msg(0){}; + ~SubListener(){}; + void onSubscriptionMatched(Subscriber* sub,MatchingInfo& info); + void onNewDataMessage(Subscriber* sub); + SampleInfo_t m_info; + int n_matched; + int n_msg; + @(topic)_ msg; + bool has_msg = false; + + } m_listener; + @(topic)_PubSubType myType; +}; + +#endif // _@(topic)__SUBSCRIBER_H_ \ No newline at end of file diff --git a/msg/templates/urtps/microRTPS_agent.cxx.template b/msg/templates/urtps/microRTPS_agent.cxx.template new file mode 100644 index 0000000000..80e3a43a85 --- /dev/null +++ b/msg/templates/urtps/microRTPS_agent.cxx.template @@ -0,0 +1,280 @@ +@############################################### +@# +@# EmPy template for generating microRTPS_agent.cpp file +@# +@############################################### +@# Start of Template +@# +@# Context: +@# - msgs (List) list of all msg files +@# - multi_topics (List) list of all multi-topic names +@############################################### +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ +from px_generate_uorb_topic_files import MsgScope # this is in Tools/ +from message_id import * # this is in Tools/ + +topic_names = [single_spec.short_name for single_spec in spec] +send_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.SEND] +recv_topics = [s.short_name for idx, s in enumerate(spec) if scope[idx] == MsgScope.RECEIVE] +}@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "microRTPS_transport.h" +#include "RtpsTopics.h" + +#define BUFFER_SIZE 1024 + +// Default values +#define DEVICE "/dev/ttyACM0" +#define SLEEP_US 1 +#define BAUDRATE 460800 +#define POLL_MS 0 +#define WAIT_CNST 2 +#define DEFAULT_RECV_PORT 2020 +#define DEFAULT_SEND_PORT 2019 + +using namespace eprosima; +using namespace eprosima::fastrtps; + +volatile sig_atomic_t running = 1; +Transport_node *transport_node = nullptr; +RtpsTopics topics; +uint32_t total_sent = 0, sent = 0; + +struct options { + enum class eTransports + { + UART, + UDP + }; + eTransports transport = options::eTransports::UART; + char device[64] = DEVICE; + int sleep_us = SLEEP_US; + uint32_t baudrate = BAUDRATE; + int poll_ms = POLL_MS; + uint16_t recv_port = DEFAULT_RECV_PORT; + uint16_t send_port = DEFAULT_SEND_PORT; +} _options; + +static void usage(const char *name) +{ + printf("usage: %s [options]\n\n" + " -t [UART|UDP] Default UART\n" + " -d UART device. Default /dev/ttyACM0\n" + " -w Time in us for which each iteration sleep. Default 1ms\n" + " -b UART device baudrate. Default 460800\n" + " -p Time in ms to poll over UART. Default 1ms\n" + " -r UDP port for receiving. Default 2019\n" + " -s UDP port for sending. Default 2020\n", + name); +} + +static int parse_options(int argc, char **argv) +{ + int ch; + + while ((ch = getopt(argc, argv, "t:d:w:b:p:r:s:")) != EOF) + { + switch (ch) + { + case 't': _options.transport = strcmp(optarg, "UDP") == 0? + options::eTransports::UDP + :options::eTransports::UART; break; + case 'd': if (nullptr != optarg) strcpy(_options.device, optarg); break; + case 'w': _options.sleep_us = strtol(optarg, nullptr, 10); break; + case 'b': _options.baudrate = strtoul(optarg, nullptr, 10); break; + case 'p': _options.poll_ms = strtol(optarg, nullptr, 10); break; + case 'r': _options.recv_port = strtoul(optarg, nullptr, 10); break; + case 's': _options.send_port = strtoul(optarg, nullptr, 10); break; + default: + usage(argv[0]); + return -1; + } + } + + if (optind < argc) + { + usage(argv[0]); + return -1; + } + + return 0; +} + +void signal_handler(int signum) +{ + printf("Interrupt signal (%d) received.\n", signum); + running = 0; + transport_node->close(); +} +@[if recv_topics]@ + +void t_send(void *data) +{ + char data_buffer[BUFFER_SIZE] = {}; + int length = 0; + char topic_ID = 255; + + while (running) + { + // Send subscribed topics over UART + while (topics.hasMsg(&topic_ID)) + { + eprosima::fastcdr::FastBuffer cdrbuffer(data_buffer, sizeof(data_buffer)); + eprosima::fastcdr::Cdr scdr(cdrbuffer); + if (topics.getMsg(topic_ID, scdr)) + { + length = scdr.getSerializedDataLength(); + if (0 < (length = transport_node->write(topic_ID, scdr.getBufferPointer(), length))) + { + total_sent += length; + ++sent; + } + } + } + + usleep(_options.sleep_us); + } +} +@[end if]@ + +int main(int argc, char** argv) +{ + if (-1 == parse_options(argc, argv)) + { + printf("EXITING...\n"); + return -1; + } + + // register signal SIGINT and signal handler + signal(SIGINT, signal_handler); + + switch (_options.transport) + { + case options::eTransports::UART: + { + transport_node = new UART_node(_options.device, _options.baudrate, _options.poll_ms); + printf("\nUART transport: device: %s; baudrate: %d; sleep: %dus; poll: %dms\n\n", + _options.device, _options.baudrate, _options.sleep_us, _options.poll_ms); + } + break; + case options::eTransports::UDP: + { + transport_node = new UDP_node(_options.recv_port, _options.send_port); + printf("\nUDP transport: recv port: %u; send port: %u; sleep: %dus\n\n", + _options.recv_port, _options.send_port, _options.sleep_us); + } + break; + default: + printf("EXITING...\n"); + return -1; + } + + if (0 > transport_node->init()) + { + printf("EXITING...\n"); + return -1; + } + + sleep(1); + +@[if send_topics]@ + char data_buffer[BUFFER_SIZE] = {}; + int received = 0, loop = 0; + int length = 0, total_read = 0; + bool receiving = false; + char topic_ID = 255; + std::chrono::time_point start, end; +@[end if]@ + + topics.init(); + + running = true; +@[if recv_topics]@ + std::thread sender_thread(t_send, nullptr); +@[end if]@ + + while (running) + { +@[if send_topics]@ + ++loop; + if (!receiving) start = std::chrono::steady_clock::now(); + // Publish messages received from UART + while (0 < (length = transport_node->read(&topic_ID, data_buffer, BUFFER_SIZE))) + { + topics.publish(topic_ID, data_buffer, sizeof(data_buffer)); + ++received; + total_read += length; + receiving = true; + end = std::chrono::steady_clock::now(); + } + + if ((receiving && std::chrono::duration(std::chrono::steady_clock::now() - end).count() > WAIT_CNST) || + (!running && loop > 1)) + { + std::chrono::duration elapsed_secs = end - start; + printf("\nSENT: %lu messages - %lu bytes\n", + (unsigned long)sent, (unsigned long)total_sent); + printf("RECEIVED: %d messages - %d bytes; %d LOOPS - %.03f seconds - %.02fKB/s\n\n", + received, total_read, loop, elapsed_secs.count(), (double)total_read/(1000*elapsed_secs.count())); + received = sent = total_read = total_sent = 0; + receiving = false; + } + +@[end if]@ + usleep(_options.sleep_us); + } +@[if recv_topics]@ + sender_thread.join(); +@[end if]@ + delete transport_node; + transport_node = nullptr; + + return 0; +} diff --git a/msg/templates/urtps/microRTPS_agent_CMakeLists.txt.template b/msg/templates/urtps/microRTPS_agent_CMakeLists.txt.template new file mode 100644 index 0000000000..90727dde69 --- /dev/null +++ b/msg/templates/urtps/microRTPS_agent_CMakeLists.txt.template @@ -0,0 +1,54 @@ +################################################################################ +# +# Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# 3. Neither the name of the copyright holder nor the names of its contributors +# may be used to endorse or promote products derived from this software without +# specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +################################################################################ + +cmake_minimum_required(VERSION 2.8.12) +project(micrortps_agent) + +# Find requirements +find_package(fastrtps REQUIRED) +find_package(fastcdr REQUIRED) + +# Set C++11 +include(CheckCXXCompilerFlag) +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG OR + CMAKE_CXX_COMPILER_ID MATCHES "Clang") + check_cxx_compiler_flag(--std=c++11 SUPPORTS_CXX11) + if(SUPPORTS_CXX11) + add_compile_options(--std=c++11) + else() + message(FATAL_ERROR "Compiler doesn't support C++11") + endif() +endif() + +file(GLOB MICRORTPS_AGENT_SOURCES *.cxx) +add_executable(micrortps_agent ${MICRORTPS_AGENT_SOURCES}) +target_link_libraries(micrortps_agent fastrtps fastcdr) \ No newline at end of file diff --git a/msg/templates/urtps/microRTPS_transport.cxx b/msg/templates/urtps/microRTPS_transport.cxx new file mode 100644 index 0000000000..38a8f38869 --- /dev/null +++ b/msg/templates/urtps/microRTPS_transport.cxx @@ -0,0 +1,465 @@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#include +#include +#include +#include +#include +#include + +#include "microRTPS_transport.h" + +#define DEFAULT_UART "/dev/ttyACM0" + +/** CRC table for the CRC-16. The poly is 0x8005 (x^16 + x^15 + x^2 + 1) */ +uint16_t const crc16_table[256] = { + 0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, 0x03C0, 0x0280, 0xC241, + 0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, 0xC481, 0x0440, + 0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, 0x0E40, + 0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841, + 0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40, + 0x1E00, 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41, + 0x1400, 0xD4C1, 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641, + 0xD201, 0x12C0, 0x1380, 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040, + 0xF001, 0x30C0, 0x3180, 0xF141, 0x3300, 0xF3C1, 0xF281, 0x3240, + 0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, 0x35C0, 0x3480, 0xF441, + 0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, 0x3E80, 0xFE41, + 0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, 0x3840, + 0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41, + 0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40, + 0xE401, 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640, + 0x2200, 0xE2C1, 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041, + 0xA001, 0x60C0, 0x6180, 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240, + 0x6600, 0xA6C1, 0xA781, 0x6740, 0xA501, 0x65C0, 0x6480, 0xA441, + 0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, 0x6FC0, 0x6E80, 0xAE41, + 0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, 0xA881, 0x6840, + 0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, 0xBA41, + 0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40, + 0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640, + 0x7200, 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041, + 0x5000, 0x90C1, 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241, + 0x9601, 0x56C0, 0x5780, 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440, + 0x9C01, 0x5CC0, 0x5D80, 0x9D41, 0x5F00, 0x9FC1, 0x9E81, 0x5E40, + 0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, 0x59C0, 0x5880, 0x9841, + 0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, 0x8A81, 0x4A40, + 0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, 0x8C41, + 0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641, + 0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040 +}; + +Transport_node::Transport_node(): rx_buff_pos(0) +{ +} + +Transport_node::~Transport_node() +{ +} + +uint16_t Transport_node::crc16_byte(uint16_t crc, const uint8_t data) +{ + return (crc >> 8) ^ crc16_table[(crc ^ data) & 0xff]; +} + +uint16_t Transport_node::crc16(uint8_t const *buffer, size_t len) +{ + uint16_t crc = 0; + while (len--) crc = crc16_byte(crc, *buffer++); + return crc; +} + +ssize_t Transport_node::read(char* topic_ID, char out_buffer[], size_t buffer_len) +{ + if (nullptr == out_buffer || nullptr == topic_ID || !fds_OK()) return -1; + + *topic_ID = 255; + + ssize_t len = node_read((void*)(rx_buffer + rx_buff_pos), sizeof(rx_buffer) - rx_buff_pos); + if (len <= 0) + { + int errsv = errno; + if (errsv && EAGAIN != errsv && ETIMEDOUT != errsv) + { + printf("Read fail %d\n", errsv); + } + return len; + } + rx_buff_pos += len; + + // We read some + size_t header_size = sizeof(struct Header); + if (rx_buff_pos < header_size) return 0; //but not enough + + uint32_t msg_start_pos = 0; + for (msg_start_pos = 0; msg_start_pos <= rx_buff_pos - header_size; ++msg_start_pos) + { + if ('>' == rx_buffer[msg_start_pos] && memcmp(rx_buffer + msg_start_pos, ">>>", 3) == 0) + { + break; + } + } + + // Start not found + if (msg_start_pos > rx_buff_pos - header_size) + { + printf(" (↓↓ %u)\n", msg_start_pos); + // All we've checked so far is garbage, drop it - but save unchecked bytes + memmove(rx_buffer, rx_buffer + msg_start_pos, rx_buff_pos - msg_start_pos); + rx_buff_pos = rx_buff_pos - msg_start_pos; + return -1; + } + + /* + * [>,>,>,topic_ID,seq,payload_length_H,payload_length_L,CRCHigh,CRCLow,payloadStart, ... ,payloadEnd] + */ + + struct Header *header = (struct Header *)&rx_buffer[msg_start_pos]; + uint32_t payload_len = ((uint32_t)header->payload_len_h << 8) | header->payload_len_l; + // The message won't fit the buffer. + if (buffer_len < header_size + payload_len) return -EMSGSIZE; + // We do not have a complete message yet + if(msg_start_pos + header_size + payload_len > rx_buff_pos) + { + // If there's garbage at the beginning, drop it + if (msg_start_pos > 0) + { + printf(" (↓ %u)\n", msg_start_pos); + memmove(rx_buffer, rx_buffer + msg_start_pos, rx_buff_pos - msg_start_pos); + rx_buff_pos -= msg_start_pos; + } + return 0; + } + + uint16_t read_crc = ((uint16_t)header->crc_h << 8) | header->crc_l; + uint16_t calc_crc = crc16((uint8_t*)rx_buffer + msg_start_pos + header_size, payload_len); + if (read_crc != calc_crc) + { + printf("BAD CRC %u != %u\n", read_crc, calc_crc); + printf(" (↓ %lu)\n", (unsigned long)(header_size + payload_len)); + len = -1; + } + else + { + // copy message to outbuffer and set other return values + memmove(out_buffer, rx_buffer + msg_start_pos + header_size, payload_len); + *topic_ID = header->topic_ID; + len = payload_len + header_size; + } + + // discard message from rx_buffer + rx_buff_pos -= header_size + payload_len; + memmove(rx_buffer, rx_buffer + msg_start_pos + header_size + payload_len, rx_buff_pos); + + return len; +} + +ssize_t Transport_node::write(const char topic_ID, char buffer[], size_t length) +{ + if (!fds_OK()) return -1; + + static struct Header header + { + .marker = {'>','>','>'}, + .topic_ID = 0u, + .seq = 0u, + .payload_len_h = 0u, + .payload_len_l = 0u, + .crc_h = 0u, + .crc_l = 0u + + }; + static uint8_t seq = 0; + + // [>,>,>,topic_ID,seq,payload_length,CRCHigh,CRCLow,payload_start, ... ,payload_end] + + uint16_t crc = crc16((uint8_t*)buffer, length); + + header.topic_ID = topic_ID; + header.seq = seq++; + header.payload_len_h = (length >> 8) & 0xff; + header.payload_len_l = length & 0xff; + header.crc_h = (crc >> 8) & 0xff; + header.crc_l = crc & 0xff; + + ssize_t len = node_write(&header, sizeof(header)); + if (len != sizeof(header)) goto err; + len = node_write(buffer, length); + if (len != ssize_t(length)) goto err; + + return len + sizeof(header); + +err: + //int errsv = errno; + //if (len == -1 ) printf(" => Writing error '%d'\n", errsv); + //else printf(" => Wrote '%ld' != length(%lu) error '%d'\n", (long)len, (unsigned long)length, errsv); + + return len; +} + +UART_node::UART_node(const char *_uart_name, uint32_t _baudrate, uint32_t _poll_ms): + uart_fd(-1), + baudrate(_baudrate), + poll_ms(_poll_ms) + +{ + if (nullptr != _uart_name) strcpy(uart_name, _uart_name); +} + +UART_node::~UART_node() +{ + close(); +} + +int UART_node::init() +{ + // Open a serial port + uart_fd = open(uart_name, O_RDWR | O_NOCTTY | O_NONBLOCK); + + if (uart_fd < 0) + { + printf("failed to open device: %s (%d)\n", uart_name, errno); + return -errno; + } + + // If using shared UART, no need to set it up + if (baudrate == 0) { + return uart_fd; + } + + // Try to set baud rate + struct termios uart_config; + int termios_state; + // Back up the original uart configuration to restore it after exit + if ((termios_state = tcgetattr(uart_fd, &uart_config)) < 0) + { + int errno_bkp = errno; + printf("ERR GET CONF %s: %d (%d)\n", uart_name, termios_state, errno); + close(); + return -errno_bkp; + } + + // Clear ONLCR flag (which appends a CR for every LF) + uart_config.c_oflag &= ~ONLCR; + + // USB serial is indicated by /dev/ttyACM0 + if (strcmp(uart_name, "/dev/ttyACM0") != 0 && strcmp(uart_name, "/dev/ttyACM1") != 0) + { + // Set baud rate + if (cfsetispeed(&uart_config, baudrate) < 0 || cfsetospeed(&uart_config, baudrate) < 0) + { + int errno_bkp = errno; + printf("ERR SET BAUD %s: %d (%d)\n", uart_name, termios_state, errno); + close(); + return -errno_bkp; + } + } + + if ((termios_state = tcsetattr(uart_fd, TCSANOW, &uart_config)) < 0) + { + int errno_bkp = errno; + printf("ERR SET CONF %s (%d)\n", uart_name, errno); + close(); + return -errno_bkp; + } + + char aux[64]; + bool flush = false; + while (0 < ::read(uart_fd, (void*)&aux, 64)) + { + //printf("%s ", aux); + flush = true; + usleep(1000); + } + if (flush) printf("flush\n"); + else printf("no flush\n"); + + poll_fd[0].fd = uart_fd; + poll_fd[0].events = POLLIN; + + return uart_fd; +} + +bool UART_node::fds_OK() +{ + return (-1 != uart_fd); +} + +uint8_t UART_node::close() +{ + if (-1 != uart_fd) + { + printf("Close UART\n"); + ::close(uart_fd); + uart_fd = -1; + memset(&poll_fd, 0, sizeof(poll_fd)); + } + return 0; +} + +ssize_t UART_node::node_read(void *buffer, size_t len) +{ + if (nullptr == buffer || !fds_OK()) return -1; + ssize_t ret = 0; + int r = poll(poll_fd, 1, poll_ms); + if (r == 1 && (poll_fd[0].revents & POLLIN)) + { + ret = ::read(uart_fd, buffer, len); + } + return ret; +} + +ssize_t UART_node::node_write(void *buffer, size_t len) +{ + if (nullptr == buffer || !fds_OK()) return -1; + return ::write(uart_fd, buffer, len); +} + + +UDP_node::UDP_node(uint16_t _udp_port_recv, uint16_t _udp_port_send): + sender_fd(-1), + receiver_fd(-1), + udp_port_recv(_udp_port_recv), + udp_port_send(_udp_port_send) +{ +} + +UDP_node::~UDP_node() +{ + close(); +} + +int UDP_node::init() +{ + if (0 > init_receiver(udp_port_recv) || 0 > init_sender(udp_port_send)) + return -1; + return 0; +} + +bool UDP_node::fds_OK() +{ + return (-1 != sender_fd && -1 != receiver_fd); +} + +int UDP_node::init_receiver(uint16_t udp_port) +{ +#ifndef __PX4_NUTTX + // udp socket data + memset((char *)&receiver_inaddr, 0, sizeof(receiver_inaddr)); + receiver_inaddr.sin_family = AF_INET; + receiver_inaddr.sin_port = htons(udp_port); + receiver_inaddr.sin_addr.s_addr = htonl(INADDR_ANY); + + if ((receiver_fd = socket(AF_INET, SOCK_DGRAM, 0)) < 0) + { + printf("create socket failed\n"); + return -1; + } + + printf("Trying to connect...\n"); + + if (bind(receiver_fd, (struct sockaddr *)&receiver_inaddr, sizeof(receiver_inaddr)) < 0) + { + printf("bind failed\n"); + return -1; + } + + printf("connected to server!\n"); +#endif /* __PX4_NUTTX */ + + return 0; +} + +int UDP_node::init_sender(uint16_t udp_port) +{ +#ifndef __PX4_NUTTX + if ((sender_fd = socket(AF_INET, SOCK_DGRAM, 0)) < 0) + { + printf("create socket failed\n"); + return -1; + } + + memset((char *) &sender_outaddr, 0, sizeof(sender_outaddr)); + sender_outaddr.sin_family = AF_INET; + sender_outaddr.sin_port = htons(udp_port); + + if (inet_aton("127.0.0.1" , &sender_outaddr.sin_addr) == 0) + { + printf("inet_aton() failed\n"); + return -1; + } +#endif /* __PX4_NUTTX */ + + return 0; +} + +uint8_t UDP_node::close() +{ +#ifndef __PX4_NUTTX + if (sender_fd != -1) + { + printf("Close sender socket\n"); + shutdown(sender_fd, SHUT_RDWR); + ::close(sender_fd); + sender_fd = -1; + } + + if (receiver_fd != -1) + { + printf("Close receiver socket\n"); + shutdown(receiver_fd, SHUT_RDWR); + ::close(receiver_fd); + receiver_fd = -1; + } +#endif /* __PX4_NUTTX */ + return 0; +} + +ssize_t UDP_node::node_read(void *buffer, size_t len) +{ + if (nullptr == buffer || !fds_OK()) return -1; + int ret = 0; +#ifndef __PX4_NUTTX + // Blocking call + static socklen_t addrlen = sizeof(receiver_outaddr); + ret = recvfrom(receiver_fd, buffer, len, 0, (struct sockaddr*) &receiver_outaddr, &addrlen); +#endif /* __PX4_NUTTX */ + return ret; +} + +ssize_t UDP_node::node_write(void *buffer, size_t len) +{ + if (nullptr == buffer || !fds_OK()) return -1; + int ret = 0; +#ifndef __PX4_NUTTX + ret = sendto(sender_fd, buffer, len, 0, (struct sockaddr *)&sender_outaddr, sizeof(sender_outaddr)); +#endif /* __PX4_NUTTX */ + return ret; +} diff --git a/msg/templates/urtps/microRTPS_transport.h b/msg/templates/urtps/microRTPS_transport.h new file mode 100644 index 0000000000..fd69d10a31 --- /dev/null +++ b/msg/templates/urtps/microRTPS_transport.h @@ -0,0 +1,119 @@ +/**************************************************************************** + * + * Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software without + * specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include +#include + +class Transport_node +{ +public: + Transport_node(); + virtual ~Transport_node(); + + virtual int init() {return 0;} + virtual uint8_t close() {return 0;} + ssize_t read(char* topic_ID, char out_buffer[], size_t buffer_len); + ssize_t write(const char topic_ID, char buffer[], size_t length); + +protected: + virtual ssize_t node_read(void *buffer, size_t len) = 0; + virtual ssize_t node_write(void *buffer, size_t len) = 0; + virtual bool fds_OK() = 0; + uint16_t crc16_byte(uint16_t crc, const uint8_t data); + uint16_t crc16(uint8_t const *buffer, size_t len); + +protected: + uint32_t rx_buff_pos; + char rx_buffer[1024] = {}; + +private: + struct __attribute__((packed)) Header + { + char marker[3]; + uint8_t topic_ID; + uint8_t seq; + uint8_t payload_len_h; + uint8_t payload_len_l; + uint8_t crc_h; + uint8_t crc_l; + }; +}; + +class UART_node: public Transport_node +{ +public: + UART_node(const char *uart_name, uint32_t baudrate, uint32_t poll_ms); + virtual ~UART_node(); + + int init(); + uint8_t close(); + +protected: + ssize_t node_read(void *buffer, size_t len); + ssize_t node_write(void *buffer, size_t len); + bool fds_OK(); + + int uart_fd; + char uart_name[64] = {}; + uint32_t baudrate; + uint32_t poll_ms; + struct pollfd poll_fd[1] = {}; +}; + +class UDP_node: public Transport_node +{ +public: + UDP_node(uint16_t udp_port_recv, uint16_t udp_port_send); + virtual ~UDP_node(); + + int init(); + uint8_t close(); + +protected: + int init_receiver(uint16_t udp_port); + int init_sender(uint16_t udp_port); + ssize_t node_read(void *buffer, size_t len); + ssize_t node_write(void *buffer, size_t len); + bool fds_OK(); + + int sender_fd; + int receiver_fd; + uint16_t udp_port_recv; + uint16_t udp_port_send; + struct sockaddr_in sender_outaddr; + struct sockaddr_in receiver_inaddr; + struct sockaddr_in receiver_outaddr; +}; diff --git a/msg/templates/urtps/msg.idl.template b/msg/templates/urtps/msg.idl.template new file mode 100644 index 0000000000..bcf93e0e9c --- /dev/null +++ b/msg/templates/urtps/msg.idl.template @@ -0,0 +1,80 @@ +@############################################### +@# +@# ROS message to IDL converter +@# +@# EmPy template for generating .idl files +@# +@################################################################################ +@# +@# Copyright 2017 Proyectos y Sistemas de Mantenimiento SL (eProsima). +@# +@# Redistribution and use in source and binary forms, with or without +@# modification, are permitted provided that the following conditions are met: +@# +@# 1. Redistributions of source code must retain the above copyright notice, this +@# list of conditions and the following disclaimer. +@# +@# 2. Redistributions in binary form must reproduce the above copyright notice, +@# this list of conditions and the following disclaimer in the documentation +@# and/or other materials provided with the distribution. +@# +@# 3. Neither the name of the copyright holder nor the names of its contributors +@# may be used to endorse or promote products derived from this software without +@# specific prior written permission. +@# +@# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +@# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +@# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +@# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +@# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +@# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +@# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +@# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +@# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +@# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +@# POSSIBILITY OF SUCH DAMAGE. +@# +@################################################################################ +@{ +import genmsg.msgs +import gencpp +from px_generate_uorb_topic_helper import * # this is in Tools/ + +uorb_struct = '%s_s'%spec.short_name +topic_name = spec.short_name + +sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True) +struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path) +}@ +@################################################# +@# Searching for serialize function per each field +@################################################# +@{ + +def get_idl_type_name(field_type): + if field_type in type_idl_map: + return type_idl_map[field_type] + else: + (package, name) = genmsg.names.package_resource_name(field_type) + return name + +def add_msg_field(field): + if (not field.is_header): + if (not field.is_array): + print '\t' + str(get_idl_type_name(field.type)) + ' ' + field.name + ';' + else: + print '\t' + str(get_idl_type_name(field.base_type)) + ' ' + field.name + '[' +str(field.array_len)+ '];' + +def add_msg_fields(): + # sort fields (using a stable sort) as in the declaration of the type + sorted_fields = sorted(spec.parsed_fields(), key=sizeof_field_type, reverse=True) + for field in sorted_fields: + add_msg_field(field) + + +}@ +@ +struct @(spec.short_name)_ +{ +@add_msg_fields() +}; // struct @(spec.short_name)_ diff --git a/src/drivers/protocol_splitter/CMakeLists.txt b/src/drivers/protocol_splitter/CMakeLists.txt new file mode 100644 index 0000000000..9e1e972a0e --- /dev/null +++ b/src/drivers/protocol_splitter/CMakeLists.txt @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2015 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +px4_add_module( + MODULE drivers__protocol_splitter + MAIN protocol_splitter + STACK_MAIN 1200 + SRCS + protocol_splitter.cpp + DEPENDS + platforms__common + ) +# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/drivers/protocol_splitter/protocol_splitter.cpp b/src/drivers/protocol_splitter/protocol_splitter.cpp new file mode 100644 index 0000000000..69cbefb591 --- /dev/null +++ b/src/drivers/protocol_splitter/protocol_splitter.cpp @@ -0,0 +1,603 @@ +/**************************************************************************** + * + * Copyright (c) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file protocol_splitter.cpp + * NuttX Driver to split mavlink 2 and another protocol on a serial port. + * Makes sure the two protocols can be read & written simultanously by 2 processes. + * It will create two devices: + * /dev/mavlink + */ + +#include +#include +#include + +#include +#include +#include + +class Mavlink2Dev; +class RtpsDev; +class ReadBuffer; + +extern "C" __EXPORT int protocol_splitter_main(int argc, char *argv[]); + +struct StaticData { + Mavlink2Dev *mavlink2; + RtpsDev *rtps; + sem_t r_lock; + sem_t w_lock; + char device_name[16]; + ReadBuffer *read_buffer; +}; + +namespace +{ +static StaticData *objects = nullptr; +} + +class ReadBuffer +{ +public: + int read(int fd); + void move(void *dest, size_t pos, size_t n); + + uint8_t buffer[512] = {}; + size_t buf_size = 0; + + static const size_t BUFFER_THRESHOLD = sizeof(buffer) * 0.8; +}; + +int ReadBuffer::read(int fd) +{ + /* Discard whole buffer if it's filled beyond a threshold, + * This should prevent buffer being filled by garbage that + * no reader (MAVLink or RTPS) can understand. + * + * TODO: a better approach would be checking if both reader + * start understanding messages beyond a certain buffer size, + * meaning that everything before is garbage. + */ + if (buf_size > BUFFER_THRESHOLD) { + buf_size = 0; + } + + int r = ::read(fd, buffer + buf_size, sizeof(buffer) - buf_size); + if (r < 0) + return r; + + buf_size += r; + + return r; +} + +void ReadBuffer::move(void *dest, size_t pos, size_t n) +{ + ASSERT(pos < buf_size); + ASSERT(pos + n <= buf_size); + + memmove(dest, buffer + pos, n); // send desired data + memmove(buffer + pos, buffer + (pos + n), sizeof(buffer) - pos - n); + buf_size -= n; +} + +class DevCommon : public device::CDev +{ +public: + DevCommon(const char *device_name, const char *device_path); + virtual ~DevCommon(); + + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + virtual int open(file *filp); + virtual int close(file *filp); + + enum Operation {Read, Write}; + +protected: + + virtual pollevent_t poll_state(struct file *filp); + + + void lock(enum Operation op) + { + sem_t *lock = op == Read ? &objects->r_lock : &objects->w_lock; + while (sem_wait(lock) != 0) { + /* The only case that an error should occur here is if + * the wait was awakened by a signal. + */ + ASSERT(get_errno() == EINTR); + } + } + + void unlock(enum Operation op) + { + sem_t *lock = op == Read ? &objects->r_lock : &objects->w_lock; + sem_post(lock); + } + + int _fd = -1; + + uint16_t _packet_len; + enum class ParserState : uint8_t { + Idle = 0, + GotLength + }; + ParserState _parser_state = ParserState::Idle; + + bool _had_data = false; ///< whether poll() returned available data + +private: +}; + +DevCommon::DevCommon(const char *device_name, const char *device_path) + : CDev(device_name, device_path) +{ +} + +DevCommon::~DevCommon() +{ + if (_fd >= 0) { + ::close(_fd); + } +} + +int DevCommon::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + //pretend we have enough space left to write, so mavlink will not drop data and throw off + //our parsing state + if (cmd == FIONSPACE) { + *(int *)arg = 1024; + return 0; + } + + return ::ioctl(_fd, cmd, arg); +} + +int DevCommon::open(file *filp) +{ + _fd = ::open(objects->device_name, O_RDWR | O_NOCTTY); + CDev::open(filp); + return _fd >= 0 ? 0 : -1; +} + +int DevCommon::close(file *filp) +{ + //int ret = ::close(_fd); // FIXME: calling this results in a dead-lock, because DevCommon::close() + // is called from within another close(), and NuttX seems to hold a semaphore at this point + _fd = -1; + CDev::close(filp); + return 0; +} + +pollevent_t DevCommon::poll_state(struct file *filp) +{ + pollfd fds[1]; + fds[0].fd = _fd; + fds[0].events = POLLIN; + + /* Here we should just check the poll state (which is called before an actual poll waiting). + * Instead we poll on the fd with some timeout, and then pretend that there is data. + * This will let the calling poll return immediately (there's still no busy loop since + * we do actually poll here). + * We do this because there is no simple way with the given interface to poll on + * the _fd in here or by overriding some other method. + */ + + int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), 100); + _had_data = ret > 0 && (fds[0].revents & POLLIN); + + return POLLIN; +} + +class Mavlink2Dev : public DevCommon +{ +public: + Mavlink2Dev(ReadBuffer *_read_buffer); + virtual ~Mavlink2Dev() {} + + virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); + virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen); + +protected: + ReadBuffer *_read_buffer; + size_t _remaining_partial = 0; + size_t _partial_start = 0; + uint8_t _partial_buffer[512] = {}; +}; + +Mavlink2Dev::Mavlink2Dev(ReadBuffer *read_buffer) + : DevCommon("Mavlink2", "/dev/mavlink") + , _read_buffer{read_buffer} +{ +} + +ssize_t Mavlink2Dev::read(struct file *filp, char *buffer, size_t buflen) +{ + int i, ret; + uint16_t packet_len = 0; + + /* last reading was partial (i.e., buffer didn't fit whole message), + * so now we'll just send remaining bytes */ + if (_remaining_partial > 0) { + size_t len = _remaining_partial; + if (buflen < len) { + len = buflen; + } + memmove(buffer, _partial_buffer + _partial_start, len); + _partial_start += len; + _remaining_partial -= len; + + if (_remaining_partial == 0) { + _partial_start = 0; + } + return len; + } + + if (!_had_data) { + return 0; + } + + lock(Read); + ret = _read_buffer->read(_fd); + + if (ret < 0) + goto end; + + ret = 0; + + if (_read_buffer->buf_size < 3) + goto end; + + // Search for a mavlink packet on buffer to send it + i = 0; + while (i < (_read_buffer->buf_size - 3) + && _read_buffer->buffer[i] != 253 + && _read_buffer->buffer[i] != 254) + i++; + + // We need at least the first three bytes to get packet len + if (i >= _read_buffer->buf_size - 3) { + goto end; + } + + if (_read_buffer->buffer[i] == 253) { + uint8_t payload_len = _read_buffer->buffer[i + 1]; + uint8_t incompat_flags = _read_buffer->buffer[i + 2]; + packet_len = payload_len + 12; + + if (incompat_flags & 0x1) { //signing + packet_len += 13; + } + } else { + packet_len = _read_buffer->buffer[i + 1] + 8; + } + + // packet is bigger than what we've read, better luck next time + if (i + packet_len > _read_buffer->buf_size) { + goto end; + } + + /* if buffer doesn't fit message, send what's possible and copy remaining + * data into a temporary buffer on this class */ + if (packet_len > buflen) { + _read_buffer->move(buffer, i, buflen); + _read_buffer->move(_partial_buffer, i, packet_len - buflen); + _remaining_partial = packet_len - buflen; + ret = buflen; + goto end; + } + + _read_buffer->move(buffer, i, packet_len); + ret = packet_len; + +end: + unlock(Read); + return ret; +} + +ssize_t Mavlink2Dev::write(struct file *filp, const char *buffer, size_t buflen) +{ + /* + * we need to look into the data to make sure the output is locked for the duration + * of a whole packet. + * assumptions: + * - packet header is written all at once (or at least it contains the payload length) + * - a single write call does not contain multiple (or parts of multiple) packets + */ + ssize_t ret = 0; + + switch (_parser_state) { + case ParserState::Idle: + ASSERT(buflen >= 3); + + if ((unsigned char)buffer[0] == 253) { + uint8_t payload_len = buffer[1]; + uint8_t incompat_flags = buffer[2]; + _packet_len = payload_len + 12; + + if (incompat_flags & 0x1) { //signing + _packet_len += 13; + } + + _parser_state = ParserState::GotLength; + lock(Write); + + } else if ((unsigned char)buffer[0] == 254) { // mavlink 1 + uint8_t payload_len = buffer[1]; + _packet_len = payload_len + 8; + + _parser_state = ParserState::GotLength; + lock(Write); + + } else { + PX4_ERR("parser error"); + return 0; + } + + //no break + case ParserState::GotLength: { + _packet_len -= buflen; + int buf_free; + ::ioctl(_fd, FIONSPACE, (unsigned long)&buf_free); + + if (buf_free < buflen) { + //let write fail, to let mavlink know the buffer would overflow + //(this is because in the ioctl we pretend there is always enough space) + ret = -1; + + } else { + ret = ::write(_fd, buffer, buflen); + } + + if (_packet_len == 0) { + unlock(Write); + _parser_state = ParserState::Idle; + } + } + + break; + } + + return ret; +} + +class RtpsDev : public DevCommon +{ +public: + RtpsDev(ReadBuffer *_read_buffer); + virtual ~RtpsDev() {} + + virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); + virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen); + +protected: + ReadBuffer *_read_buffer; + + static const uint8_t HEADER_SIZE = 9; +}; + +RtpsDev::RtpsDev(ReadBuffer *read_buffer) + : DevCommon("Rtps", "/dev/rtps") + , _read_buffer{read_buffer} +{ +} + +ssize_t RtpsDev::read(struct file *filp, char *buffer, size_t buflen) +{ + int i, ret; + uint16_t packet_len, payload_len; + + if (!_had_data) { + return 0; + } + + lock(Read); + ret = _read_buffer->read(_fd); + + if (ret < 0) { + goto end; + } + ret = 0; + + if (_read_buffer->buf_size < HEADER_SIZE) + goto end; // starting ">>>" + topic + seq + lenhigh + lenlow + crchigh + crclow + + // Search for a rtps packet on buffer to send it + i = 0; + while (i < (_read_buffer->buf_size - HEADER_SIZE) && (memcmp(_read_buffer->buffer + i, ">>>", 3) != 0)) + i++; + + // We need at least the first six bytes to get packet len + if (i >= _read_buffer->buf_size - HEADER_SIZE) { + goto end; + } + + payload_len = ((uint16_t)_read_buffer->buffer[i + 5] << 8) | _read_buffer->buffer[i + 6]; + packet_len = payload_len + HEADER_SIZE; + + // packet is bigger than what we've read, better luck next time + if (i + packet_len > _read_buffer->buf_size) { + goto end; + } + + // buffer should be big enough to hold a rtps packet + if (packet_len > buflen) { + ret = -EMSGSIZE; + goto end; + } + + _read_buffer->move(buffer, i, packet_len); + ret = packet_len; + +end: + unlock(Read); + return ret; +} + +ssize_t RtpsDev::write(struct file *filp, const char *buffer, size_t buflen) +{ + /* + * we need to look into the data to make sure the output is locked for the duration + * of a whole packet. + * assumptions: + * - packet header is written all at once (or at least it contains the payload length) + * - a single write call does not contain multiple (or parts of multiple) packets + */ + ssize_t ret = 0; + uint16_t payload_len; + + switch (_parser_state) { + case ParserState::Idle: + ASSERT(buflen >= HEADER_SIZE); + if (memcmp(buffer, ">>>", 3) != 0) { + PX4_ERR("parser error"); + return 0; + } + + payload_len = ((uint16_t)buffer[5] << 8) | buffer[6]; + _packet_len = payload_len + HEADER_SIZE; + _parser_state = ParserState::GotLength; + lock(Write); + + + //no break + case ParserState::GotLength: { + _packet_len -= buflen; + int buf_free; + ::ioctl(_fd, FIONSPACE, (unsigned long)&buf_free); + + // TODO should I care about this for rtps? + if (buf_free < buflen) { + //let write fail, to let rtps know the buffer would overflow + //(this is because in the ioctl we pretend there is always enough space) + ret = -1; + + } else { + ret = ::write(_fd, buffer, buflen); + } + + if (_packet_len == 0) { + unlock(Write); + _parser_state = ParserState::Idle; + } + } + + break; + } + + return ret; +} + +int protocol_splitter_main(int argc, char *argv[]) +{ + if (argc < 2) { + goto out; + } + + /* + * Start/load the driver. + */ + if (!strcmp(argv[1], "start")) { + if (objects) { + PX4_ERR("already running"); + return 1; + } + + if (argc != 3) { + goto out; + } + + objects = new StaticData(); + + if (!objects) { + PX4_ERR("alloc failed"); + return -1; + } + + strncpy(objects->device_name, argv[2], sizeof(objects->device_name)); + sem_init(&objects->r_lock, 1, 1); + sem_init(&objects->w_lock, 1, 1); + objects->read_buffer = new ReadBuffer(); + objects->mavlink2 = new Mavlink2Dev(objects->read_buffer); + objects->rtps = new RtpsDev(objects->read_buffer); + + if (!objects->mavlink2 || !objects->rtps) { + delete objects->mavlink2; + delete objects->rtps; + delete objects->read_buffer; + sem_destroy(&objects->r_lock); + sem_destroy(&objects->w_lock); + delete objects; + objects = nullptr; + PX4_ERR("alloc failed"); + return -1; + + } else { + objects->mavlink2->init(); + objects->rtps->init(); + } + } + + if (!strcmp(argv[1], "stop")) { + if (objects) { + delete objects->mavlink2; + delete objects->rtps; + delete objects->read_buffer; + sem_destroy(&objects->r_lock); + sem_destroy(&objects->w_lock); + delete objects; + objects = nullptr; + } + } + + /* + * Print driver status. + */ + if (!strcmp(argv[1], "status")) { + if (objects) { + PX4_INFO("running"); + + } else { + PX4_INFO("not running"); + } + } + + return 0; + +out: + PX4_ERR("unrecognized command, try 'start ', 'stop', 'status'"); + return 1; +} + diff --git a/src/lib/micro-CDR b/src/lib/micro-CDR new file mode 160000 index 0000000000..f2193957eb --- /dev/null +++ b/src/lib/micro-CDR @@ -0,0 +1 @@ +Subproject commit f2193957eb36365680647c6ed07a8bf8a3e71a9e diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index 0fb2205143..76d89e6b1d 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -36,8 +36,8 @@ include_directories(${PX4_SOURCE_DIR}/mavlink/include/mavlink) px4_add_module( MODULE modules__mavlink MAIN mavlink - STACK_MAIN 1200 - STACK_MAX 1500 + STACK_MAIN 2000 + STACK_MAX 2500 COMPILE_FLAGS SRCS mavlink.c diff --git a/src/modules/micrortps_bridge/README.md b/src/modules/micrortps_bridge/README.md new file mode 100644 index 0000000000..55e4b41ae6 --- /dev/null +++ b/src/modules/micrortps_bridge/README.md @@ -0,0 +1,385 @@ +# RTPS/ROS2 interface: the PX4-FastRTPS bridge + +This bridge adds communication capabilities between a *PX4 Autopilot* and a *Fast RTPS* application, through serial ports or +UDP sockets, using [CDR serialization](https://en.wikipedia.org/wiki/Common_Data_Representation). The goal is to provide a RTPS (Real Time Publish Subscribe Protocol) interface to PX4. This interface will also allow sharing information with the forthcoming release of ROS2 (Robot Operating System). + +RTPS is the underlying protocol of DDS, an standard from the OMG (Object Management Group) providing a real-time publish/subscribe middleware that is widely used in aerospace, defense and IoT applications. It has also been adopted as the middleware for the ROS2 robotics toolkit. + +Fast RTPS implements the latest version of the RTPS protocol and a minimum DDS API, resulting in a very lightweight implementation of the standard and full access to the RTPS fine settings. + +## Code generation + +Support for the functionality is mainly implemented within three new (automatically generated) code blocks: + +- *CDR serialization functions* are generated for specified uORB topics (those that are to be sent/received). For example, the following functions are generated for the *sensor_combined.msg*: + + ```sh + void serialize_sensor_combined(const struct sensor_combined_s *input, char *output, uint32_t *length, struct microCDR *microCDRWriter); + void deserialize_sensor_combined(struct sensor_combined_s *output, char *input, struct microCDR *microCDRReader); + ``` + + > **Note** *CDR serialization* provides a common format for exchanging serial data between different platforms. + +- A *client application* that sends and receives the CDR serialized data from topics through a selected UART or UDP port. + +- An *agent application* that shares the CDR serialized data via (using **Fast RTPS**) to DDS service clients (e.g. ROS2). A first step in this part is the generation of a IDL file for each topic which is the translation of the corresponding MSG file (For the case of *sensor_combined* topic the **sensor_combined_.idl** file is generated from **sensor_combined.msg** file). After that *fastrtpsgen* tool is capable to generate code from the IDL file. + +These pieces of code are generated within the normal PX4 Firmware generation process. They can also can be generated explicitly by calling the script **Tools/generate_microRTPS_bridge.py** (see section below). + +### Automatically generate client and the agent code + +> **Note** Before continuing we need to have [installed Fast RTPS](https://dev.px4.io/en/setup/fast-rtps-installation.html). + +The code needed for the client, agent, and CDR serialization is automatically generated when the PX4 Firmware is compiled. The actual functions generated is based the uORB topics to send and receive. These are listed in the **.cmake** file (**cmake/configs**) for each target platform: + +```cmake +set(config_rtps_send_topics + sensor_accel + sensor_baro + sensor_gyro + # Add new topic... + ) + +set(config_rtps_receive_topics + sensor_combined + telemetry_status + wind_estimate + # Add new topic... + ) +``` + +> **Note** Before compiling ensure that the code generation is not disabled in this way: +```sh +set(GENERATE_RTPS_BRIDGE off) +``` + +The client application will be generated in *build_OURPLATFORM/src/modules/micrortps_bridge/micrortps_client/* folder and the agent will be created in *src/modules/micrortps_bridge/micrortps_agent/* folder. + +> **Note** In the process of the agent generation we use a Fast RTPS tool called *fastrtpsgen*. If you haven't installed Fast RTPS in the default path you need to specify the directory of installation of *fastrtpsgen* setting the environment variable `FASTRTPSGEN_DIR` before executing *make*. +> On Linux/Mac this is done as shown below: +> +> ```sh + export FASTRTPSGEN_DIR=/path/to/fastrtps/install/folder/bin + ``` + +### Manually generate client and agent code + +It is also possible to generate and install the code for the client and the agent outside the normal PX4 build process using the python script +**Tools/generate_microRTPS_bridge.py**. + +First at all, we need to disable the automatic generation in the PX4 compiling process setting the variable `GENERATE_RTPS_BRIDGE` to *off* inside the *.cmake* file for the target platform: + +```sh +set(GENERATE_RTPS_BRIDGE off) +``` + +The tool's command syntax is shown below: + +```sh +$ cd /path/to/PX4/Firmware +$ python Tools/generate_microRTPS_bridge.py -h +usage: generate_microRTPS_bridge.py [-h] [-s *.msg [*.msg ...]] + [-r *.msg [*.msg ...]] [-a] [-c] + [-t MSGDIR] [-o AGENTDIR] [-u CLIENTDIR] + [-f FASTRTPSGEN] + +optional arguments: + -h, --help show this help message and exit + -s *.msg [*.msg ...], --send *.msg [*.msg ...] + Topics to be sent + -r *.msg [*.msg ...], --receive *.msg [*.msg ...] + Topics to be received + -a, --agent Flag for generate the agent, by default is true if -c + is not specified + -c, --client Flag for generate the client, by default is true if -a + is not specified + -t MSGDIR, --topic-msg-dir MSGDIR + Topics message dir, by default msg/ + -o AGENTDIR, --agent-outdir AGENTDIR + Agent output dir, by default + src/modules/micrortps_bridge/micrortps_agent + -u CLIENTDIR, --client-outdir CLIENTDIR + Client output dir, by default + src/modules/micrortps_bridge/micrortps_client + -f FASTRTPSGEN, --fastrtpsgen-dir FASTRTPSGEN + fastrtpsgen installation dir, by default /bin + --delete-tree Delete dir tree output dir(s) +``` + > **Caution with --delete-tree option** so erases the content of the `CLIENTDIR` and the `AGENTDIR` before creating new files and folders. + +- The argument `--send/-s` means that the application from PX4 side will send these messages, and the argument `--receive/-r` specifies which messages are going to be received. +- The output appears in `CLIENTDIR` (`-o src/modules/micrortps_bridge/micrortps_client`, by default) and in the `AGENTDIR` (`-u src/modules/micrortps_bridge/micrortps_agent`, by default). +- If no flag `-a` or `-c` is specified, both the client and the agent will be generated and installed. +- The `-f` option may be needed if *Fast RTPS* was not installed in the default location (`-f /path/to/fastrtps/installation/bin`). + +An example of use: + +```sh +$ cd /path/to/PX4/Firmware +$ python Tools/generate_microRTPS_bridge.py -s msg/sensor_baro.msg -r msg/sensor_combined.msg +``` + +Checking the correct generation and installation: + +```sh +$ tree src/modules/micrortps_bridge/micrortps_agent +src/modules/micrortps_bridge/micrortps_agent +├── build +├── CMakeLists.txt +├── idl +│   ├── sensor_baro_.idl +│   └── sensor_combined_.idl +├── microRTPS_agent.cxx +├── microRTPS_transport.cxx +├── microRTPS_transport.h +├── RtpsTopics.cxx +├── RtpsTopics.h +├── sensor_baro_.cxx +├── sensor_baro_.h +├── sensor_baro_Publisher.cxx +├── sensor_baro_Publisher.h +├── sensor_baro_PubSubTypes.cxx +├── sensor_baro_PubSubTypes.h +├── sensor_combined_.cxx +├── sensor_combined_.h +├── sensor_combined_PubSubTypes.cxx +├── sensor_combined_PubSubTypes.h +├── sensor_combined_Subscriber.cxx +└── sensor_combined_Subscriber.h + 2 directories, 20 files +``` + +```sh +$ tree src/modules/micrortps_bridge/micrortps_client +src/modules/micrortps_bridge/micrortps_client +├── CMakeLists.txt +├── microRTPS_client.cpp +├── microRTPS_transport.cxx +└── microRTPS_transport.h + 0 directories, 4 files +``` + + +## PX4 Firmware side: the micro RTPS client + +The client application runs as both a uORB node and as a micro RTPS node. As a uORB node the agent could be subscribed to several topics as well as publish under internal uORB topics. The application receives from a internal publishers the messages, serializes the struct and writes it trough an UART +device or UDP port selected by the user. Also will be reading from the UART device or UDP port and then publish the info +to the internal subscribers. + +Steps to use the auto generated application: + +- Check that the lines **modules/micrortps_bridge/micrortps_client** and **lib/micro-CDR** are present in the *.cmake* config file for the target platform (*cmake/configs/*). This enables the compilation of the client along with the **PX4** firmware: + + ```sh + set(config_module_list + ... + lib/micro-CDR + ... + # micro RTPS + modules/micrortps_bridge/micrortps_client + ... + ) + ``` + > **Note** For Nuttx platforms (e.g. *Pixracer*) the cmake files are **cmake/configs/nuttx_px4fmu-v4_default.cmake**. For the *Snapdragon Flight* platform you can find the cmake configuration here: **cmake/configs/posix_sdflight_default.cmake**. + +- Construct and upload the firmware executing, for example: + + ```sh + # For NuttX/Pixhawk flight controllers: + $ make px4fmu-v4_default upload + ``` + ```sh + # For Snapdragon Flight: + $ make eagle_default upload + ``` + +After uploading the firmware, the application can be launched typing its name and passing an variable number of arguments as shown below: + +```sh +> micrortps_client start|stop [options] + -t [UART|UDP] Default UART + -d UART device. Default /dev/ttyACM0 + -u Time in ms for uORB subscribed topics update. Default 0 + -l How many iterations will this program have. -1 for infinite. Default 10000 + -w Time in ms for which each iteration sleep. Default 1ms + -b UART device baudrate. Default 460800 + -p Time in ms to poll over UART. Default 1ms + -r UDP port for receiving. Default 2019 + -s UDP port for sending. Default 2020 +``` + +> **Note** When working with a USB-serial adapter the maximum link speed is used (the `-b` option is ignored). + ```sh + > micrortps_client start #by default -t UART -d /dev/ttyACM0 -u 0 -l 10000 -w 1 -b 460800 -p 1 + ``` + + +> **Note** If the selected UART port is busy, it's possible that the MAVLink application is already being used. If it is the case, you can stop MAVLink from NuttShell by typing: + ```sh + > mavlink stop-all + ``` + +## Fast RTPS side: the Micro RTPS agent + +The application has several functions and possibilities of use: get the sensor data from a system that is using the *PX4 +Firmware* (obtaining the information from the selected transport: UDP or UART), publish this to a *Fast RTPS* environment +and, in the other direction, to send through the selected transport the information of topics that are expected in the +*PX4* side with the info even from subscribed messages from *Fast RTPS* side. + +> **Note** Before running the application, you must [install Fast RTPS](https://dev.px4.io/en/setup/fast-rtps-installation.html). + +This section explains how create *Fast RTPS* applications using the files generated by **generate_microRTPS_bridge.py** and **fastrtpsgen** (this step performed inside install script) from *Fast RTPS*. + +On the *Fast RTPS* side, it will be used an application running as a Fast RTPS node and as a micro RTPS node at same time. This application allow to launch RTPS publishers and subscribers that will be using the information coming from and sending to uORB topics in the PX4 side thanks to the autogenerated idl file from the original msg file. The publisher will read data from UART/UDP, deserializes it, and make a Fast RTPS message mapping the attributes from the uORB message. The subscriber simply receives the Fast RTPS messages and send in the reverse sequence to the PX4 side. The subscriber can be launched on the Raspberry Pi or in any another device connected in the same network. + +To create the application, compile the code: + + ```sh + $ cd src/modules/micrortps_bridge/microRTPS_agent + $ mkdir build && cd build + $ cmake .. + $ make + ``` + +> **Note** To cross-compile for the Qualcomm Snapdragon Flight platform see [this link](https://github.com/eProsima/PX4-FastRTPS-PoC-Snapdragon-UDP#how-to-use). + +To launch the publisher run: + + ```text + $ ./micrortps_agent [options] + -t [UART|UDP] Default UART + -d UART device. Default /dev/ttyACM0 + -w Time in us for which each iteration sleep. Default 1ms + -b UART device baudrate. Default 460800 + -p Time in ms to poll over UART. Default 1ms + -r UDP port for receiving. Default 2019 + -s UDP port for sending. Default 2020 + ``` + > **Note** If we are working with a USB-serial adapter the **-b** option will be ignored and will be working at maximum speed of the link. + ```sh + $ ./micrortps_agent # by default -t UART -d /dev/ttyACM0 -w 1 -b 460800 -p 1 + ``` + + +## Creating a Listener + +Now that we have the Client running on the flight controller and the Agent on an offboard computer, we can create an application to communicate with the flight controller through FastRTPS. The *fastrtpsgen* script allows us to quickly generate a simple application from a IDL message file. We will use it to create a Listener which subscribes to the sensor_combined topic. The Listener can be run on any computer on the same network as the Agent, but here they will be on the same computer. + +```sh +$ cd /path/to/PX4/Firmware/src/modules/micrortps_bridge +$ mkdir micrortps_listener +$ cd micrortps_listener +$ fastrtpsgen -example x64Linux2.6gcc ../micrortps_agent/idl/sensor_combined_.idl +``` + +This creates a sample subscriber, a publisher and a main-application to run them. To print out the data from the sensor_combined topic we modify the onNewDataMessage-method in sensor_combined_Subscriber.cxx: + +```sh +void sensor_combined_Subscriber::SubListener::onNewDataMessage(Subscriber* sub) +{ + // Take data + sensor_combined_ st; + + if(sub->takeNextData(&st, &m_info)) + { + if(m_info.sampleKind == ALIVE) + { + // Print your structure data here. + ++n_msg; + std::cout << "\n\n\n\n\n\n\n\n\n\n"; + std::cout << "Sample received, count=" << n_msg << std::endl; + std::cout << "=============================" << std::endl; + std::cout << "gyro_rad: " << st.gyro_rad().at(0); + std::cout << ", " << st.gyro_rad().at(1); + std::cout << ", " << st.gyro_rad().at(2) << std::endl; + std::cout << "gyro_integral_dt: " << st.gyro_integral_dt() << std::endl; + std::cout << "accelerometer_timestamp_relative: " << st.accelerometer_timestamp_relative() << std::endl; + std::cout << "accelerometer_m_s2: " << st.accelerometer_m_s2().at(0); + std::cout << ", " << st.accelerometer_m_s2().at(1); + std::cout << ", " << st.accelerometer_m_s2().at(2) << std::endl; + std::cout << "accelerometer_integral_dt: " << st.accelerometer_integral_dt() << std::endl; + std::cout << "magnetometer_timestamp_relative: " << st.magnetometer_timestamp_relative() << std::endl; + std::cout << "magnetometer_ga: " << st.magnetometer_ga().at(0); + std::cout << ", " << st.magnetometer_ga().at(1); + std::cout << ", " << st.magnetometer_ga().at(2) << std::endl; + std::cout << "baro_timestamp_relative: " << st.baro_timestamp_relative() << std::endl; + std::cout << "baro_alt_meter: " << st.baro_alt_meter() << std::endl; + std::cout << "baro_temp_celcius: " << st.baro_temp_celcius() << std::endl; + + } + } +} + +``` + +Now build and run the Listener: + +```sh +$ make -f makefile_x64Linux2.6gcc +$ bin/*/sensor_combined_PublisherSubscriber subscriber +``` + +Now you should see the alititude being printed out by the Listener + +```sh +Sample received, count=10119 +Received sensor_combined data +============================= +gyro_rad: -0.0103228, 0.0140477, 0.000319406 +gyro_integral_dt: 0.004 +accelerometer_timestamp_relative: 0 +accelerometer_m_s2: -2.82708, -6.34799, -7.41101 +accelerometer_integral_dt: 0.004 +magnetometer_timestamp_relative: -10210 +magnetometer_ga: 0.60171, 0.0405879, -0.040995 +baro_timestamp_relative: -17469 +baro_alt_meter: 368.647 +baro_temp_celcius: 43.93 +``` + +If the Listener does not print anything, make sure the Client is running. By default the Client runs for 10000 and than stops, to run the Client continuously run +```sh +$ micrortps_client start -l -1 +``` + + +## Throughput test + +[Throughput test](throughput_test.md) show some real-world examples of how to use the features described in this topic. + + +## Troubleshooting + +### Extra steps for Raspberry Pi + +> **Note** Normally, for UART transport it's necessary set up the UART port in the Raspberry Pi. To enable the serial port available on Raspberry Pi connector: + +1. Make sure the `userid` (default is pi) is a member of the `dialout` group: + + ```sh + $ groups pi + $ sudo usermod -a -G dialout pi + ``` + +2. You need to stop the already running on the GPIO serial console: + + ```sh + $ sudo raspi-config + ``` + + In the menu showed go to **Interfacing options > Serial**. Select **NO for *Would you like a login shell to be accessible over serial?*. Valid and reboot. + +3. Check UART in kernel: + + ```sh + $ sudo vi /boot/config.txt + ``` + +And enable UART setting `enable_uart=1`. + + +## Graphical example of usage + +This flow chart shows graphically how the bridge works. It demonstrates a bridge that sends the topic `sensor_combined` from a Pixracer to a Raspberry Pi through UART. + +![basic example flow](res/basic_example_flow.png) diff --git a/src/modules/micrortps_bridge/hello_world.md b/src/modules/micrortps_bridge/hello_world.md new file mode 100644 index 0000000000..62b3ed17cb --- /dev/null +++ b/src/modules/micrortps_bridge/hello_world.md @@ -0,0 +1,115 @@ +# Hello world + +As a basic example we go to explain how implement a simple use case what sends information of some sensors (*sensor_combined* uORB topic) in the direction PX4-Fast RTPS and receives information as a text message (*log_message* uORB topic) sent in the other direction. + +## Creating the code + + ``` sh + $ cd /path/to/PX4/Firmware + $ python Tools/generate_microRTPS_bridge.py --send msg/sensor_combined.msg --receive msg/sensor_combined.msg msg/log_message.msg -u src/examples/micrortps_client + ``` +**NOTE**: It may be needed specify other different arguments, as the path to the Fast RTPS *bin* installation folder if it was installed in other path different to default one (*-f /path/to/fastrtps/installation/bin*). For more information, click this [link](README.md#generate-and-installing-the-client-and-the-agent). + +That generates and installs the PX4 side of the code (the client) in *src/examples/micrortps_client* and the Fast RPS side (the agent) in *src/modules/micrortps_bridge/micrortps_agent*. + +To see the message received in the client one time each second (**src/examples/micrortps_client/microRTPS_client.cpp**), we change the default value of the sleep to 1000 and we will add this *printf* to the code under the *orb_publish* line for *log_message* topic (line 274): + + ```cpp + ... + #define SLEEP_MS 1000 + ... + ... + ... + case 36: + { + deserialize_log_message(&log_message_data, data_buffer, µCDRReader); + if (!log_message_pub) + log_message_pub = orb_advertise(ORB_ID(log_message), &log_message_data); + else + orb_publish(ORB_ID(log_message), log_message_pub, &log_message_data); + printf("%s\n", log_message_data.text); + ++received; + } + ... + ``` +To enable the compilation of the example client we need to modify the *micrortps_client* line in the cmake of our platform (*cmake/configs*) in that way: + +``` cmake +set(config_module_list + ... + #src/modules/micrortps_bridge/micrortps_client + src/examples/micrortps_client + ... +) +``` + +Also we need to a add basic CMakeLists.txt like that: + +``` cmake +px4_add_module( + MODULE examples__micrortps_client + MAIN micrortps_client + STACK_MAIN 4096 + SRCS + microRTPS_transport.cxx + microRTPS_client.cpp + DEPENDS + platforms__common + ) +``` + + Now, we change the agent in order to send a log message each time we receive a **Fast RTPS message** with the info of the uORB topic *sensor_combined* (in the Fast RTPS world this topic will be called *sensor_combined_PubSubTopic*). + + - In the **src/modules/micrortps_bridge/micrortps_agent/RtpsTopic.cxx** file we will change the *RtpsTopics::getMsg* function to return a *log_message* for each *sensor_combined* with the text "*The temperature is XX.XXXXXXX celsius degrees*": + +```cpp + bool RtpsTopics::getMsg(const char topic_ID, eprosima::fastcdr::Cdr &scdr) + { + bool ret = false; + switch (topic_ID) + { + case 58: // sensor_combined + if (_sensor_combined_sub.hasMsg()) + { + sensor_combined_ msg = _sensor_combined_sub.getMsg(); + log_message_ log_msg = {}; + std::string message = "The temperature is " + std::to_string(msg.baro_temp_celcius()) + " celsius degrees"; + std::memcpy(log_msg.text().data(), message.c_str(), message.length()); + log_msg.serialize(scdr); + ret = true; + } + break; + default: + printf("Unexpected topic ID to getMsg\n"); + break; + } + + return ret; + } + ``` + + - In the **src/micrortps_bridge/micrortps_agent/microRTPS_agent.cxx** we will change the topic ID of the received message to the topic ID of the *log_message* (**36**) that is really the topic we are handling: + +```cpp + ... + if (topics.getMsg(topic_ID, scdr)) + { + topic_ID = 36; + length = scdr.getSerializedDataLength(); + if (0 < (length = transport_node->write(topic_ID, scdr.getBufferPointer(), length))) + { + total_sent += length; + ++sent; + } + } + ... +``` +## Result + +After compiling and launching both the [client](README.md#px4-firmware-the-micro-rtps-client) and the [agent](README.md#fast-rtps-the-micro-rtps-agent) we obtain this kind of messages in the client shell window (showing the message created in the agent with info from temperature sensor in the PX4 side): + +```sh + ... + The temperature is: 47.779999 celsius + ... +``` diff --git a/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt b/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt new file mode 100644 index 0000000000..e9ed67d7b3 --- /dev/null +++ b/src/modules/micrortps_bridge/micrortps_client/CMakeLists.txt @@ -0,0 +1,86 @@ +############################################################################ +# +# Copyright (c) 2015 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +if(NOT GENERATE_RTPS_BRIDGE MATCHES "off") + include_directories(.) + + # Do not delete everything in the current dir + set(msg_out_path ${CMAKE_CURRENT_BINARY_DIR}) + set(topic_msg_path ${PX4_SOURCE_DIR}/msg) + + set(send_topic_files) + foreach(topic ${config_rtps_send_topics}) + list(APPEND send_topic_files ${PX4_SOURCE_DIR}/msg/${topic}.msg) + endforeach() + + set(receive_topic_files) + foreach(topic ${config_rtps_receive_topics}) + list(APPEND receive_topic_files ${PX4_SOURCE_DIR}/msg/${topic}.msg) + endforeach() + + set(topic_bridge_files_out microRTPS_client.cpp microRTPS_transport.cxx microRTPS_transport.h) + foreach(topic ${config_rtps_send_topics}) + list(APPEND topic_bridge_files_out ${msg_out_path}/${topic}_Publisher.cxx) + list(APPEND topic_bridge_files_out ${msg_out_path}/${topic}_Publisher.h) + endforeach() + + foreach(topic ${config_rtps_receive_topics}) + list(APPEND topic_bridge_files_out ${msg_out_path}/${topic}_Subscriber.cxx) + list(APPEND topic_bridge_files_out ${msg_out_path}/${topic}_Subscriber.h) + endforeach() + + add_custom_command(OUTPUT ${topic_bridge_files_out} + COMMAND ${PYTHON_EXECUTABLE} + ${PX4_SOURCE_DIR}/Tools/generate_microRTPS_bridge.py + -f $ENV{FASTRTPSGEN_DIR} + -s ${send_topic_files} + -r ${receive_topic_files} + -t ${topic_msg_path} + -u ${msg_out_path} + DEPENDS ${DEPENDS} ${send_topic_files} ${receive_topic_files} + COMMENT "Generating RTPS topic bridge" + VERBATIM + ) +endif() + +px4_add_module( + MODULE modules__micrortps_bridge__micrortps_client + MAIN micrortps_client + STACK_MAIN 4096 + SRCS + microRTPS_transport.cxx + microRTPS_client.cpp + DEPENDS + platforms__common + ) +# vim: set noet ft=cmake fenc=utf-8 ff=unix : diff --git a/src/modules/micrortps_bridge/res/basic_example_flow.png b/src/modules/micrortps_bridge/res/basic_example_flow.png new file mode 100644 index 0000000000000000000000000000000000000000..a48972b7addbc2894d75590df54080d53277ea68 GIT binary patch literal 182298 zcmd43WmJ`0*fqQn12HHGX$es}1ZfOHS{gyR6r>TPk#0ml8U&<7x}{r?R7$!8q`Tw2 zZan8a&#!Nc@5ejFyFFvb!5#O#))n)bbFS_8R7UI?CNU-og}NsGL|7h$y0C~so%6xC z2*1JE!b^m|F6v5(38PMtKOd{o!%!$nl(_Ii#W!(FqjswJMhAjxhc_I;(kQ98gmHu! zd+w+vHxpIJ>2-;w7)swGQQ(RR@@rl_k?Jotmy!#^_)6T9@oq51Pg`0sPg^9$P5#pp zp}F=|tPhtPl1Ohvp^qdkQW37k*&8L`RdMgN^X=X_{}B6u@c%rlaKf!r{?{*hd-I>k z{?9+taBwa9`TqCNZ#ERb`R@_h-fKnp&ugV6-@M^IhmPK4`SdAvnrtGoo=9(RQ%lQq zh|tLc2?9EVt|VyN8R$z+sfg+`|#nSk&#i= za({pSo3)8LJWi_9<5kz`QM>WJVL`{8SFgq@_x%<=(W(4Ow6y>5;X__wp+{^iiNn_X z+d7X+dhJnctel*E!}qzk2uz1dvIDF{Rx3BJD`%@+_-MGA^sLZuZEfwr>R1(tvYb=H_v{uiHNE>*(mL?d&xBP`Id?rjVoV5np50`080~ zGN20!Fj!#l{b%(BDk>_0SN(WrYtL!<@Zm$w1iYI!{W3B#cr(0b-o?cD*Bt$3QO(nS zJCe$uKR^HCD)Bvxai>k`h{NTf;wyU1fv`GQTbkBZR*xc?HM*-D?TSo?31(+!@yQ=! zd#Ytd!~HRi6^aN8Z-qxyNH+Wast{Hr!^6Y7K}d*>3MS+84iCRkR#ryDU$gZ2prD1_ zGb{{G)8P-T<bCLvD}yuZ#5ygZ|0es%QD*; ze+6Y>W7C)>9eb5`{IgP)#qNrRW#yZ7-6FHmuS52uUtedfJAP|zeJCY$wZ6XIVt>QH zvO+nl>1cnmCtpwODiP}g^RdwiyY)7P+z07D{f1-in+NZXyHbSRmUgeGsL*!}67^tE z$(fjG4a2y6xh|T+XfT70Dw#J0d++XJVc~1x`TDB`&$RAGRj3z^Xt*J_SiB(=cCfP? z5PRR8N@8v(^m+YKN@uvZm&-QAW@YO#r#8U3fucB^AeUtceFSJ;_L#d39gcIAWi4l_<)xS!wU+p-Ca!6vv~)?4#(`Et4PnXIoDdew467Q|{? zj`NJV$XiQb??{DQo~QX6n;mTZamYG7-J8aW@ql{CX`S{A;6fx?=a3EV5gr7XO*OR6l} z5Yac?cX{z}_>@Zu~Enc#=+qSktGhD^(`Ds5JZ8Y)ww-@ZrxjW^9$NO`MDm-*_ zbe9fymhoB)NKUrJQ+g)qy{?ow?lQ|OD1;^^Vv&%LAfXM>^f*g7J7HnZ-rgPq3rkE_ zH<>8+KBT?Pe0S0hp8MuwjZFcB>uZybXXfS_T3at?tCxyuYikEl8!V_lcz}|LE`y@T86F6n>S?>3k&qob5m1P zGrxcL?HwH-Y=@D~!3}M1kh{CPpSQNQZmoo1QT%!eK}~yjaCmqnGc)tzz?->FGMzg2 z3y&-;^6IR8Gj!-rIbPPfp}A9H)cfNzG@3H0m)s~)GmU8ZRbUWMR#RMD{4O?@0V>XC z(Ztx_yI7c*?0e47Yg{y<;8)rvCJa2H`z-L#`ST;S{`hd0fnVn7(|7u(cyuxt@TQk9 zU#^E6xB#nLrI({sqq)l6)YMe(eT~G^c6mriEda8fRj2;^WOES7#hNacPB#Z-Svo^(zkbp}L`p?vd@rg>Qu?kP z;aP0Mq8UC&dWu55fB*jTarCntnW9LjIDX{wCp0#^WMhu20(*OV+AYCk-#R;UtWF_F zboV!Yzbbkat&GBUynFRMJ-`2J?+mr;^@ zX5#>~hB5m&GN+AJI?kNj91&4biDuKGqR{kr>DUw$EH@)--i)S*VMReZnC|UWtlaKb z?=~*pmZ!kMk$WA5H1;5g#~ovw%_ABgCk&1P7wK4f+|_(Ny;MUkG(Zsj@SvjXAOU!)Jj@k+Lwi55Jt1Roe0 z-iG402HT>uGE#0~ZH=cD5)go=vT0JRCY2~i=I7@(wFpt!NT}uXwkJhQl9}Msr%&2F z$s&8JuBQxU>eWs>=gysD)&GX=v6v+ZQI2u#TEwfx@tPW`KK`2zu`TAiZ?%?e5LPoW zF|nDAa4!uNOOEVp4`@w8V7^(*E@d@rC*tPi?U$^Akiyp~Oz`z3j)x$cpg7&TgwlqZ zp;~T58{XDtetWpe@&3l-bpxv}B?_GZFl*BY>d=0`ho z73uS}>&{i_y}U>4wEsI&wa`#HwR9^sHdb%uTc~QjuGg55XVBZi!b1J$wh{V|Wt@ubt#jW_U33neG#f1}-P52aDZ)HJBU2P?&VyxJi* z^0>Uxe$y~c&{>VN^wlq1sKWR;qIQ;+bg1s4M!D4#T$lQ2|+y8vmYfRndg6| zVLc0Wq8=X}d8p=?&1^);jKwYj?)+%nuba#KpxS1@35XI^+&Bb57wdK;QEg z21s{&l=`b8wR96&yAJdg{1pbV9WzTyHYkO39!^sp zo3+%moFL$sY(3ZcTJvX><1S5*J{A@hqgqjhOy}>ZDfaY$GwDM`64P;zo| zN?a?`)6;CP7Zd?rk!rc@r#^Jmf)T;kosC;qxc8296zfALlrij<$O4~ZY4XS@^u1R@ zMVa-Y0&7MqE5E--GPFnKK6$yalCRg2_v#nBcnbNQXVI!V6w?s~s|ajZJr#esvjT{q z$rPgOH%ITHy2AI-3lar(rlzK}!xDf70R`u1ROmw09jvtH$a!8aKV5OpH{;LKOhqJV zxtR}d?r(MpQJ>*kz0zuBf<%CR?97LOQA7PO33%)r!kk7k?VqenuV-wG>FVlg3DF)1 zP}E~?AYy7t_XYt$eP5r_ihP0uEVbp)o@M39!Q#cP^{uVOjo;rb0jYmVO`S|nbg2gr z$Z9q74Ku|GrTzT_)07t@z@wqYzbLXfrphF+yy8Ja=a^|*c?GJ_&M(6@;+Qee-yc`6 zsZDgEa;^S~1J*_k!`-`g-&<;kt`ZGp$Vf{^1PTZUnAjw2*hxePX_{Ku+BUC@R?upV zyPgUlr6-VFK+P($zS{Y)yT;XZJvlJHFfY$7D~kcpu7}qZ!l|{%2BZ>PyiU5;*kWU0 zQ5(Qg?VBnYNptAM&KChNV@-&}$SJb2SZ0O_sP{NbO=ZXGjN zG5ft5k4z5gM@L5!Fek#mfdXv0yt2aVXP%XdL5gw+nr>6(9k^&>V&bvGaL7-Da#vmvWSMI8n@Y5^vAG9hb1)2P{m-O1e@{-n9UN4B)|m}x z-e&&kRWjZi<1U9xnvTnytsJiXU!Hl8@!5WpCxNSzLFPia6oXg4Dw?AzuH36$8cl=0 zSsf#Njk{prSci^`hO%86M1yo+f7ssC>M1Z8saTPQXB@)AHT z6w2p1Sv^!KHj{qF=qwKA-0B1R8rV3{-BA9j_y-ux_XR{&KqC6uncUu(LMOUa>BcDh&2~fH`CH<90r69G1+j~)~XFWYV+YTpyx8o9LS=MKir zn>P#e|NBHqYrF3*9dSH(r+Y0zd9J4}2#nq^(uk=rk>cm)r^Ij{Q$g5(_wOxc+i!kR zFTLI+bm|m8BCi!wbqI;52bbZ%CS}t9C3D*vSFS;^=kdUBv5AkHo0~)S^e>~th(OtR zUZvc*+$SOA0yNVbcAZM885vJDUg4^!sHBwRE&Y@giU=I|@~ok6`}e#JZ`GUfn4?aZ z-4)3Yz9yrGVb}s%=%o_#akCr0D%wZ0HB!qf3@E6c$5cojXgY5zF+MMQT9ADYV&nx3 zGY*4Y|xv(84BYj(o5v`fbG>>~43!h`zqQuGDD{%nfbO6aeCH zwsu+u-dAtB3pyY8BEZ^dyHAB(S+N3Y&?P9AQZe@~*PNa>2F;oc<~>|Bs}c{p-DhYI z1>`I>e`;U-Cp9~lG-g+by`g&aVgs9jGOybHz|G9a*a)>L56~jb?c2)SbWBXww4Ar` zkB*P?U5*dba$f=fd7oyht4js&7@L3~ZP%KUmi7XNVSDXDUsjVTrq?-me#F=X1--RN z9}0=)(}RJUr%#_!DsUFdVxM0ct0Jj#*megBMmgs>!scO)>p^$|!?Jd?*`){7?!AyY zVB7Y1zEVL+7b+#{e&gc7GE3@_(NTmg z11PKw#g>TE_y!F7-Iey%NQWqc&5Q3%kmS;+3iSPG##*8RNqKNjPEMw{d3bKZ1Q(j0{MCAUL5Webk_fgBg7qyh zeo%eSSS;WYxwyEH&kZIQfKhsBDNw+1r?#Ue#}_<3vi_o)pWM0VNc>x6z!he-JM{GLGh>FP0aQU%QQnIYO?fCUj|(-_ z;?ECSn6h%~Mev;ucbYO4(z~GvePxb>OQbwY-BwobB@Mmy(F?>zJ7#)aqZeQz7M2c> zNUaA(#u8p0NFhW{KtQ0hvN}EOfzO~k@7&y%20=>6&W>v`kRvi&V#+Yu)!u$}x+SCq zfv`~i`<@9D8yxMezc;jb^ypkQgz8O(&tyQs)&uEjxjrT01XL!*)vKPFnJXGfD6RDK-vH-`k?1d*b>nZfNKh8#AqHJhuOEzv}?w z@?os-*tv#@`Ps^AfBanV*e~Be)!-Gn>6vAr3N4-HU0A- zLQ+yjzil4NDNoHM8KojMCJ1$louy}%u@x132(1`M#P+DbpAF)EwQ4tE=7WpZqqmQJ zuJlpN)-;_5S@_TQeYYpzbuT0}$vgH0mOb zui+YdtR$1b?*}ZEpB@DT1(0ml-oAYc9nfd&u>Je@29}y5_wB`j#nB(DKtDl?U;E%f zWz33+iD_}L^|G<4=@us^K2U@uB_%Hga>$Ti1mNS4dzY7&7}{MuOj-yR1ymJqo5b+e zc|}EEb{#Styu7^1UM~`ujaB*qDYt$Th-$99(o!Fo5x&~|(S53r=<7Rw_i|+yLdYgK zpX|?-IUjPloa`H+TxVBcy2F7fN>|iaS(yL^8L#0|^MKOL5F)l@8Dsj6v1=F@53H=% z-GmD5Mn^|`veoaaK6`dcP>}p=koti|WWHnea>eY=V+-hE<8P*~MKffP0IWoPRL<&w zoP~^gm@0pZg98tWEB@GzE@1nNecL-a)<>+nS~a|d;eEDsEx(mTM@QE|HLb3$wu*cN zbI_Sgu<#6U?67%FP!P#|39HvgJ^|y?Ca(ej7QtIUOItcZ0OI1}(#JtjSUWu#Kjm0Z zKM(@oEd@}S6v>__4kMWq)mthtRgR1OOjQGbaKnHA;unQ}l>d5BdF;nufr5s^5Fx}{ zYtJUg=&E7WzpUY3j{J5zkTz88=MYH5>R5V97a9Qakn^B9>rhaf&mJ@^ZxIml--BHb zsTcn~o*4d1x}UwcH4rI`|2?Ar|7ax$iS*y&{Y|7x{rC94@S&XakG-$HeUyY<12qa3 ze1G&6&0YKRCmz&s zR!GEo)yc_8s4zELK)Z;7KB}-PDJ)D=+7`2c5V0_g1J}Lkkb^AzH`cR@yqP~T^4tlg zy1{B^K7em3lM;3EAXv-~NK!PH5q`Uhm)M|tUpE3~_ z7njut`(M(`dT$F271d``;P`71&e8JErc#(um7gHe0SSU(Ub%h|I$xH6A;NJmdq8SvPt?Bs2I^o7g=-*;|F`(~)Xft>=K8>_ z;eUVZ4LYV*a=jiO56>+D0S)s*5P}%8jez3d24SQ4HS9GfZD8FkC_=c0yQ?k0BhU^b z?CsHR&1rU#oK`5PJyU=`-yClbFdU0oGGLsS3-a8egm z1)1w`@$gKXm{Dae$GkA%dP9L$M&1IjETd{33Xy0My%^7jn`h6-4eCk3W| z>Fho{vaZI)^RZl}Q0#?G!^MP!^?PBuV1D^AQgk9bhE?a>7<7{xH*NqI=XF|IbKEg8 zO#ze$OV!rbB z3Rfu3-g*lK4jvwLFz_nteJWZ4+m?shi@Uuo8BE&|72n%6sFKstU!4zz4z78-Dm$A= zG=!XqtDZ%xIuP(d?Z80kklx(P%mlnN;@$#mc?cvvF~Fzy&VU42T~C~j0B);(wYkd( zMZpE@dn8Nby@loF<@GMtlhCaJ-haISc&_{3wX}gm`?WjU5ewiH4UjG7NBxLnnC6iZ z?XmhJj3KHP#wk`P zjh2U?*dR0}`Y9GbIUGF;NYTJr_$AFW$ffm7O(JQ=pMVDkwZ1WTVq${0qXshOwsZ`% zh)evtBi3)AMy^8$lOd7-=mwV|;6NqN16sj>fq(%QfLvz!Jr8bbYV<1vj0gt<#7gjh zmMa;Ok-$1*V`HOWjD0mymOrF=4iM6v8<^sSXm?sinH7wI9z)Jq~g*@ zIbMVJHN4W_Gc(#<2?7@rJz$lLz0Zn%G|-%Xn))hthD_L%6dV^g>>{HpgoUM5_R}2q z)0{F1HQ%6t}qW>fYTIoa9SGyHV23BoQe)eo&5w->zT5?!l@j=$QiGVjL) z1P0!l--FVlXnoexTbE$ecy9@NWAORYj$(L4#mk?!_4V~9O2=IqfD6UO#dZJo?FmpD z=*XSzGIfk*Gv}oBCW{2T3lBdJSpy{OFOl)uV7EX&f1s?aoO-BLZY9FL0u{fm z_%$e=#>HQUj@!g0UoZA|Ojx66dG-xJr@eVE7n<_L#D=jk&7-kyQWprD&pc0M4~7}~CY$~T(6WQmV?L9NtGV|p{Z?;Xnl z(#K!_4Z1I{t~0vP7g`6!|F=xZDJhmfps4YUm6#5%{Yg(;Fl9L`4~>lU0YOF_y@nSC zrM{Kvi3v&<7L0T7Y%u%itnnbYX#GqC3vF+^zj$rmrz-zF^*@zFR;hb}wOA-QLFYV!?*x`kP+&n*Bfd8<2z9z#k`l&(?z6Gr{WEwD%`{N(8fg*<?T8jrv+*?PK7Q&x<0*gW9l=Qq)y4f9CI(@ZWYuy zj|C!jeP8_}aCuDvlr(!6WR4gg%9haGfUnAM_-FZL69u1U^+AD0xk0A~T#y8W2fK>0 zb^9nSRq|J5!E;97rjfOYgWRfbZobIF!-H}|1Q(c^Ay=jZ5s9fg>9OU^Hyl(g5HD-U z2SUHj-WW_uN&?&#_3$;s-9mY}N0PqU54!>90fAJMWk!X5Ab;eO= zf;tTcsO4MW`Y2eAHLniMj7e`8(SYQV{PpV>f+(8u0iJ+sA(f8zLwPw5A_+phaR~$g zZee-1?h?h5=FPdT7HH4(0%kBsg9xCRq9(XMgV!o?fG8KhPjT{!K7al^Xs(w_R#x^- zglox7m;K*_H?xqdcyqQF?B~p@_tW%AZ`|;N(i;8Q-s(5CGs1@{(8}iCYKB(NX$$j} zC=^$2azUp(1(CD}t%w@aVXi9Yi`R%f!58N@?e2cAa&Iaiip!K3k@`o94KP7WM*s2qwaHa_k@b_m0$cuDD;4wv0H(?0O2fhzss-RZY zVhJ5-ckeIwr>4?6>@3|4b_Fs6_-E{N*+fw%Cw_T(`Nmwa5b{>lyD+6${vFnE5IqhV z)<6Y8L7^i6B;*6G6qrY#hIB(hsAY7s{@r&)bsX+gpl1;*0V)*QooAO5qN03(X%gQV z28L2sPp>Ir%AFE%iU2Dv=G9VMScr59nyizoL&hTz?O}MKs}_5RjfDKGUj-K+P()$u z(*{fld8}_}I0br$Z%Byi)UKuq0i&uLxC(ryuaR(RL#Q|$UL)rpoXCLGNKSKSKn#c7brNtV3p_31EHZTj(*h|kg&FsjF?^F5=QQTof!sXa3~SBAZ7$k z<6Z?ag=}R#L>E#`|9R`qohRl(P@6oxy>&s<@8cSEc5(uZ>cSg)`=pN_AIO_4fjz1E zaE0%SW|i8iyCtmYb#i`RNJUB-n)7heS$T5MXS9CvEHrHW`H9#P%D*Fd{O)h;;DQaO zLF@EDrL_c@SRF_qPXESzsAUMhiu6f$%3j;(KHU{yQ2M-J5E2(0Xb!xoz<|ZZQo~zw zv~VmBM$Em9?<^4St`pg%V~E92+sNn=Ts4?~&{9N$>LCc+giiL*VKzp&wYN)IRwr2s zKpo-&rFab#hlaks;-O={*9)FV&_j2}&(V%-KsZl;X6=bW6u=jHdU&8qNlBei8QffA(y$ctEoOARc%*FgQ3k);Z&4d_d*D1?26mTeo2P zsN7QnpAAhGwxpMj4>c?6Q&N!bl@3@dW0uqxKniV!9?_KlD5>_#v%Ia-vnEsJIMTHqcFtZQRcwK30;38E9(POJGW+;#Vv?5mFa1al*m9}23p}U z7;Aum>-qAG16jZQ>#5+~}~%DP;op?-PQ`)BwZY zNATU6n_~gy;dePAf|=Pj~g>6k)jaTwPD;c!Pn7gmKCw1!w~* zcB`|}d-Em~IRI>g&>%QJFg|k!x}bH@ostqjK1gE`X1l z%Xs^(t*svT4H)J;pih7)tD(Q2AUHU9elVXJRFx!Ul3nS)J;Qq*BpmS12!Qn8U@Vjc zGpaXuZYUWTz*z*|j|qsRtVMRD3F+YdONLQ>u7~*n4VW%^3XNo8Fg<5n zOpL%vi^+3fi}M0%rgh}x_;4D?fv5ELdVFxNN`C*6h{>PBxfV^@fUE$;)jc*=olFrl zJmH|gTFFEB8+j!N2r{fMx+$gNxN%_D!z%OBo9ImYPyzhz z2l6fn&U|<545a`Nx6~e~uFt-2%dOEO1EUN124IuoiYygFU!hDE*zC3^ufB_xGIj~TA z0$7-Y9$g1H{4P5BuH7^6)LL3wH$YDS)5#5+m64l3##==SOM8M~#E zZM_6v;`0Eb0OsjJg(Tv$WgIFs$AaiA{|=$ob{R<&PBd6_Uw{94=vJUHU%!Em@0XjY zNDm}@-H#vg&-2@qvV>{qvXukCQ!z6;O9feK;HqIdR>^}fns*h_YQKNKB0;M_mbrph zgx*n5o>kfdo0?zk<(C zh9Tf6T0~es4hdc3C1epGBB7{V1ZBMYj}2fkFsph-MiRokgut!Ad_;igYZ9sNAxey= zkZp*K4FEEO8hncg8i2Wv)((Apb(|uAfT{l7t;gB`pY@7+RS`Z0X|Uixft;e#yl33^ z86S}XOH9=fKQ3%BXdp9lbU=ZA{D^{(1+uXb+}y~7)!5ib32TAU*3o$jN+RNUtL5n8 zZ@9oKEZpn^v6$S9kS0)RLG48cGV2z`xi4S7oLM8t`H29EyiHH1GxwpTN}<6xXJut& zaeVL^VtWD^^zBwiH#RmwoL9w>B_% z^L<%_06rRO?1c4;U=l){=-`~i6bmMOsIN~0s{%z8cnmivd$%YlAFM!yc;bI{ne@Pg z1H}z?ziYrzP-2`LDlrW}7-yEswR5n_UBg;_8FhDnQU!SlG4vsD0~{z%=_8Px`^U@@ z!*D)R8DNKQ-)ALcMd2FY6T3^zwZP@?T9>EOFaeffNCe@FIOoy8I#y=$2NzO3AIu0a z2BT08yDLEm{RHy;hjIxjD*DGyoxwGl_)X&iG;wC|$paZY1x=ICd~_EQ5%f701h0X& zPFo?sm-t4p+BG0)_V)Md!0ZlH;oJA`NF#zQ>;?!0gwJ=4+ng3K)PZ@O4ji;W&=SDz z0W#gW078~#xIzE`EnTu8ngKciVs&z54jj%GfHZV9->9k*ffp7CFgJi_TMK;w z*Dg8GBjJg_7#cb{bX0=tiT%+u#pwg!2y~2%+e8I$IG+H;0)ibvUEA7nfgJl3AQ{vP za5w3KZ|`VdR9K%T%JqS8?>Df7PebhNL6Zk|a<AEky7D16btghE?ATInWhbz@(WE zhAk8=)+YfdzSk)P8LbU^yR(6g1G6*=1+pT7TR;G5Poqn|DEn6%pm5o{brFmFD#(|B zw-Fl|kRIU`{8Us26v#YI91Q>-LNW!8TA)}Ff2oLoN;|fko(>QzAd?_xLa@)HVUhFK zLWU!_)$V2QgV9QRJfuUOf9M7_!RBDH0G$T!^+)${IO%O|ZIKfvOG`@-jIe#!q@-7~ zl^N__{-fFv<3l-uEt>+&gF*pLL}mb}3gPAK;M+0+*#T-oU48vI6r#r>^y=*AjHDsJ z)v!G%#Nzn|?5+Ehwp7O9;00I*EQfxloR5i~9uqX7@N#-^e4LdZMMxX)1VUNrqX(_lIDiFxpg*@g$H$Qy z1+MZs7&R}V%3!_+e+0EPbk6gLve%mdEc686TolUD(GdyY)>iS^&%VA3!O#j599MW? zj>T|y1J0I`iAj2;AmeR0BoAa53WZpsprjFzi3tbAfQW)@6bjs#jnMBALxr`HurT6e zlcRng6GJaZ)YZ{(4GN-B;agu~PMBB$k=H?eMqvZ;`0@qJQ_0@9+1cd-Yx9eXy%G}> z+wmd!sz7u`Lr(c1r-gt&ie`Wgd$#qVfD`?&e5@=i9zb!`2Qe(e>~4g_;P5b@WBdoL zk4rW;HuQ7+iDO_Y!f;1H3=uG?t>xSUuZEMebJJ>JLBYF(1ZF*u=l)rX@Z$@^NauMe zA>11k9UI#KJrngVEX)J)CYk{*kDB_i(^vr9>#78G^6jLh`UD6|&86EQot||xDg*1= zea4)<#>Ihs*f@Py5fT>^6ckVofW>;_gA=@%Hsao!uJ#Lu?wooU1g+X~|o28vBVJ!rpfdcfAwig?km(=Ewj7pRqy+oIxJ{ zPw1{vOm=Ah;G^b8*ymxvvz4!)z*LDs1&N}=&t8wv;DFSfh#$q~AO($?FiB#cZ{1DZ zrjL+-G6!J>^vl^cp+!j0I(EQ&(Et_l7h-WfOAT7CuYUxQcy#0hT*f5utI!12wzfPW zgdIGonkhY$0Qa6fdj>Cu z!*3#B06-{BM3ew7m|8UOL7`y>HW^tE@Qh{U$Q_hZr!5{{v0XeuNcrt2lAuD%cdHEWI zBxr=7AE3ifi8#oTl(XPJu;%&0Jl^))(0)5Eh^=lD0!Z-Qn&)t442Qf5Q(Y~|diClb! z_!~HzM@3DI11COU(0oy>hTH+rZh%8WPtIR}qR+^+58{PPavav-mfYP7pL?gL8)G)HJy81;(X>522Y zW2yw&LplI4yIrN9&I5vlGcv(oq>fxlSEQn(L;;fZfipORwX40EcwiD7EQ5*VGu_#E z1=lZ^lGf6iaHFbOic!{IOPD5^O*97>d-vT>RHP;$nDfEm7DPctJdY)jo07#R3{J07-G zv2Wtj5}rds)6>TX{m#p=imzX(SXr?V`S2W^{lwpGFGuc*?|<$JDc}(Ih>-|D4pK^C z8Um=QHF;uOj9Y!Ip>1aBUgX*GM7GnTJc77N^TmbYOx%1Gipilrmn>HGeNOO(sTKzG zk6iWym*Uzdw*xuMjuZSZS%&DCWqKw^)@~`W_{m*@o?owKZL3REm&9vNY+cj)ib z!v^5s<6i(+2}H#6YNwmv4flYyqw))e**^9&DFVq}Ilqt)u@^7y06J^zo1#jZ5i)gJ z>M6IoGH-Lv|4Q*U*XMytTaN|@W9$0st}^j|Nn+|p!@K|xlhIVVr@w`~{#4iM6{%Fu zqL=cW_Mf$%qwl^V>-hMT{@sVD0JE<0`d_1%70RMX84s>}q&XA>w-$r)7dN125rtDy z@;m0D5Qx)=K>(-@e2{vlY`xCCSRTFFU}*nP;fqIDEI#kHC9)N6C@F_hhF9_JN%9OZ zjqraRe4OMqsAxW|hm|Ui79rlcczc#U&?SZA%W{V{#OjdZWv_F4uLlHf5WZ~MT(IGV z;qVq19AT!3VmH79baQqJT8`;I0}^q>($cF>ptJ-XtUMl_80x$zQH(1=`;kkozOD}! zGBrb5V(K|SK9h>~-rP@rOen`nZ2rcVxX@OTF5RKT%E|Ie?B(Z2b7P&|+cxe)!j}_K zgf~v5eVj>hlcWh9XAB5$3G!Y+jxEingdk(u`Sa)J4F+49n{|OE;07<=p0@h<3G=t_ z%%aK;Xx?4xj}|*SP6h(aFGi?cPA&LE?-(f*dkW3}x8tANhV-qACBcSymaJj-wgNEk zSuAUNK0D}A>Rsr5NDJ`z|M01l6tE^_#DH+o` zTs8H&J{sR$H-7n;uIO!X)m_vCke7o+FT-Y%a^UE%2ppo^!yX|p{la!)sudMQ-?Lo) zVQpnNS#y!_Jlf5>_GM1|mqX+wj2F6-&`C*27mBYhxDfsKy#QyF^1ob+u_7Wjft>%M z*mX8XY$-tGL{B=^`aIg}p>~znJCnoX_|6B^QT`>>4Vs zh_mk9O|pr>9|fHSladr))qf2W*gW_#N;+~vEj?oUcV?a!y5a_zm_YomMXfgj7^Nwo zG*GBiiMPs{wt05>jVa-k^mF+5FG3@f-HuwCUjHa7&A zA@LxqZwib;-7n~C))19T);oIp??&`ysH&=hg9Gz{cwx0<4Z-|KIuGe{CWiQwr{Ob& zb3)9b4)Wypn$+%Dm$-Rk8Dw*{k5N3D(eA+!!#)8EpUzj00I^qNH6p> zcO_IEj_n(=fBQZF=Wad^1iZIbF>!xKyS8y=|MzT`R4%z>JuJFG-k8a)YHoc&MmH2% zXJ_Z@k|A(wX55`_`^Ob%tmx$AgiPrG|6cgp`0_>v#sxl#Qdc^0dxl~yWq)`D%Vdxz z`k?~N#16$v-#s=0JC^hm%2He9;VkL!d9DoF7@k=4JI^!_WoBu-h645R={aanb;VUo z;ce;WzE|Acz7(AkPLOKOtsFPo1C3UVZ}Y~@R0c&5RYx!Ohs)nk(hsYl33%ISIkcNN zF*;W8v0wYVw(NpZm^vO~2?%RxQJ~62ZY?MizK^Hi zUp_`3ESVMVI^QvT_;TFN{b-7H+XORHGg{U~yg#sS>v}e451zQ@ajV?euOChG56-z^ zxvY77Q7e`>ai)SRXFPX#(F+?c7k)lcTi?4>cEm8)1=6X3z0*&-v5$KUb4s<+oNkxZ5&!U-jfIuI=%c z*iSEe`ucvKn2EpUN-gF|*HFqe?eME6;?tU+t=$oP^vk7ROSARIw#bbS-m*M$lLpZ- zkNFOMZAxIV+6%OYOEVHYHeu4Kf~(8Np!q`h_aZUYO+W?nvEY`vN8BX!lIwWI>O&60 z?e}&I%G{a~cON}-p(okAli6w5bSZM}M@aD6Ud{4!am#S|)`3I+bNOH)?$hgqecw0N zFFDcZDGyCwNPTuA+#shCv6*)lzvba{;@+RTmu+^;7dJJR-LQH@CN69ZXqCd@fwS6li}M`{=G$ zSMK}^a>JH>vsdbP*L})Cu59hVG1KEB(VRbDi z!GFM}V8hypb+W}I=y=GZnER~->?zAJ@|cNOo#n~?sf+&mtBzO&cIsHCyE|lGPM=&L zG|$l!m%e^dyM(tQaktmz^xjjt8p9-0X?C-olGXEFRSC*MAHX2uvT(v0Szu&Cc4Np~y}9L|-4w6wkk=vRZKb>$=QV zbKbH-O-RVqMmB{%T|Hcl&GIzO9XCsVIhZHw4<1KTQeqZK1}qzi(&FZ%^`}! zC4D{6!@-T3@6!G+53wh-uTVg&mcfzeyG%?1)6U3c={m?iV}a#k%=`7o_VT2wK>HRi zZwQHZ=nf13G@jV2LWy0G$`>?M$tRb-Ghi67w2Mt@e@L{>$@uhzIdUNJmC-3l6~DC+ zhnVeks~$SzOmzirQ%RC+PM{EJrNaU!soLXq$8IYT; zw`}nHhKlHqlX%u{&bpk)uWad;7afP2x%X^^3|{jHZ;V|TXZkriScfyV|B}wJWc!_z zDxrKC?rcT1ItxTAfEBH#D)<>#$V>N{MI@P<#Q%uJ%*Z&H`KPJ>t7i%gQ z`MFRd6gKa7zCv?hw!X!`#xxx5imHynNOm&Si zO8gyE5~ENS3o~sEO?wwPZ+(KPz>%&xmPdk1L1~gF#mtw!MWC}eH`kO+(N@8((KW|&wKXt$cc)I`ZnplywcvO z7|P;OEJav*=^PrQ6Pzti%gcNB^v=wQSsEXs;cz>k? z_W&A)@ms#|n}QxO5&KS43|YQ27Y9#9*n-JOXN6_2x^`>Z+<6;OU^LqGR5tK_;-87y z9T)FIJsLfNUl$%S*I3@A7*v$DJ?Tx@G2*v!3!-wq?AU>Fg2KX|370l_uiR=p6uH|(aa2c<2e{|e zuwj`{vx#g`sDxVFZoaVm+Jm{)72g3@`3_(G$0UEZ?=R0rQdCHW?X zxRiuqX=*%v@m6hDpLjlD!U&68XWXPpHLZDW)3X1Wk!9TlLdLdrWLrXI>K%|ug(gMV zZ<0OA#htGjsG{W@;kZ)n17@H2&`=!t%o`sJCU+0nq!rwUweVa{9ZxGAR?6qf7IP}f zz$aP`->fm}wV!6<2PI9{Qp0ZawG(_F!QAS}%4(jpw7GitY4ssx&ECEx^Wk#pm&%Xf z+HWQaUS9adbk(Z$_4bl;YGi)WzR$L%q;Wy{{E*sFofjE(?Y9SUr3nJfJ9E55%d*i7Kp)BU;_J4ul?2s0}Cf%dMno~aT0?me;?uG1s6BB$ygIhPZS?(%o zsQy9~@-6zx`EyR2vE!f8(!9Ye77v!e_VA8;bZY(+*PV@g^$*r35q(#Py-i3Qf&&wj zm7LR(rt!9H0~PwBN>S93ozYc$8-NXHnIYBY{h$-2V8Ch28u*xac$RlMk$pQROsX-z^ zy*h$8G79mHh3Vxyl=;5j<*+S1X z2k9v4360e(Is&X3xEcww|fz4egi)SGMF|vvn5mB{}tSP&w;($a2&^Yv!}^hVwFyQ#?6rMRBVxptD-jnsjv z3to?;bS4Q|_3-w2}HP0S;b71UX$!#_r zT#EbR&C*kHVNiVXUtoTZBh@lBWr7mINpU^SBT0P>hPckLk;#-E0tggWy*sEby} zKW!5}29%QD-eg}hKzzX0V!xfALVDbUEjd8glb7S$*34h9>8_A4?))O$uEf?VnNE~m zCp3!H?>gPhKOrg0t^Nlv$oZQ)O_L}pDYYKHgA%kZNprSKmNAtPTQb}xF}IO&0^gc; ziy)x9W>Zk>=zy=!B)ixUM8ut)on1>|2uVZSs}~W-{bzoD!g2hN{P_5o<~F0laLS7H zhD3dM-(0sVW7~sBDmF8AuDA(d*+3Zjyd87_3KJ^Ev=0HQQdpi&?8D{_R|gGqL-$MDu2q-r~DAY^~(cKqFMQG0(yFS zn!nl6`gcn@-R_4gNwD$qwvm`uK9rU1DpJ~hgrdQ{?Cs-|8UrxVMFcoHOZZ|TD}WaT z;8P`kGl2$`YUKYg^%YQ6u3OiHq9}-oG+2~0NQa_;(%ndjba$(WG^ljTLDrq`;!Ey^U6NXx3oyF|o+!^m5 z39 zjhn2izklpvl<=3Pv?2>@ocPE{0LlFPf?+}z@6Er$5M zx6P!Ksliv($c-%6Bu z5|*XRki0c0pDD^o^z1G6zQTL9@2$NuwPwPrS@U$ewrfTF>B?gd_oQY*#^rM3-U%Og zE`EcIjf^4cPR8rH&kl9Zf>=HONWm0e$^;4A$DjWN@C4eNN1Emliu7szZF9vXC4J-L zK}H%RAKseAo!x63=^{ecb#1t{aSYogv_Ddn)F=5sKEyf2OEcNj&JHg7c6KjRF1 zktb{OEUZW^%vL>&Q#uge*&*D`&8>X3bR5hGMZ9;7y~UN3ZU`sKO+~|3^w+)q?`$Z2 zCwRjtQhn$l%u^gDo(kWRott~{LmTSSr^GiSM+tlP?)MV-C9=C1?aqn}j-+Q@O*(Fal z5LYGRGi_eXAN!sv>id)Ss^mrZ3HxheBPMPR?|8PavX0}@`5f&rZqIG-g4k39BE^K$ zxMc#AXZt7DZy{--j$rc&6MW|cY-?U2F0N=@q;EP=7DV?#2(PQIX&`z9go3kz3tJEhMDNWoxQj&3UX|iu(1L|Ph zCPil<91ry<-yyQ(UJ3A7(mIcs^y7@Gcp0t7_MGOb4Yf0^oOJ*FSZS6qookxrP_=){ z$cVM8Rcxn+Tu+qqsHUc7!nTca0xq(ZJay|Y9F^~=;7dL1o5qBH99GmV5A`r#EvJLv5!dxVcHT;;C+f7xF)oacK9Q&3V86~BN06omGd zTr9_-9KJ??Hwr8&bdozugWeCqfSK(kH|vtBy#i%MF(%@BWFY|FBK8|5*4A`XVJP1X z;pDKwLXO;;T}>Fr7FfDVl2~gH11Ag(Rwapwgd&sW#!G!5bn5{{j2s-vw~uLZ0=;Z( zK7!CF0L;R!65#PIXBU;vf0pupc6UvOP?F(u`+bD`3+fW*+k1%tLvg@I;I^9h{xeMq zdty!_O3d1t716!|qs%_pJ3Ym7aamqbQS|B4r(={P*8`y>J2Hm!0-mWc?wFeB(^D@j zyNxZ|)ZqAFGf8C|*`omSAWOH8#;Y$|WmU5-$WQ#vGGMrTdqCi3pxv!S#?*+XL%b3s z=xbT=cDnvs49z^9?l0b6vJr~R-dxzspX@ew`^bwac{2`@;ZM)sL#2H7B{S2kp$!Qp z{z~EhBA>6)`EOG;{E*bWBr>6S22=>5SF4#!Jbl51p zeu`Wkd;;v62zhKK9fuV(Gy(=BuLqF!8r3Fvp7VLK zw7fjofwV^$)_$&0P+mi8a~r$_u%4}NFr>aC4`JL?(TfsFm6l}@&4Dw*KzL5)cK?3zDCyO>&cf4EoOEHg?Ul_M)@jxRYL37 zNnVGhOG``pJMAi43&hp6&om$~!5qM~p(7abiP>j$*fIlbBY zx+P|}bdSb{e=jc^0)N0Xa!>X_?Ve!5R_L?437)&76CPXLFnkYy`&?`v(l!T5+!(O5 zii3I8e?geHk}tEAzk$ZLc*{<6*(3+; z;oSV^qOT~x8K0ArMT|V)UJ^$S#WgfMS*ty=0#yK(^zOH_n1c7y9E{)N+a%^!56|tX zuTmJ@UESDzpnY2+bTb@vOhRU%mrOM`ouhgxQW6}==sdJanD(ttW8znqK^MnC1(kz@ zr3Nu*|M(Yq4Dz4(uCKl ztX_g^7w3tc3mrZdWH%U$FBnoEk*KJsn4TE^L?W_2c9#7BA z?AY5q>Zea)RYis#0rnpPc>L{rm68vkSh{7kpBr(PDr~Ej+@ZJoy&e~_Mys2a z1G_c&?MlRPj|hAU3fSQh)bH=_7tc9_T90!d92{ip)(PjR)s@ZGWn~4Wq}-A2*UoRh zo(E<>adC0*C{5>JZcwmqF}?_joduN0Nyd>g#>}olJhI^ZuLL?dZ!4m8R@LQ*FI0N| zH;-1?SHzC9JVmvF^(%MQ$woR!&h#i>CkyeTJV_)KB;K2c*u`P$w21`)% z-y_&^FY+(yMDeQBd&3Jp8S?B(O7!Cvvm3I?2tfzFGF}#j#2h`gn4z&2@`U6o)?xc# zRRE@3Pc1ET+$oHY;Wz{aUIM<`&mIUL>jO%12<~B3`G*z^L?$xb=_X2ZqKjUMR8Ubq#j$jnC6=%Q+J+ zb0PaDr^QqIY#P`Y!9}6dkr5K$U($o3VQw~v)#<280M2Zwr4n@6Fqa$!Up}x@u*(|p z6sC?cg8bIr)3cbRd%~D}&}EDq+M|AfISMkeSqYKDYu-m?-ktCZ1D-VssouYy0-iS= zkL+3zq1)l%;p>%XOw9-5L`PzfE5~xvQ&Uo=)zl=Ka8=UZsq96kLKJ}i6u%%xLL{7? zE2S2rv!~UP3;9#u@A3N81zB>P89CaQP0HR}j_9=k9t&4s%xc%Wj$eu@UGZiyCx z(ARB_Rt4^qTaE*1D<632YjtN{nORvV<*x!lQ%_T_QXl^C+wU?Ke(LPZ1BYs)G{i^) zqO5|JR;TXif-aJH%Ey~t3E=c|Aqhuhzk#UyXsrrr3e(}XSPK&q6B}GFjO(*h1rQ#6 z2S<#F6St!U_dItHZh=by?ZbzcI}6i;jr8>1fC-+n{;2QQh`U!W%B!hKC@Azrw7h>% zd|TANWv}^$oL(F)matxAM_SUwrJJ8hhvF2ZsYL5^|twsFW zHIMyB{)K|q2C1<>h~bP*Itf&5XJ}0pvp3YK=Nz-pMrRm^cEoIyUlL3G)FheMq)++4 zwb0#@G136yn}d^+qK=LbhW&4oe)_K?T%_mpclM&9q%;EY?fvj}jlG$3g|Z73Lu0Fd zk|fjQB`XG(I8{b^7f5=XWPj^uYD%i8+)9x*k$j#2{X5XuB03z5DcWCs28-KI;EZXr z)y<HU<`!MW8F8qqMAM0w3l+7hr|TQ#`dA z5N+_=5duVp@_n_{|M>#6XTv5IG-;LwBf*A0 zQ*Q|79l5rzC2zfIU^kdBEn%OPD){tZ{zgo}U>J3aTV&fqf}g$aXGx?~RIlNY{u@tV zZv1OhTsQH?G|i!goa{ z#+eV~R(e2dF}-z?p&SUO@TJFwnAd(2^(N@MK0m)dQOfrc>RgDe!0DT_!qiaV;^I0u zI_k%zSNU5m?$}Xjfh-&{+?rR-jl2K4-NU0J6yecrQ9#Q>LP8+Q77yz{kev-`F#vDk z&XbB5nn#@55yOua$GMi-sS2uGWr!+op|>JMw@RsAqo`6Euh>U*=mUPC?fbnS`yB~y z|9RrLn{o8CC;TriuxqZ+UkEU83&luWYpf4z#QQvQzW^1S9}Q)dBb(m+gZB!ukym<2 zM)KstZ{Sbm3q#>PG0_FMK|nvhGlCX$h5ak1NPlSdPfSP~8`ITi503O;62YcoUXSEM zl}T1n?<)@1u^jd4wld3c%Nj*>_1~vc;}}m96MqoS!x2TD`!1X2CP;+_sq8|E9~JPj z-hr&7qM>f@03dyByY>gcVPTxY!aYEhmj&w#&E*6rUcrge1z;{0kQMVf{JshrnAJ*` z-V`WP!R+Ar6~F#gD-t}&3H|*~<>bQ1^LrgmaNlA97t7{$N4Etj7t~hJ)ZM#xPw8cz z@0W=G3JZVc$VPktz+p-knkyg-REnUpupabphYy>ymb5%{^QT*xTj@(h1^;%O7B1eMVb!07Ff^Pq-LW5hRAG?fH0>`bpy65G|oX6Ff z#NktxT2=*B{tY7=|CjHebcUP+*04n%Dtr92>Angf{SN?x^q?%uasZqdcqm(t$~d^V z&UMvgPE|qq&q7E@2zNA1<|41kF_h&LLT(Nnl(@3;m|*vRt_rcOt>TOiA5NBX2`95M z5A<|)&H;dmLn9zCJ_!PJg8~xJeDEVpGq}LnyN@TE>5m*9xefks^E*?r7_X%>W zp&yhx0`4w#MZd@WwITeZ;;^lElfAaDlX&y!8qFf5d;;auMdxSeY&Zmy>kZ!Aw{&|a zv`geILjj{^P(8z^ZFYV%i%(+?#}`0*t+ZPJx@bAI*;y?=uLgy7~-djW0u3%GjhGU3q4FY_W(5!=`Q zhqCswPP$8-WF##Uz6O)xij7usdYTKRdeIkxtJCZ&c2SCma@2TI&X;VaI5 zZ0(YVGKx2o)=fBc?k|5Ca9 z?ak`R-eouc-|hRJ$yBLoZG2zbMpqu96pX5bwr&MZgd5LRr}AN@1D=Wg9i`2B()=w{ z*d=0_6^e(T{sgp;+kBba?}n_JiVC8#0vL0`i31v~C%}%+A`#JnU<)-ea+;}jdq(s( zcXvUNbUj2IT`U5_ej@6{y3^%46Eib}i@4^u7n=(h-S*z!;mSHPoQaAe{@ngb^C1&FJ`H(OeJsT0*obEP;G4b&pu{A`&`7v&-H3?g=OdqVd%moOnx5 zZc?jAl@G-bRB%4*M}?zsvXxw!21l8c_ykRy3+2MPUAvGU7*%Uhyld~3#}@IQKh150 zW)59$sZ|TAqN>T4+qhp{#P{sJlc5<^I`C583*N$_rDLPb>u|>yr<-06YisZBPTVU0 zd$QgB?_?_m!fXkp02$H}aN$c+`Wn%E{zczbP2 zH`dxl>l6c_$Atr$o@n!3FnV*-4opY+=CRy?;*gO!jZEB0Bo&~> z4Uq)6tSXzECtpqvAkv??bo&)l^8oA=sR%d4C`Dz+q$xHV6u46BB7or*-NR<&PZR@j zPyy(-VUD<1{X0%E@cI2lfSfc6U$sZjP|)ITFD||Y&;Nd$*#nz*%h1%phkv23pE5qw zLT<3Pvx7KCC}s>K>@Eiz!D9jYgNU*zx63Yh)MpNsI?!AJAg|}*;?f~nShV9&W*HA6 zd_>(IE=}7{%l$g@`JQT)dor4^Ink5X6J6uEllW`uVAP!eQyZxWB|{K!^^5KI)~1g} zV0ie{)^;Ny7YIK7zPCceE6z@j`l$q-M+mHPC-v7*+~YQs*M0m(%cCSbh35%D+QbmM zecGEh9K5=>HceAMbELCaEUP?w0}m?dQ;02Ic*P~LX9wkqk()=gZg-O|*5iq@jpoX& z^Qc~~v#f0*o)kzcI|ZhbD`=T-TQoTStskTr|5CU52LKQR5-EH4=F!?m zFNo#8l#~X`dvk=XH9>#C^I+4@d*5$mq`=37YiZZ1*MgjL(v?09s=^tq=|f`J_JHsn zKmt?z;sOn`jWgpqbElnF52VVzfdP=E6u4`n2t$YBz`Q3P^y9@ZE*n!%eVHb2BqAi- zfLSaXH+Pg1OMi(J4lhu5@bP?Hn$ZMUtICZ zb+Q2s$jb#Khr+O9QH6T6$D@^g!|D`c ztC`!6^;7zBPC#3?mB#8BkmtE-K4H^@_{%-l`#XsL$IJA0wRxuwJt=Jesy^%xn6VHO zI}c|Qsl@fv8DQv(5K@3(&oHy@;oGDSw0?0hG2be0(CPfeppaQ!ixF!10)}uIHe#xp?+Urd zxFck47?S|h2w;OuR=V>V2MiD>_#OOVT8r}C*IeeCd^E%Ke7QQbpP8cyRHN`wqPRcZ zx#I^jy`*P%8y@CWH|m}Y>TW=EuG>4kp!`WJce4)_PQZ2&$9zdWv#_E^?Mccdmi_%9 zGS`7|jqRoVh(&=N#vr^~vCdhE6&DTGC2H}m#3_7;;dfP#B3@Renu}Q(G_(qHe*<$l ztGW{>h0q7G48siK=@6b2^(B+x`R7zICU#DcG#eFdA6D*Mc#jD$*k>>t4AxOm>@XTP$ zSKoMS&%rP@_g1K4Aaude;6_<2Kz#ofT%#8KI9l*uo)?%txB`ZaACA0;8`^v`KW2q+ zm?_63kNXH3ILncb7|+b5n&CfG>G?01-M@j4G1+dy6ywl2UP(WNxR$?-vwW+oOSbkt8h>SMY~RUTc9nqT_}K?!@*OX| zRznPrZ?OSiPeNQA@sJ~TNX|?P;u#2eb{BXf3i9$;ABSpNN-fKXYKtagnHE*GwWXDm z`hy2I+rp?(MO!sQOR+NrTN9O){0JauRkNcCgOA^MJF=Ha({AR~?2;(t3rH9B@vjS`AOi>d)c#5<+N@FlSFcdl6UuXtewzmM^G_39xl#y~jH%CYY!~-y zYZq!Dxc+)~IlcJLH7FR@i-(}Zv1_ArMhI5UiqM!QvuEySS~EnGhz(?3BoBFzfZ9Y& z$}uCQqaKr}W0he=M?-Rfw@4t)EgCK6mpX~q9?Hxq@3+64SVXqDMM^v-eZOH_qR>iB zN~oQE3E!o4bb7iMsdS6LAV!QF$dd51B>&|PR~ykKpsj%)5kLCND84D!!e~G<4doh^ z>E(jB^mfQQaEIwX=$B(R{eh}^U}y+B_+)N8x-S5fLZyd?hxe0M(2;Q|@x1nMo^CH# zb96l#)_w{DX|FmFW(Nea0dUac>}VPdu7E(`4url(c=Jzg@B|D`p?wFuONI|3+rQ$ql%_4-stQz=pjuqm-GwVt;L_UG z<~kcd=W_T5_2T|@tca`gTjGRjw)0U-A5+|{0a9&f zxq`S=Apy_wg#6?BZvEPhv^F(O$;%^pZtcl2UJ7OlTwGk`Wg+gjqhZ7c0}7Z%B&lYI zOiNm%-30jg!v{Q|s`iVz8S4U80qW}OK`j%$%88P$^*T3qp&~)2$6NgeG=1P1miF1Y zEl&fb6&bTuL$?Iobs;ztAOjkh9QG3rIO|nw&>)ImwBh3^enh=YSeo0!8f|>bm1*r;6J0KGO%mRdD@c) zfc5%U%kkvFjJaHr0pGUwD3UqoRqkxQ(Ea}C&Fnq#_W!nn_c~g6((H7xTmPeWE$r^C z$gCHV#S+W7bgjex;<04k*TMtK)Xzm6nmCrzwTT!{jQi#(l5Ux3{)aFHLKKFe4dtuz z9hDd%lidRk0LWl~7F!xp6a%Z7(kd!k#{v%z&h1Jv05*>(BCu?N7oJCt!E=Z4h677_S?LVB|thr{iCmM<`kfqO`z={ z4L)=b3QGe`XfP8KVXqveh8Blr1t?ggz_*;Hp%^O3ZkK#G6D6sKKdnF z{Cs*$R`^X(gNd8a-Z$V`93jcmG0)IABxcKaEY}mq><}pmU)JhzADbiC?-hy#S*>F|a zsuT=pk-85T{jY>ZdXd8HVs6IR978?3CpFLSzq1@iP7E?Ldrb4ja@_RRil#X<*T5BD z_$e=<_(=7DLd#3^J)fNyyg#2S{1ig^KXkV zZd%$x@bHBep-VV4&wm3iHt+mn=)ZS%cFy@U6pK8a+PDPWGYMkYtD~b+KhHdWo5VL;v4RA( zUp4et##Btn_}P@-H>%L(@^Rd$l($b3U#X+$)q-vhWrfdpcBg!APnOjq=MjKoIX2Mb zrhohPo$zA~+B7a*fKN|@7@{b6i^hWw>tE6Zlz$fosSlw7L2H zxSPoxgo5%dGxNW%Utf&{5JL*MEMeXabD*VDZE^ocjLsavNk&y&QJm*Vg;s9+;9Xgw zU*uY~s&q_Xp+rgh-gf-?IAuLq@Lh=T!F0x5cV4+$>k&)(&ruU?fR~MyT9OY#XL2_b zCV}twyJ`OEa`Oi$m&rGYt!Q> zk*gQ;!PS+e?%3{K1C3Xmcf(-?9BeXjaxhP`Z8I7#b(ev<01QcQBcD8+-Izn;SE2Lh!Ub4g3lZ8|jPG8PF~q>` z?rvZV?iGw`rt>xcRAmk|uN}30<}@~-cL=33-Lz8Q5mafQgS-caLS?&WtEQnm`o@^R ztqu6x+q=7;CDXp;<)O;UM<%0t(e_7u?pkfUgB$R<5li9;$dyo&R6eOKJCRv*b$e>v z&*chpC07_4Lm2`kY8CpIa-~*O%g9Jfl_g_j+)rKa+PuiUoqVPsNEBBu`KC_@AzO;# z;^W~3DU}LP_Bc8~|6ZuoVOzrS=4urPJls!1rRr&>QJEI$ZKgyLFWmz4syt%dnfXg z3PdM?{yn3fkN;XT0uCQz6q&o89*t$ekJxuc z*7-U>vC=S3j3gf6$F_wY8!BBZ`rHW6_#+iwA&`fQJzulDS+XRZOFXxZx6!i?^REdr z7Zi0(la>xA!yfroHMXD8gmJ0t`>Dmycq%GfrZ2GQau*jFxm3+Sd87(yt(~mc`R=rdY>@x0p z*kOH_e(OsuScWX!c%QFOjsk^zYf(6u+&S(C>=#RpCcbGtr!YyDi^3~e0*=$a>m{i3a- zJ>>cBO~+kWg1{SkO!JtFOh(IMkQB95#M9M7(9PN8g|$ zh34ydmgG+AQ5BEbW*HyC+e4|t}@dODi<$N2iibKi1v)3dX?bOu!2 z4nS))YpeOI{#91gD2{PVHZ3*nBTJ(b1tHng4vlr&q#rMmhCPef*_Z97`_A= z(MmB-h%Owyx^~BGxt7|7-l~*V6lM;!!dhBc7 zy29;AK08JqtU1?pf&u(Rzos?Y>cQ0>!&sHIDPKbrd9w5Mh6CZEyVJ3cZAy2JPS!>e zZ6>SobL``5loYH<@Vx4#g=Al!uh~=YsZBK0ap)5}UamWRn0z#WriXz`Z=1#nw>^## z?Uel`zb2$PR#)d;;G1Ga^4h&sj2qV?)8#arVDlhsMWv%ipXAGqMu4c_BdkjH1r&|TU^#Xj5$)T#)ki;tr_6O zT53Yq@@I8bCQC3`>TDB~B0c=e*~OVQ);3dpeLyLTCnson#cM_K;pnU@pOP$y`l@=K~BnWb__@gQ?&ZT25rg^LZlO??5Mk^A;=02$>}lVH|C6oY1^IhEu~G zm_5Td+6|Y98az;2p<$~zPy~v=W4sJqx8;qQJRh64D(!6r#VX_nIyxDrW5@sF0?-+c z4ND=RyQ90?u}jk83nn46yb>~(l|^UR<`@fXo1_9fz1Oi#a-_b$;yUMqM0y`PXf{!vyYmS98nD>BWT-Tud!ezjg| zYzwhhQ%kG=aM1VznlmFa(*U+gBNQDp{}Hk?^=~i7MsdYYqsHwK)bwA9iw6h~P|Jf> zakR*u0EEh!Zo27Sx93g(pe*=){umz@Sg6K=u@Ex;f+(JRJWmI`83O6TC=}>yUkeLA z{~NGQA5HCn)C|)4)~7I!_vz{B#esWWSKTcvf)R!(An-vzU4@sWrfqv3gitTXaEfAA zEtxtE0M`-(^$Qk49!8jbP}Fz_W-$A*n5ZaS+(j8&@c~-95^SH$N0X27EuL;u&i&|64FYa+$!cRU^QKAA?lvp^% z#e!dnpZ8)T0qSN#-v|VQi~s6i_IuV^(ZH?)bJRvyU6L^VU;Qf=gpvxQo}ZePywd%z z{!&{oDx;6Mxi@$6yc0WFs)AwcXi4piHiymS(7r>VI5;?XJcT)-f@DjeNpg7Qtj$jXO4u-8jTkD7J2sVK12i5IgCL<#Q)W`JJM$fM7Q9R(4Q?Mri;ktvg zxB{d}u1gsxml@yN@OT%1S@;U}Iyg8uz=njOVkbdpO^(+vrz|{^4mW_aW!pO*OVjQl zGn}IZdBoHRI5%8V^QQv1k#hkbZ>+|?6a5ah5=e~ATj2>sx!r{t}0 zqTXXVdbJtTWNT9yYW&dUKTU3zyS0FzsX^&6_3e(15%StT~PV>({+xkc6o;;=v*N2i;YHS+0SBN6dL%0`aL=ZxE9*^&N zLX=FDwFl9qe2yxg%R0@1T`YnGz_iCrDnWBOUUQjjdhgHL+M*D~l?a+ExXAczwm{Z- z@aZ{t-ZsISnApU`g$i^M03I9E>;yhAc!Y_&D1YK>pl<=^1b5)6TR&I8v%3TY1V3PI zPqeC(adTMPo)82BP)|X{d-_1%b2ULNM-wSB*<^~QYUz@Dw_wW*f&zxOzd{JdWtrExJd9Z zilDLvj@+s5=xFrqsjQGy7sh3v)B#Baj_5!e46GoOc4GzXnOH_PuOIi@d|f`Q<5of%1Jpgl(6LHm(XKTS!yhHo@6a*k{8T&QYvc^{)k{ zDt9Uaexx@x7huU?Co`m?u*JFNeCTqel&IG990VI%GsziuaAR z@sbTfV?A0e;}j9;1-7N8Ik)u`@Y%trnw^ugX#Ub0O+7(2w#WQ6Ken9Ug+c;`CMn(2 z4whuBBLg`&c9LmO0s?Rhsv^YMM;G>59)SI6fRVFe_J{Kym5Bo)Rh<=+}dO&bNxQ$I<$4*K{X5i#RoOTld5{LxXu^@s+bQ(by2_3KA z+35)kL0C+a4N36e^#Nm=O+cU%8HORlpTiNe@Jq0=bp{r*lixB|PB0fUn`0@_u2@pic1LHo8tEVln zGIXBhCqtu|seg7~m!eTs5A{|#pP<*xVEf0>E>(T4{MUML5=fWZ8)5SugI{e8=)pKSk|WiNDjT zuKqkD3^G4?-AcU{AHz|=_QQk%$8O9pm_zOyDOKNA*BsTB$KG$8dzI2RcJ)J+btu=L zedNnVd+{eO0(*{cvEVNm!Qvl-&o8^!|JzU;c-({Ic}!B$%b#uwE+#qfcxU@0s9OrN zA2hh8$p1pvwg(8Wmlo?DbmCSaR;s%Ovhm#JKY5$s{3&H zd3pU61EFODDyh2n@t7Bc9ji(HyPqx|cq9RJ@}n#YYP*&#!4DrkkWf>@jUG-W8ZQNh zj<2xA7AA&809^;R7@WkE)O&$u9yojo^f#Bn$pDFRaCTOrzljjjz?{*q1RKgy;C5fT zG?L|S~#5o5kZ631cS7kZeFsFY!OQ?z@(nR&#w%+Hk%# z;hmC?ywRPuP=?vT2ENpY%ra{QNd=Z@L_4g_GK?{|uy_SH32Y?D{_ z30_?ndbfBn)m!C;p<{4vTCTon=xOK(YvSYQG$|+=^wwf?_xBYVny%)SOUyqks){CC) zNcgz&hg`&WH2LIA6V`ju!1N&0YjD7>sQg&7ck@kB8g~3mRiSLw+3*&fpPiJ%?+%w$ z9#XUMkLumeXA8C2j%4_vBetJE+T!};bMm
4(BxcgY$H&xOdc79*r$F3XV^!O-? z=Ra)SX&$Y6zQ6k0WvNn_OnQJ?@c~sBt4Q$Q5dZF9h`+|Prd9`BIJb|4QccH^yIHn6 z(Xf{Up~pRVdn7sjFb$M4sZ~|+fBu+m9tc8~ety4jp55Ke4VGr>)CkG3M9;yP1C^43 z-DVq;mYC=&!|Wkz3plAA$d9Sa|2t7 zrFvZyN?E8*3<|zys$?PFA6tUpK?~yoc!TikM=hdY1_q5FRPD$J$b?H0*0Fn9NHPGF z3E?{xBoh#a;GLRUS*4eiMblhdI`S30L(!HY_l3zjCv>M$;_fxrLm&rum8Ux#_Pk)I z9T8G7mG|+6Z|_wPFDhw{FSFWD$fQWmX>MirY<^1;`O}8~#&yE5G*Y1+(y$d<ptpWyb=^d6kUR}e_ecJ{M|h}Duv&KKsv(% zMo6ch?F*TL%t|@{M!-T+HMrD5)eRz)=Uik)up$MSESlul>f9bLT^?MMk&%Jg2w6T2 zykS}RHPu@^u<;CdI^x2~Xh=6HaJ7I$jJRpo!Mtq7l?oB9ApA6G7#{w`7TaO`+XU$P zlKJIX|WM4{?$M@g=eG~G^rIY*8(5?7FI#;n<+v@9|`|t3jf7$4= zHQjRyz2Kv98hUaZ)z>ri<@=rwd+RqQK5>vll}*@P&QM;8=#@bN>g9hBAh8Bjhg(t` z`1RJ5Naiqi6f};vSZb8!?lg+HvPl%H4)Pux=jF@8 zs#z+MY1cu6uRwJ}FZe(g6!q~#QCGjA_YeNor`J!h^# zeBeRVyY>6eAALxgQjBxvIZkkmAgBs%G~bxFwHuQu`AcJ@{w9YA~+BsdZX|0Sv4UGj2D3 z6-TRSF4$`bF2NS#r6CsFL1nz{ZcAp&t?7CR>I=&gy^BOP!{OAkN;vkfX|eb}7}-xUEPKw4N+bCTb2(xP$-QU}5PUp~;je2JJf z7C9n?jS~<&vEYHZ!V4TJGA5E_K;}h=;un^FKcg?^vQaZc z$bN`U4WLk_&P=uH;dgGmTO&ZSLHOZtLFv=>hstV^s#{L@;QpXlWE+)xaNS{6U8bD2 za+V5WppQruAsa%Y$XLHPK~I!h$|wsiWYa< z<5f7195(WYxFkN;&!2H0x<>bfhVZX!wW|h-i+Z&Fo=ee-5)|&w_E4EYcyfptjiJVM z2IR7#!aWLMPI=Xj$tqs)s7y15MZ=}UX?lZ+%UzJzTVdBT8A$p?kPMp`*KU{fY6!}< z*~&|9{FGwdC<76hpQq_dilJc~@9Di|5%{UZzZt7O2kpAkj+J&ZcX`u?`WS1xG@2=) z%7y81&0XP(I2PmSz$u5-nz%%Q_0VX_ARVUAwz=BXfp_bggYK&vphgjnP~5MTyLt|q z%dHxWClt5Ky<#PrP*xwt;fS34k*fghRkU`WJh}C%wpm-2P&6z#LgeP^Q7Y8Evz~JE zkFsSR!_E6FO-tlX{Q_ak<$Wa2{p!U zHqL}mswD~$~E<6yjzh%uqc2FzQ+T<2`T&T(>VVBnTeDl_R=49%B1ev_! zj!8?`Du>7ExwCF2b03X-{T$O)(X~1rthz?fsw%hy?my4(e)k;Qvzjuwy%V zYbROGSmk8Xrkq%Nc&v#jS5tR_#n?6f<+!n}a1j5E5af6ypTf)j*65q7+isjIG=2UteL|%CG zP)2qjw1~GWPw1>ucYMw@$J`Laz=)*UujDc~2W)gGNwP!ER#O|+*Z0H;XU@dGJol}Q zO(9zaU)Xw=^J?>cnBF^EMhTsPM;{vaBWeB%^;+p~Xw{Q%d7;l>a##tg&uV4<#TBAtY}mjK`F$jWnwpyntPO)LNpmcKwk<$i zeQ`euZ;M@;Y#>1A6_o<*FnP{#?dVhLf_qlc^2ECjZw}zzj}$W*9d^SdQMMH}$ezWy z=lJu+g+vOf?@%(dz+CWqb20P@wjaLJWg~yygjyY_6kwXEyM?_H%Uc&odq;Mcm#%X4 z6P2~=a#A>@9CNXnWFI7Y;I#ttHSb_A0Ngnq!k0(vnE?2bvLbr8^%cj0+$SsKwXo6d z&(;p+UV@uTw+NOAJ@-=|8QA;ubw3bqvfcZp`@(GW{RhQBSbq&Q-T>e4ub5P96E_FH+N`ly?CE^r>m z-I6d)DgS9QTl89F=2oq2bV(RW?sT6nGq~>6sMd{^oy^EAl`VGnP3oWui!*38Y{7OD zBBIm6^x7hA@K$u!rG#LDWVgY9In~=vN0X08( zcgSB{9p-7-pq+LTN+pktAYJ5KX38xNlt$OX2k8-RVsjZEpAzR!%$-(!pr@z?U+<35 zdR?%UD(mucQj4K-w5{&jc2B~U;Rklr)hu0Sij&0|ky_gc-}ojDy~j(tA4F@5g4cy9 zUn$Z`s?rAdAV=i;Y^F&Q+qxi8+RZ->aqucOTX|~Xgep#}Rtq!bMdbNz0RG~!Ta>&2 zJ%jU!S@4)=$;;hMVQ{%BvIaZ=1{sH#`AgXDjvEnS4m`OiJUvE)k`d^6~ONXSZ z`4YDoC^NG$^7>PjrO8oA2V~vYI+MS7Q_iA&HEhZCgF`H*hBn5$8;~`rO8L4~pG^A};X}H6SwdIj zbI&HGrevL+_x|^ULc92PY2isVFZa)y{ei9qjt2;*{}xn;w;Jq_Yjo5B`SzaYyI+x7 z^0EnhL3DcWXw>aW#K21>p2vC-=|_-G3)bMON0rRh!f$&?8KH=HFC6cApYhaUlpg5u zoPX^Ysp_~HIUDG^beI)PyL%zcZCke)eW8KGyo}w3_)1}QZ&%2 z0jLIN>li40rR;)&T`MaVo&|l8ySLHlnns@VH}8Ta%H(7>1Opeez;ru|c>w5>YCLEW zT3)b!4xe5px9-%ZU!VkwsYezQuzw` z0&zoR@7~ng<5w?+V=%@*&~U#k7yAH=Dr()^0-1K^WtcNTzacW@7?i# z?Qerra2HK~s}QX_e4Nop%sK;y`EC_89TnX&3FJr{hrZvLO-T0)>o{f_ovE2``{0iv zGZ}NaHWTF(;dsc(cT2STbUwUdRQxj{MycT zi9YsIVc5q^6;Y}ONyAiUq|!EOYz+-hSFO#szcriUFQbZ^>dqS~6P45h(4r0LLmTL@ zC=Uzx^r95;@bM>7AH78@wo8Xojx`-mMaOvBvR2^U<0|G(^)#tkk$F!RM_d}c{_LXd zXR{d(=Jz@0_d0!CH^vmI-r+>;ChH!%buL5wicSaT%}|IdLs`p2vo_9bV#$Ghd9!qs zj&1Cw3i_&=c}^b~r-{V*zI0ai{?<$VRL|c~%8Q*Zfj-#NO90eu(KdR5y5Wn8uiSyT z+<|=F$uv`DrnR~G9GGUZF*Bp`sB4jU7AoE7W-Gff$tY_TdOYHl?kw0ouxrc^ET`1Y zzrXOttn@MO$<2aL7P8qF1f9Y%w|y?%d1)P`_JZ}widv<&tINa4A$0A+latL$2xNqg z0%-?x*+ipZn2OeM78((|55eTQBij7-hjl= zLx)Irw{&-Rs|?*;3ew%(-5{g1q;xk32uMpeND0Vy&-1?Le9u{nS&Khd!0g%g-q-c3 zi^=Q${aR&C%bJa)#6WEV&ay9J2R{B%dBuC$O!Hi{Q#2j~R92}#EzwVfp!0sMwxTUOnWSZ!JY+`us&5 zbvF#|?&s{Sbjh?EuyosV=ly+)dt{_4u-Z}ktLD*_DO5o6(s%pXwruf90q-@-D*YKO zH^8$UxQOmj#P9LGU8a30Y$})Po(e|AHTY@ck)p+LOK@+{_4LW+M$?S968MBh0;ApQ z>`XhArpu^hxZq@Q5<=Q~o!)FPi zfMFlzSvsZrq%Cz6AI?WLy^P1Pvw2k*0{1nQhNmOs!a88&XHbPpo*=HhgVxJz z_>e-h`FrNp7lykGRs!e4Uu>5>#ENuYjHa$#OGR$eNd6+xc2sHeTA-u$Xch9Ep%a@vfKMjBUY^x9O0npakRbq*rSrQgu=3FOiNW7H_ZzrZFMk;6+>K%5g4{LnJ7$uN43{&b0vRTEM|TG33hS=d$_Qv zDNX#LLEPNSD;3l?`;G!hX5O>rxKg%q5#kKDPmIda z2$d%EAED#9z;EEV1}l|DHhOgKTCe@{u0z2?<*81Iqi9PVUPG%LeEMCgSfYda}N9|r2-#pih_!7NEYb) zNmc4q)#rV`zknf?0O^>e?ze?!?b9z6sn0TXMNCe<3ow6MFdq^Ck!i_tyd?mp*uelO zn1~goLxHKFd>&TT)d2I)68W+%9i&sBvr(>L`r9B>Z)8%HM^tR|@fTwF%S5%WxawsW zR@R(S{7E{8JBQfNi%$efJSpR+AL1|M{Z+ZziD;7g>@IuIKqlBY z$f{6Rac+i#t$y^Yklcj{a?_~eIv>%e+6`jJPabLmmH}Wp0M9Lezr5}|P<x>9x<`lVDW?HBXCa?o;+}Vq*chxk zp_fVmgw1{x3bxGh8$SI;s^gixN{0BCzF9B*vkjE7M^1Yho{nMX5Ul8;BSg6YxSgMX zR|a5;aS`F!v#m!ib13CmsQ&20@)OVpMFBoWbD4}KC_4T{!XE)D{8uvjdN@L$xzE&% z)nHXt6*!sHps?zQBX)SYlav8VwRV*)7Y%*llHN*oo&;Zmxm;%WXE4S^=%h=&(zIM? zCHJ%hYJu$uXX)7Sv|u@5Q%6u(^J^GL4GY`?hFa5+#^n!M8-iRvyO2dZoOKm+0g9T9 zx*_tu+l0UEs*w#)16DU6!W5XO)(g0%9itmFTU7|Cv8G#|eFMBj~HV zhUWPva;Jp|x8U#vc&*jFB%8B7wNg|BRZFMv`=Y#G4Bi`im&EB(viRh(yYl%A_$Rar zvvD|RC8@5>1zi7G*8WctP`XK=j^@ai_bOQ>!FJ8%D z>7Lm0V!=uoKgLR-2~*;fp^Q;`?KY}a#I05qskzrJx{C995VLJ89KsY;t58^yh7Cfn7MxnD z$E~c#8#mFo7khY0{ALD(Hs^V0_aQl1KD+STDEYK5<u;vR5=mP8IjIxKc^jC#m&mKb>cJr*&<39|Gat;<3nq%9t#wWenCyP-`m?tykiiUV zt5eh}EaNz+-VRw=Ti*k{T@MfxKr7iPuxA5p1xho3DBK2eoYB%forYHTZuSQZi<;ir zcyIfrq8nN<3=%JW%>kyMbH6TtSJA3Mo{fv^Pj>CSU|e>q()pyLBx|xrm9H>2{k{LU zay#*dLqoZO_gKzC%F1nF3P1We{ixYAJ%(jb0_|~BZ>C*0jcryQ<$4dSQZL*nWQ7Tb z;u&gLU%tpV{=Mzf!#j%n)yTqXN^Ow5tw6z@Xfs?c)%H74bDFpktSa(k>s?2H0XVOv~leWot}w*UIiW-yQ94~guM*6E@Q-pz9DQ(s z8LDB|#K#8596;G5_PYqX4p3acJj4E%DFtMUQZcJCK3`{g;9O&Q?q2ojA&2zaYEyYp zSo`J!6z;d1rY{#TwGBYY$h@gD_ysfV@3`GNV9Q3Pls8!c8cY~CZ34K1_kRCj`DX<_ zCiFg%nfLkr=sbE4a8^udCb%Pn+1aFueDsn1)S2mFT4>N7-d^Ck4`L2JD{PdmN~Gc; zqM85Me~3O+u^~*>i22=wyxKC=p8a?FBHCO%sLV*Q5hw}DHFr0iSC%QVM|ruVaZ*VJ zO7jftDc)A8xH_d9tb9N#qaKgPh0;gyH=4@g;(q^c#gwk01c*Rdj_b!@X_S2g`X)Uv z+0Tz3KQwRAA>aXl63LGfzyaOhQ1>GZFv-Kr@vul~U=wkwUS&Q2SA+Oz+Yvhu%l5H3 zf~ud%oh$;DxeSEIT;_iMoKgFhENubZl2j6`F*?aD$lX8vR}=&Lgn_4EfKwV!piKYB zq|c8u4adM3gKKg@t#mZ%$BQFQpEw>TzHddy&*|f}u9d=(ngL-#p%}RV@acQnA6zL; z_d#ulL3=OIEE!c+x;gQeZ;1#SW!Xl4*hAk3+Yxjf;yD?p(ymE2mc3v(#Ia{jad429 z|CFkPclVcU1DB_btB-4X7VDoz6KD(Tmv2J=sS=Fvb(!E>JO_lWdp`r7pYYMb2p)v6 zHMdanAWiYOeIhjLT)f%2H!U2QR)99e^%&?pU>FokTf-JSbz2x zeZbi=0XBh;k3sK;i{*y943CXg;DP6!OTjn`2-WJj^VV?PVWE=cPIf`vlI3tz3YE1IV5o*fT5+@J9E*CZ7OAjKjyr ztlyq5r9Q*E$a5-vLUV`O(f1xe%@&PP`nCZbU-Q91A7O^B5+I5LluA1Qg~I{UrUHe7 zRwiwzLDIGWj2g4{C6>zNzq+~tBq$MDRWhuE!Yh4(Ou*woa6nmT#10I}gqV3`e&jec z^Rb9b-o}ZeKRC3b&vT;0MK?D>CZ&k$UCge^GJN~tfKF-?kxkXHP&%|1r+7x7NFjRM z54ED&^^-2zJ?o}TtVdhe?q?@CqgyWLU_&paSF9-xaS{TQ(@43qoC8%vb!Ljxm{7*K zP|EHvLOSS3(JAJ?3B9^0$rcg_M#e{RzTt|)k*|1b&Eg?H92-Dw_t^Cyx3xNx_d+HvKj+>$18*0uM zk8UJT)@ig?K80_l;gt@;s&QXb<1<+?)R|*u77>RNBuC@@x8mU{(_#|4sY|#3)E5~* zkCuo+?i2X#=};e*f&%C$MA!rHj?FWrI1A0q^3Ooa`*kHO#*b4?C!pvPj_hpFy zFl|fF%MRJEZedAQY0+l+-2|Ot*^oC|nm|YUNaB@b?OO2&WCDv_Wlf#KtOS4`;GUf( zRDi09C0Ok{P}UCtRs*rEi#uELBrpd{ni8y;6y1C>Ssd_O<>4&W4-dUIL;Yex%_BDY z{Ty7Tm8HNc$(>c+S{CObB3G8(cUz4ZM4vL@=3<7hf@Qt}3GSxEk4|=SC~h#uLDc1L zRTNnqsP8K!C5@6d&kT=}D`}E@fRERv$`}Jj(b+iKSA22CoZFtGRmmAW7AW7r(WkE- zsK6cH(s9ci6vME@6JR$Q0Ld>F#-fEu#k;YG+&vPg1r1vs(=2*&FfLw{YV{7p-*i09oEZh-}1#g8y z8#Qh&egIS93!aXxVVu+i4epj@Lqh`t!2*h;iyB8ZE2PsW>+L?xJEjZ?$+lKhVNyE6 z1Uyx_^Trr$<`PkgIW+T3{_uLmejvArE0!LJz*eFqrR%l^WDIYFy|mcxc}tBAc!;UY zhPe8W(I|$P5KObEJS3B{3d+h_8_3 zHB$W%#U9zD9_!!`~ZRedDEAVae&ZV=|MFPN-P1M->Qj zbWmcmc*Hh?il>SV*x(*orJ&p2`z`!p8(JBf2xl!IKYXY!4&o? zF4@MJ=3tkx6^rr35S#Xhk0~Pp1%{;=v#hyLm}Pe8F=vtjVjrSqU=f1fVwnjm-W_4w zfu7#&@99)EbK-0>uD-jT7sqQ))SvXOXWH8$bd-{&)QUo=oh*^fvLAc6NJ+CJ2Xjy# z1qM1BD(k4dN_v&#L7tzBAsbpX9z+Bjg_$`ehb=zjHrS(KxaDtpIcb0Zd}Mrj^d@G~ z)S!ip_vG_#=~6e8UiDEf#i(;aqA?Pv|2fUxiUU$SK(YgyxBwd>ljHm?3#fh&;4pt( z3~$%H%kV)9spYT5dV^9k<6~2esDo-ywblfM#;Jci)b=|zr!WW1>!DIwHn6c09q9@N z&qBo^f!()oVce>zS`oUY2AiOfazd>E!JqfG)nbeU^h?uHRjEkp1E!l=$%(Iuxf~JD z`Zy)nes{{-<40SFjQr_olG#=yowa3E=He2ZJSFn33$Ov8&eC?4Xlj{OgN+RU+GQAG zRGYvZ)7f{lDH0M6VNd5wQ6%G#+cZUWU!YkdW3Xa~gxX4xXjc0Z4l!*$h>^a4Vj?UK zF%i~E#0x+S{!o!Lc&{dk+p&_l z3COWN9|1*y#=dkwOWO|ayi2|YV=#eQAoo$gce^rdN9&CT(xEDiQ5A4JpP3O3hOkb6 z(|?{P@RkhV4hGmQSX~4w8(@GG3{1opf8@+kDPPm}e*f-G8DVr0P*wl~Ltry;;0o^g z833K9n6fo&GH0ZIbm;XLSM->cHlH++`_>map9pFc&{C;!m5VUkZHb}yMGCPV$_$^6 zz~d@~x`AgIk%Lq)W?&h0X2XxsJ>@jKGKT1W7z36_yl-*Z;D#{RMcSzEb1$vYP zdU{sL*Do<}8Jk5<9ku2tSyd#d)_4g`rYo+@pOxn|etj&Eg5=w=Dov9}uke$sR|xPS z_-+wjfV|Af8j&&!5mJjJUfz9EF3TK3lUEEiW9*Y-(Lmhq?zydI#1AJya2PFPO**Fa zqE#EVlVPg*3=@?BZz@-$3?E1j#`fEI(E+5H(4>si0vdBz*fWsxo27z03f3Wwew8 zgQNSoPQarkzx6cGgmD3@jrRE7FwvFDD-nq{DBeoE1_-0^hKtR;s3caaQo7R;qfCOt zpuBfRchoY%g*B9f8`Y!xFn`|U!%~@ro1s_d-OJ<)kTwcK6(LKFojt>=IB<*Dd@E~v zzJIVzt4z({euBqau3BqXC-<7uuuR|4)N<39LfYG9p@saSzEHJeV7ecYZvYCVb4mEm|dC1IQC4J7r((4dkaRj-hc9+elq z+!hCIppJ$qmG1@my{Ny2EDHRDDi?c;DNUJ4kR7|ci6k|N^n3Ew`}e6|E~1g-uw!S4 zVx+WFeWWwPx(J9%$FsgoT-oS$3G93TIK)(zFD%*Y?&FO)pD5kbl-LPcD$R z#a?IGOtYFP!w5fv$Y}2?pcRWr7FG%&jkenM*73?Q%RqMkefd9|=07_JXdDW*?a3iItzZ85i3_y zfH;k?zjUifv8(RusvE0bA(bXADcb^tVajt}qX$NbZEXOt-f=h33)P{HgM`;Qt;wRy~5V(PuuoE>ltq#JwH<5Q`i zMnx|Dfsr;1t|~%i{PJB?V+d{$NRKfZ%ft`ichQ0f>2#2MlR&~}D-g3`qj4`{jRrnY zMUkR4Ml2BKA8D|U<4jJNhT$1(GMWY=-u&zB!}KA4+%o~X7j7N8fxlOUPhY9$#%O7} zq)Eo0T*jTCon2wXyp{2$Lx~Vd9SYaie7=hN?QEN+wl@yLd41%@_Y88zGnKf1Y_YAY zkLwhPt1NRNLL?0z@wbBOyh*+&)6&NyG>_xBNN{!XK8L-qT{!kgxFuh@EEix|qU-8# zEp~UAeklb?{-}*=g;&j2XP$19r4GeJ`m7Eq@BRCR-AW1~Xln7o zY$vc-T)l1|_X^?IBH2fo#*21DDlXuC5lteJoW_8+8)6u>4*^D5Ee&do3oZ}7Gzl6( z3nC*zp%Ihjs2XlOpQ!;A#+XDg?4J0awdl{HhCB(fy1c3$z}V^KE&GW$KT0OK0Wrj( zzOdp{@ql|fFR3ru@m$a;jD7RSy6^YwpMUmuWzzqHYDEh8Mm7^2k5Z_I1iiGwDE(IL zy)%J6%Cn0^Ck;rS5VIdWy-$aWFoaKX#H4A|IK)R+qBsy_L)$}}QcFvlSDJDnml>gQLU!Cc=njS_uKhdWa{?HCdQq>s||&l`tWyco9tHtN1h;; zs0cOx5Z}{#Qv2IgK+x0R^BdH;gQQpA*RL7Mhh_gtD|jaQB=60)iwWPm!8Z&o&q3N` zf-aFja?a=_b(|CNsiW)ZPtpo2!;1O9ihtCm^})^ABJ1VkYQwoShPe#KRu-KYxw0g2d}t0Kx=6(n zMNk(jy?Jx<2t0Vgs0KpF{NM0;Typ|lL0S@L+;Y(^Q#k6DAKtBd@ALon>lVLGyZL9G z*ygXdicq#stC<-TS=)xnt1+UyXNsc{*Xmr8M!A}mLKWGQQh%y{%IccOR^h0bnumaR zdIhAzQ5Otqnhd%PVye(&1bR>-T>12fWHgnU;WQbjg&S4s`3v*amOh;0ccxhuJ4L8{ zkq09ZZ%ZiUx+p9a&58CGg#?di@Q|nrx~@NsbNuEkw>bGOoh#&-&120^e5z)1=;igE zR_>(^G!a1JrP7Iz$==_Tk%@i4c%8-F<``31XMh=(779_qA4GIiUeRH6tgPt;RaVfg zSo25ydDFX3DTyEG@`Hb9-rOW-dzrL?m(m4?aTS~uK5a$(k_IY^Ot?q3V3=CXR3Y4- z_r8}=dhlEO+Lg%E|9(A88g1X@XtzIpU72!Ocakh)8x-1-s7)MrJa5pyyX6ocq`a7^ zxy8Ph@7E4>$Fjz6W3v5(vttqBRxkSoQ`0fXmPJK-qmgEWP_lHGk}8th;^#nZg!BfP zO<7T9v1bTB(&rJyHgu0Y)|fG6vd&Ai(Y#mT3{$Q*-ueu#$(?IPGiODRWTYcj=3?8o zW@16nGcY*TjtY-EAgr&ftf6nF45dB9+J}-;pIWq-DSdm7RYq?>7Uc4y&8nqInRh?g z1Mklj(jqGGOuZx-)w5+N^XYSS3X&|rB z<)pA#|~lO2L#?r`?k2`B!AYtg-~!Ub+*N#5l@{s&Sdf zw1x?tolJSFT*2uwLM~L*^_BIKAjwqPNX~G|Zo!Bdwm}=0y<0d=1=~6SGAyWZwONJ_ zH>DcNum)vmM@s_wzm`(uOmRqXh|OMl?eCH=@#3GA{4YA;;^K92aQ-JK1rufrAGVP1 zX?JqX9UbF<=+iV<>Jt$3gWi@8WXzreb4m+#c6Nq*LK9d)2=%N$UQODb*llYEkhc0a z-)RMSz|DY!d*nAnI@_Mn7o@s%(x1?3>}FJDwc~BerL$);tt{&70u2;hP^fk0z}6&7 z8gY33?$zX1hC-0tJ=SrYXrQtXAST-%V9&}m669B9SSbZ>^jp(21KWfHGZ8`udYjR_Q3QLxxue_bjQpT#mR$`8+^ zZoXhx`gY9S_C$`vcKZ|XQiz^|bBt-Sjb`GsvkwTd9nWh0Z!iWLk#P!DWBPHBs363U zz}l3057RIUZg_LBqcqVz1Je~mCbEwyEU`f-`(lBfTTx+`sIoelb3%bAgNcDgFM)h( z_$ohS|MvanP`g)?kltDqeOOS;Pf>9Fr^GKE(zi=CvBvbMP^W}i&St*pfo6= zAHro&VpGjEu#W**riv97tGWHxse1)y)3~FIeR8qTbw^*K^zk->CtbYNH$(w#?RT`Y zpisu8iefJR>({`<9I?LZ#dlNs-!2JinuvTA5>TOh|1@gremwuoSDbqKId$=8u`3@) zayUD@gsr@fK zTWMbFHJ_|z;5?!no{=&&B49(tq{WRa23xXW)h=%t#nlorNR)FOY>B+j!@I^!mh5Gu zXz;(J(qOCOAIJVsx`eA3Kps{0%86bvu+Y8i!i~6a|K#4DyJVKmfTAuBPjx zV9u^l_xzO1Rq!)C``4bo#n89yvp!qjY~%QOTN(W4%Fglr?#)XOy!eCotL^00W81FY zzx`2oe*4lCTYyw`|F$Ff@5m@|A53q<@ifZ;Gtpi)08$>9rVg>kdkuRo;+iNWM|XAn zuOpXg9P^;goa3lp%HiW~U9}{ixz4wcD&^u9b)kS*0psGXdWq!US;8$U)2;@u%RYzi zyD8up`LO^`3NFiZFvFy3MSmJ;aHx2qUtT79MvmvWymkX7`V1vVTJ1_>89_ zUskdLD3=DQjk^#pG!#_B*TN|Q#~r!P_JvcxFA_PZfC^$4jfSevdB>-xmq3PO>coU9jQG9?ChFJ_W{10hJPquU$u;fUDT%I@ zWjkpS81qixLrEK%HFqMt+JZ=(L+t97$iO&W*wdmNG7GBU&B*5b*;JZkvry)WM$Z^q z_#~>3_h8%_WSnF#!hJUK!mdW8+%lbkOz!of(V?0G;Sf8rEB6S)H=_Lqe*>2nJoNN` zWX0P~Ie~{0%NmCotGRS#9eFL+0-F$vXb9tZqa%Y&o2wj%sp~4+LYs^5kV6-6sfR5j z)Ima0$skEM8#1UKEjMMfbgz?2iUGfOGqK}|DNC3W0RnK0Ev+omfuwgoyhxTTu<(z! zT?NV=lHVxfUp`NtOf*1^HOwt2QMY3`)si5QiDq3y3V|3@3Sh}#Pt!a(gAiNHd7He( zuPR_qP|Bq2$9_Sh^Cu4LvWL~% zTyb5Pzpdl8^K1tYuzcsCt`z5(atB7%s864G!R7SBdLCq z7hEc4_qIJkRZ6qbok=(U?hyf?knG{pq@@^|pXC}POWC9t5pf1FW;`X02^&45oL0?f@Oab>F@t;HxMl)UNqSLvEq|>-J~tz;TG2cHn|tcG|o1^NY*{g z5|OYpYCc3W8c?bja%1SxBXFDt%TZ-v^w?>kxPrm5@Z2EEL;)%d)i6gg2w-w$!j1XN z%aj}sipoQ>uhXIoMcj)F>o$}YTQkoVysS3m&7-zgetiPAMg<1nr3<<;Y)2D`VK1H3 z3X{71`EKi=J3S@@6ir+PCS`01+Q(v%GB|@IlBtxzaHWBinVvu7_d-5I%mLn8TGZd~s)aT{y>#nS~Uv4A!t{_i%t{d2ZK^EO;NWnSR@r9_yy-S`3LUEJjDiELL00X1iigt@}Q`)kf>rjlMj!e zr?S{to#R}wxLB=O%EB7v;&M8EVDo|}>H62BKtzzH=t^-)oChFlM5bKXKhgxRm5=8sT z!zR|MrFCR&N!8+Q9q((?`)+P`^sDhNyrZrahl zb($d^dw%*-FmX9&5%y#)c10ovSogGb=XtnmP>AE?Oah*+AJ4I$IXOPe#E@Tz0Jmtc zz@E#(CAysSgKGyP0aqdA#fqq4_mK2hAYlU}Bsy1Cq^BL@FFL>Y8rS zD1MyYu*z~-J_5Orxu-$={SFHfWkpJ^v)sz{n2idA75gwna{aATf*TQY)@1OK{7IG+(@5uWyJd$$x-5ZMHSY*dr z-^1&_gIy1jotXs7pUO+gopG(*5fxFW5Z=A}KX)tdBI($>yq`Pbs~*WbDcM6T?oM$# z4Yy|-fw#{&dm=mfKY)zdD}ag41qSk1J7@%~RcTkW0M_oiZWJ*Ivgf%dVu}TE$=s&K z`&7GIvioyhU4VwC8?>p>+qY5@T`F7?jUhifiTF(-!$ckFDhcBLfqfLjNi|6r*{&RF zNMuiYvQK7YTT{0om5c5|m^;sVA6i=BGCPwl*#5GD#MxO(RVf?!a8QG(77>wKLMFak z(;@%mrp0jK>nTdz?{lb*1h|Is>177iiZoFvX8dAg>4wkk?pS+dlHe_bp2tyYLwZS} z=xVv8XeaL^N&^X5&VUV0ba(X3&Nt<^>v5SFRk@{nq?T-YjCO3482jV5bqIsP?J|mk zJv2ka*z&oeuE6=2Olx_6PRB|v8hU*FV|k^_S8sNt?f0%8s1G!!V)b%@oDBcYde-yFFDIu~`<$xC zZ&&PNfwgz0LFzbL7l{}+u6p?chi%ba ze}+cx36>^FbqqBUni&UQrta{o3dI-=#v@8O!f3AMjUV7Q`5qHzx*!4I1@ zOV*@Da#D})qWYpo()J+1OWlAkMCc1l(~!wRQ6b*&O9y62sq>Nb<4db1=8dhYS&QHK zc%dblreQKHA>4!|ujHhSnX~JA3>6)abeE==aariNF~B_z(t3M8|0?})X5+%Pkicc= zUyZF<&-0wAz|pq6KlgBTUs=H1n2i@!g(CLJ7Hre2?w1qe~Qa#%nhQEAfh z3J=Per7@`pRCKDMWx2@?=e+(h5-?!0@xoQ*hkmjImgJz=V|8^`0h`B#w*%F@ze0(M#+m};seHeb!@&t$$6R*>rl=BNzp=kg*q-sG z*YD4;>t`^+y+U1T2q(A{B0)MTFCKU{GdPIMpq^jqxWe$*Tre*7d_VP2`!{MMR`xZ) zwS@vu^^AYDsTNJmF7}Mm#BBRKy+f>P(`%FO;FQm4ELSS{+0mNiFa#gR3eh!#@_;%R ze1stdD(0nG#y*^i*rALPR;ImTV<*O;d$HAnASW<-!QXen6Wi>~NROmjRz)fgrM2A7 z)Qg9_O(~~@7CGWu&d=(gk*YGk_@j)T=_YiPN)!xN`@r{lL2xpoIYLo}Y@pv(u3}Ld zRXULl92TmnV$W*{otBJXRAii6TDJ-f-QG6s&DZ>cxSVX=(O|S9K!L*iUQYgKvKvzT> zub|49^!Awv64Ph(BBoV0q3!7GoB$&0@VtE0|Ct<3e&GS!8iO9%JgWjj7JHJ_ABZg7 zY8*MM<-QWMWzVWHeD@VB2Pu9a(L4l?kkx+;W*elWvG~cLf-GYj&>Uq8Hib&UNfJ{^ z2_9)!cfBMBZLxRmY|E^Ynd9s7K)8RJc63f!I43YWS26dM^6D^4yj1*zIEohCR;Ghh z!CUQQdq^lF@mdx51FL;wDqk_ZO6#D=tXji{vaw(Ts>u3S+8Cg2kEM2Cln6zH1QP@o zJC2NncQ{BW1P{+r8Wq9hOr)(pj~ZTC;#?cr<7!}^4R4W77mHSFCzP5ismfLK&IcV_OXs-00;K4=ip zWC|e1<)Mn<7-peA#T_I-tXS4R9k$n+sVPn%o)Qc1=+t~8H=+uPe*f!px*|7@tNZC= z7K8oM<1$$I@CB96K@q(3$9YSW=IPD8uOj^v{^l<%PfEUhHZpb+mhz`Sg zz6p!Co7sc9wG_NP_Y@@s>e>U3Kb0H|p+5bX1_che?l#c6giA3|_uX-t{8QkrN#qG{ z&P_baEhqj`Wa~;?5e_CR;YV@8Pe(!MU!u<)35yR#v-c`EVjMC%uls$(T7Fplm-Q+j4R*u$Ll z{X8essI3!A&w#nC>L|Un73srR4CCVY#-Px>kCG_{7iAD*B8WtS(N$7n_H2t5#Duy9 z3ZXms&G=FliV^49xNHhGWh>XT;mcALVEs~<_$!6Ul{nerW2`3Fz=Y7egm{%v3SP}P zI*-bDMH(?!2W{L#2`5x01RkWAdt+0begEQ<$>mRLNmBPezim&u_WVPuqrx_(>y$yk zhR+@Rq!Ha{Q4Pq83z25gkwP+x0!N>T8kESO1iD;hx$!nfXy(*}SP2JgWD>}KnRfmS zXy^b<1q{&W`so(ku>B|avoxB|!6y9kX4=qwhWwtQ)Ck9$kAj+%_W@mA@e3k1S<0k)d%qE+M6bomRJJP&ffF9#T zFC)DQUSlX_R4u|RFO3o&85RrTc6E6TUtF`nkpJrpX|z`Hx(&up(H%9Qy+0sp36@?) z(~j5FsbEj;tyc2uNl*!KR5(OkTSnhU0+n-q+#7GP{Mc4%No}r;lro(aP`V>yVP4=)>oo z#yP$n3b<0-?D!%{*(7e}qhnsms+qH$;G0Xg*N&MK` zf|3_l`Vtp3^z%~k!zWRYUFvc<+l`B-H2&|T3pf(XNQud|{ei#Kf0o4Xu_L;%f;^8= zP6Y=nVn%KR%Y}u1ZReJ2F>VjDOfc$yXYP**G%{qiv~85NWmF!pF_~>7wUDV;Dai?! zF^KN4YH3%^-vc>DhEb-&YvSYeQ*p;p#nmq04sdA_a~l|REB4&1xpci9DufOQ#du=b zTdQj@(P|+pFlj1rzPwf zYv3zL7#IM{Hi_Q7&pi|W3k9ma9kubPZ;!;TjCcEv_TT?RVIMCJ@_o%ExvHmeXDv;5 zKKyXjzNbBazELBahO~1^=$K+|qL}tYTm7|7v}3keq-Hp0I%0i{3O4}bl{N&*(DWgj zPtN@EZ5#mW658y5>u41B5+St|lkE{lPKX=*tfd7{f&6?s7Aczx(y{ytjB*6JWj3S{ z+z6JmKnUS$0+ncFoUq1fNGegI-1G@%W{h@CL$2|kd?E-pE7;NeA!M-&LsPZCw>Si@>D2OUuh4=bL>UTLfP=fJ`%pt?hvs_SjX&P>@zMj7HKAxYo}Va0Lh%PcLt83eSS- zJ<&NurjhzsV4RcN@ei)gZHLTnfw*OEVvI+e`TSenlGuL$`~oMTkr%#nM2T}RTq+A( zPWYy_=7$Isdga$v&Luc@*E@eRQUbf6qTsxH4gU7@mx|p<-ya4NiUnZS17};=uy zjD-@uH7om#fnj#Vx@zX>iB_DvLwoud)~!!Z!yg&Qpy=(H+g1=6RQf}VJECi78ZI7k zsqNrnq597e#_VvYrlckxzHSVcRrA4#|Hs%FLMSf;oZR1l$=c{NQ!N{9ST@C5fIAGA zoLQYY&5xvHZ@QpO;HhmvN{u4}QCT?C)Tb+F=2|fIRPJn728`&5GE&ns8YIfjMPm)m z12GEv={_4p5eDrKyxSA-hTuezPs*t`)75f0mzy-CiG=f{)y0(2JjFkzQw2Q*OPQ2Z zbTxL^gsZ95mNe}GnF!Rd#Q3}Rt_R`j>JL71>FA=d zlUMl%pl#OYch?&u3e-g8FJv{(i2^Q&{D7I{FmGw` zXZu(#1N)B}XYYwN{3rwdKJi3T6A}^KM-|+muH7_$t!r!hkR-qVe$Bi`=&qf|-2a;6 zZ2P!zSE|biD>)In^Y4Af<1kr|_#B6OVaEAj#;c;4@b&iXW4yOf+AO|3c(`lZLjav1 z0Vhd@XGPNdqjw)JvX-#Xu5Nh)!$5m3RFHeZMKL-JtHh|S2m9f<(m`?1!D(L0T5ZR57$HBHfz6TqOt;aC(zAI31&^wJuLy z(eE{b=YkuQS;jdiOz$_~drK4akaPP4UAO_d+K%*ch8%(M3P+AFuwS6kc&sIJqm~ZO&cN;#rvD@06~A|2MU1Y7gIcM2mDGYc%+rp6nT80%$&Er*Hy{)hD?eN z#d0+|DjTN5WUv3^zQ#HG(Kx>!Glq>448XqXsGuyvhYbJ(?AEUW?lS`J&-c!|#1(I$ zA2UU!e0e9k0_;RrZlR25{#UO9Qr4eV*LU*H{1}`+%;hK~_Xl{td};ANS^&B0jta&- zGVdDoyResMRxHl!cOQ0>6W5>Lz3uH15V<|KT{gHWr@Jj!rTb!p#eVbtW`?eqk`hGw zX*Kk9*OnIP34q>D&4>gAJ()55X=ZuujDc+!pv7#I_V!N`qL^I}% z_~de(TBt-BNQqImZ0aa6$Gfk0;@uMSG=GJxyO)|G`p1=sD)=ewceb8x>YQk~Z%%CU zB=^tdGG^n$g=xEKxx&U0t@vV3l_SD!eARi*tW;uzU45+SlUq=zxxIOeT}L170wOLJ zxj<;MX;Zlk!7Y@4w$9W*AyRABpMrtzNi9R|OAJU_X`VYDUu6v0yr}s#;m+)R9 zsF$&qigVDkMp7V=+q5h4dGm@;Hhuw9?=`56R#8R!wMw~Q5Qbs{mJtc*fy)Bef~4M- z(@5K1HIgO~fd+As6wp9WOX%}ipM4Ch>{4uRk}rK#9kkhECNO%y!J1h5F}u9nk=esO zQBnasdFb=qBGk!P#~2S89+D~rCnvyMMxu%qE{wPE?E^}uMOJBp!uNxFZ2SCMM!-Lr z9S+zAV@$kPJ%9Q?oWRj4_HJ!a14ElPflFf(@E=(M@&dIA_ayn__v&m5M$yHl_VzI_ zMFLD`4Ukp9<&mXU@wnjpLOd$yDj0HL4yXD)#7X-f!jHw|uc0WG@s zx2yk*2Yh}y+XH;27b#}>xA^9{+X1;b=V#*Aap+h;P7~PygWq{X!L5tNm$;q$IpfE# zT`hUfe+RzQi!zgo2|Y$j$2@MSn@n_d?hdeG3e|X+|LtQ*Ft6EG|JEv5MgD$!W=M+> zi9_s%wb=E{c}iTDJbNlQ)KxASv+@#05+8^D1&F8d6P$~IgR!)j6rZ3ZF<2H=vtGu@ zYr4AM5S_XkHE6)Bsd$p1^a(ks)TX3z3}>#>Q_k3$o+}7NcIveTD zXmL$pQ?ik5bO(I_AtEG}vT)@rFh@Q^`%h9ihnoeM1_;r)3LX@Y3$qfijY=jakr}2f z63*;1?0cN0UN&rw*j_^Z1YP^GAiiFDmZ$}1c0=9R#pIMcX=hPgEyKc>6IvV07!B6i z`pNoBUr95Kz=*GqKwd8$2Q*q=%&L^!N)BP5FHji?RQsy_^JI=$mM5<;Pqw#aj-2Zu z31N{q8cJnlpHMjmx#)%umZTs+bU4E}@ZiBB7ZO-Wef_2CQ#S9>^g$^xbjC4mE}Rl1 zsX&H6^iEye2XqYPLV1@Jz%aL1IhwWSzqeOgL|s29igw?t<17e%^ZPK&v394*&mmA5Va?{% za+7U+!I3ce!ZdcL8PED|{&}y#?_x6Lal1SVW#QImMc(Px&BNs7=jSIr6Mvhe7oC}3 zJN^hP2#UE*?QWC)K!*naAoqDXbPwtRW6`C%@7o9hdm6g3b?vHxYbB0oxJy)OD6~(y z)y(n&A^(r5vy7^$jn+0Q4N7-NY&xVnq&rnaB&55$Te>@>L!=w&4r!3?2I+42p8cM4 z#`yLa{*qYiz1DnY-1EL1-;~T9S2_n!h&v_iG7>{bjx3Rntt$PmQ8$%)mMnjPXe@*ef_SzUpywPG z?CS8fdMv{A=~So>?Rqv1d(rKf?hl{1X%J^BL;-07mLS04-V= z+5{z`AFbiN-8p#LyZ3E@*=O|c@PUL7L`j)gB6isbKY&w8gMWY0;Z0c9Pr|ES{kx@j zj)-x|Nizj}SwGr#T8R%y4(rh-Lisgtbu~QvP0fz0Haz-9P3OojblW>){DJtdy1&-Q z@{m#C6FN^AwzB*+{$Yelgy{9PGl~si2_-7TH`#NSPe%(9y*vF)qvy9w&jd@Xaf)9cQl~YmW^gsC~W%*!?$P!9S@=Y8g_BbzP2AU#RnV*m%1G zb-!}diZdiAcO5prxy^ibEo;3qo8V}f6}xCI`~iF*PoREdGc8As9-EYJ*MKY5HLv>> zqc=DtyAXsCm%7@m*x{(taO~&rMh83kb?BWXTke{e((E6m=TRsk3TLOjFYF+7E~<(JcrRvNg;eqKlkuUme9hOL=nZY zDgEA1{F~7E9bZ708!r(WP}3wUpf1_XT1%fIKW$pTJJ}+5HXdDI@{>qRg&=fV7l~DJ z>>rFJ#C7f)F}7=mgGLM_GVr${{Q0@TMAkV{0j)`AGT9rMNoEmry>yAMaxpt5N#x?< zv3U+vZ)6fN@>$tJ@D=SH_DteM2vDS3YY&-tV0Yr~t%vdXpg22)59C`V){T>UV|D-D zJ{2B$N2gd4o4)6%32Zh+%=O`kR@eXeD^t%sdN0VzS>iq)|4t?H<8I{#dbT)PiW zRzMe-(cAbd_p%=_mYlaP@|FA){ciHx)D|?LX4eY0LJ~t7IVdm4gnOLEC)}?PjZK34 z%8%uAWmmOKAr}XR2|){fwaTMMc1h79# z)IGKl`2O60!Ia~_M(Rj?FM#ohuW!99^;o&~%=BJ%TiyUQc31QL((yKcTS7N5paQ^A z&m((HuiLHWEhg*#DdNV@n~&RhZ;nB8#NT}iPD>lP14YgKq4QJU?dLwcw?|&iBewe? z?29)E?$2}kwB|iDtsdN}$jeu4PcWnWb)6mBoeO2H>0SN-?}QrqLYDk&ON~+d+7Pm_ zi4SO+H{WMI-~L8u*sh{dUHSZ+2U;p9WO?HKFy^R@rYyd_oN$Oi=&_KrTqcI}aWbRg z>cDWsbyAUuKo&BE&%0&XzF2~tWV!V=FzY_QNIyhg;aioc9Dtc{Y5^q5}^P#GgL-(|!4&a%I^O60G#D6J*K)}^mfMacPue{XTs!&nJ5dEBpL!(jYqDW%=} zAwRZi*$md&aW1x_^dfqbV+TxrtW6WT?-OlyAvuT98$#menpA7hbI5XoWv$tZZx zP)kM4&l{tIyBMza&rI({7U}>8Ft2i9O~hi{>YxKjia2q8_UdK$ONwv!hSZSgkA{k7 z&F6v}%lD5Pi}aXCCNBvgJJr)#Uy9sEh1%SI9r0d!TswPvzlnKE#^{m}wlDLLCDAhe zo`$>*nNXzluauBZR(*M*dPr?kooJ#0!r#7`1UCpt zVA8-I2G1&0$fSOX+87i3tHiuh>FoC1C|@#ZV~xz_)0+fZoE~=)gmmu(4!7l zhijY@&9HWu@9k*7`ce0Oq=n;^0>hXzu>-1XxAaD?LqwowZ2CtR3i6BnzeY}~>BKqS z9msh}Od=!wE^MT(n;6je1_LlD{a~6NDgSe{p9d8i8E!=2T%PNHU6#yh33VRU@pvCE zCfS|8N%mGpLvKQ8LeCRPmmsTYH$Vk2M*nP*5@Kw-v*XtltlhBC1TWBa?k1A(Nl3P! zo2q~cY|!Bc7u3`Y+{kHkn{md2W5wp3Y?XYU9slTQS3iUtfmz2wUoisba>+OA@U2+q z^o}#QN7GlcYs`xHLN_jk`j&*RTcXsDf61pm>yv*FedAj(W$-XAHETOVGGwtL@6`}6 zf*`K@D!h~7!sm}~IEE-?f?TVB_-|{W-+I2{2)mHpQ#&5sAR|k^l$P9&ea6gTCNSD{7bjk4oaTIV)V_#FIzOA#y0aH5%1 z@rg!J^nr&g{AJ$$xA6D0Nr5Pm!EvyfLBHOrT5=)928a`7VUbT_jF(obA1sDv93tM3 z#Cb~f*Y_*7-j}E!^I+;THnN-ZHgPyldsJV|=Dd7_AV0t;*{74l;b_d~*tsS$@`aXZM->UW|5QAXU?M6gY(h!f; zp5y-=WMuG#Tod`0Ei#Sf^O59lt2#zrO8vJ``y>`%#UBr~Iks7L-2pg+H_l%O2&5oO zOG^)XnNM`wK*tOH2UTZ4xeA4uUUzHEOqAfef!RB7g9faJmnYD0_Cb-C>OL|h#ugu4 zlm&3P0p9jE2%7}p7Qt(~fdiYF!`*k`;eda-i!XuZE16tTO`7LP=>3Wu7Vda;Yr5dA z?PWO^x_Q^u^S;IQ^;147O<&;)l$_jcS8k%xaQnV=+Pg9tD`YC^u$5ol8Rx8r< z16>lm*G~=c65XscVAd>_r_&m)CY4n&J596ly^gnVC;mEF9;ZL@zZNcpqcSI8zg0M? zmEfs2J!4YP;gs#KyE6Bx=g?9_Zai91hjW39mn)gmUdz0rV504VlT#I|CEdKbCu=HOmEOFLa$sb30801>?la7S!j_~(QD%vml z2G?kirqp~A9qA{Vq>&BJv|s3A*=c!7&kR}>u(83E0$zsw>*#HxOn^eXxW0b7{fmt) zQZoR(Wzx$&j9H-ZRQ7Nf|-0vi;tfBU|Uf{Aj2g(BZz z>rX;D0DwW=g$;lgER_ESy;1ht;$u!3w|-^_cn1EJcO@HtEcywHq|;bW7Aoj~{cObzBfB%3GO!4vr@k-!?taOji_FFq`te}E;wshHS;0H!Zlg;w>vLhoSFB18(Z$kc!*j@l5C zzckL1$teXYrC2qTe(xudQ4hs)O2vM{RjLF?PMS#7ELf%{@XbfjIWycLz!U5qlLr|c z&pQ2Ua-NLG)Ma#~n_zUwZ+Dc=YnOdbi2icsygi187cIe=pnSSgx|63vJ*IJ;X~^s> zhcaD`Tz8svbR(yc3zzPCpbD=jO-pvpHIJ27R)$y#LtH&Avbl;mQ{8!R zZ7&*Ss4E&39Prfs$wfd+*v;S^cf(2@&Pw>JmU{lWXh=SevLpn8x^f+Kixa;Ny+s-8!E-Z=M zp?g#OhoMx{#l`gpTIWfVAZ6>ZrAaYNPDE2mJv>yG-z;A#7 zSe_A{jqn5em>An+TjHQNMZOR?6kHZQzCTdb3Q#bn98{-(k9ZwGL%soi1x&izKVThP zv&-^1J|>10#D_5L3yQMlGud^XZNM?uKByiA#y>YUNr~V`!XTHe;~tqaah{5dPBUiy{Q}Y;P*-*LeSB z)p;|ITh-r!Cc0h2;7#el;_o;TekTF_4MV-h58q;wX-y{535@rbxGNq*s!ARYxKEp55_#sPTy+x}%Oc8|1xqHZwZ?d*vREtJ-60Sz zKgqA`pHNH#Vl}gar&FEybCyu0F?~0%V>*>`9diO=_mziuVUho+t|EqDBX7wByv&72 z(qYm`voyG(#hD0VsZq zk6A@abz(;vX&1Z!yJAh5pQGIGjCx*2IUUEht6;W}xpcW$RKlK7m#D^1mTA9xOs5}_ zKWC<&l2cw7)cH;LG($$<_2B@aZzL_hUzuJ=m4gk2G()ARA7{YJW>tbMT*P&J68QLl zyjp#drAWmk=)&a&b#$&QlYA=Pnu`L`=$uv zWA+nr6)DFO}FzV|D0rfHM)ECq8TZuYOo z#&(02H?=BvxHSZtJZR*Tvxz@(CQG<}0&icEOp189{xrCsvAqO#VROk$ZMpm=H;68?EqM={zd16P9`#Ij+h9W*av7302)N#@4;$G@2#amqO|m^!v!grg``%1^nR z-;J!+A>-?8h5t3oB`bUPM+^T|FaA12k`H+Ru&TL#Z;OL;h=BIrtyl5cPT8_ciu-EtDv{Mq9E*X6zhkj!qU! zo#!(pdc#NzyF~Pu-#I($Bx&*J>~|sGAur>ya1a?z2(cOht>XDnQ{-4T5RCzeyln2G zGY|#Mo)hrisxK}tRTy!7FZkO5xlg^>03u zFq4y$;^WyN4&Xbz@wXG~G~K4@g>056Ez-^GqN!bA3g$7MueX_`W00?0rBsL9n=iw$ z=GZ4!|70#J)b71i^_*F*jJbYZcs?m|engV{?p~cxCWV-yzS5x)HeOBf$Wyx%rMz-a zCUU7F&*A$O(fGb(#IU}JN}^RsIkhl(@lzq+IX+XH!svQJx1bh;g3L+*v(CumbD_zn zRPjUDQgV65()W`muVZX0RI_WzgTW{=4p9c3Iv~5ZH?=u1L+`~XmN+{yITIJ6j9ws) zkDZ8Y2_{4~ClF3bq!7cR=p!UpPtUxFdmc7MvXPfKoA35qk85e$Ry?&f5ZzucwbqGQ zN?Z2#u^a~5a3LNWi3$z;=s62@#5gPbI!}iqN$9P>JbpNY_1?LGx<|v@Lya3oB`^-rY3XI>4 z5*@9dmkUQmEuY}GEr04F_R|xd3%$8fNE@F%GwvIvDTFQks$quJ*s3tY{$_I%w(%9)IGB?TkZtS-zT)TjI2+$?sWGGfT0DHAg5SL=?E^MZ|B zh76U7uTq-MRxl`ie|?*YK9fw-e`(ps%#C|$$?)Sc`7~!LJ3mtDCwY8b%CPY_xFRK3 zdiqG13QWPl91vacrtt#pOIumN_&-b7&BU$AqIZ_5P0kxGFNq`@0tKim#c`EiGQnyf zm#9M2*ACF{>7Sk(WddQaed_j&pp{UQVxllyt`hL!>S_3 zW0H_BuQwhoj*4W}%KW%C$&23=*N+fE_T9+u^jJV+A=zoR!%nP0DxHSU-Eg4joaaSo ztOM0;pr+{ZV2p{vr1gf|o1QW@TXd{m3^=^T`?CvF*T3ej>7p<(;<_h!;`%ZUqRJ_~ zh$0hKVmaf}%4lCNE)!GgcWJ+4$u&*s8QJ+&N^zloG`|t)@7xM=T@LB1T;J8z)aX8> zS52}(St7$$GcS>8-@TZXMJJ5qp++=o7?xR775>AJSBy{x$CP9~;wQ^>m%t0?XsjAry@Hv{NUgta?^&?FHBO?njcT^r$Uc z<+4UB%eU*U>&nBC%b{?=;2i~(47_Yv)?TxJQ(W%OoIgiQ9M)I2!s2Bm?%eDz&>A)e zm5<;8Amj$uN30ZaV~D>#GBm|-Wyil;<$d!quom4sP{a@0L{CFRzH}mw^^;h@cji#k zcO>u_Yy=!ggzT^%KJ=%Hl{HDPoCpv`;7)1$;0Ya@)|2Qvw0a$=`oa>maykIsY#5i- zlv14>n|DTxK7ntBKeoANi1T~xUWbfCO=NO&IY2eNrwiHnjc;CQ8y>yt(3*}&Zc^`A z!f8)~Va~)iF0K;3&$ro3OdmR4sar=-s+vXYFN+y21Jk6WtvDafCCi~8oTW)0{caPn zE846!vdT}dNP7K#2#ivqKJ8gLVSG1iwu|hx*4;p-YsZS^kwG+bjOFloTLME~B(FFr zC^XXEkNE05Xg6e%`0mG7(%dR{ZbjD7_t*51+O5GERXJR|GV9!|aQ@M*0cmnOc=B$H zB4m6`EWMb0Kw{Ux*a}*y{g(_3G*kH#0w784lhq-mzLOYw$ukyb4Ip z=X4@4sK3_>dXvL_w*9M&_Iy98?T7AHuIWBQF0o$Y7yPXK%z`@@H0n)NoMhnlXrDr< zR#HEW&XxAj>G0cnrGiDv<7atG4YOZCIO7WXo*YH{$*Pr8EL zsujGg0ew^ov-jo@roI@qhoV%reOEoM)hN=pBQSnv%cR%6^6v5F|7ihCB9BD~B4Yjg zqIpy?^Cz*T`??PQy&TPE)zUS)e}lY*DT(ao6!&u~udO&JSB=?tu8NA5%H;3<4bxka z07xYqjZzsz`48M$`=Wz1AC(>>m_GSaE9%F3c=~y)cm$lVbqE3I-~a#GV9Cl`4OnAd zeqJ|3gl${ov+sX%|8BXKM4#!H$JRixqHPy^)U}D;&jW`yYaLPsoR7hoCEl<;VJl92 zec`CY7x)C;#Ke_)o|xa|!-aY&XP(3N`s!HN@9QtD{$&7x>cNBQjWLs1gUx4B=1=uDJDU7`d^J7 zkVKa6b(v#k0UQP99EIjCg0F^z&Bz<;gNlZ8gC)bRt`4P9wTbmf5K>078$;#m%|B8z zz8Q zgxH2if7L3=4CmA#4Ut&<@Q`5rh}v%vB58^rzOc`{!!7C1h~OkFf~X?b7>(4H$9LM2 zgr5dm%$jO8DSgl&XPH(tuNl}8ILi=~6^S?Lgi!0yW7c|t9Ih<|-I)kfGBm7~`ZhHM zK9FMbYc=xRbsc*8r;w?GF zyjK_`WLz>1R_K?C1TXWiEOgNqRn>~RY86VKxw~b;k3XN#^V=XBrt6`pl2pF!3lA4| zE2+I{9R*B_-mAlfQ_oDm)&#`YFkGg)7Ov;wDKn3!^UNJ6v?kqtWDW3#a+GNwmam+7 z8Xm6}ZaeW>+rhWp&Uin5Rs?Lx-#efT=mEqyDxiYUIRPH4KY*R=#MG1{e(`WWc)1iH z`mOq;tcW7o{a!p46g>ur=`AR=L&F?8)jI?I^sB5s6Rx!8r_1s}KtF}zKDk>@Bkl#C zp&GkI06|RmI2(Y@aFm+1Au>?X@9*_c1|9&mbbY>G83jM^v8E6D%Xlzt5;nWxmYR=y z`(woVo<$u>E%vu5lS5GB`sIGO_1CB5rNzFMae(hO(TdK8X-S0y*Mb+JtjNG(R3lDCRtq zLiId#Nf2ZTH-}&qo0F;)3_3Azw;=vNOo!RwMxkP<`RdSPsl66nDZU? z=vnfqC7YzSMp2$i$8GQNmF0|mZD+udPJP{}7WU_cl*MoQ0`*N@wc7jDZIF_@rVORR zw6r4dTop|qAi2@KbRtX^fn2ekp97UybA zv1&Ce+jjiOlHH#{EjySQcPtEI-G=m*edaweluM5`%iU#5oXGg46S$zug1)?Sg~33q z@k5hC_1tD8{}EZF{_;fuH^~IPhB?$Z8kk6QtZQGB7Y8rfX2Oneej`x~SUn5G6XA|Fre(_0_b-701g~*A?dNB)jx#Gg26_ z7OJOFxN=FDXOCb%PyXQFchf<1o0?CT@1EmDnfD*BG&h2A_FFtMGGcO*>&-az*`0kV zHr+KBtHeq?>Dd*2v9tQ4C~jV$JP9Y3Y50GpJ-CKbmX@h(O3H}YK%_^DyJ@l|mSd)| zH3*J?T&BR^HcQQPij+ii6k8Thr*?B@#-`;SG_2Cf=SrIIXx}_1n9KB?T6qoCl z36!BAWG4?y?`w_``u_b+xeQc^sUaG#n22BMpOi{EpPl%6n&FbH_3v>+>>Esu8ci?E z^%I1>_raE?I@LrQwI8P@N6r0Bd?#Lb%H0`5yZ0?XW@+O`i90KIRdPgHrkJ^0(-JjK z^`wSswovH@L>iL5DG2bsVI@gw-3>Ra`1?ZD(#pCA444-FHISE8RG;c~hdCgbl;g9n+Tmbx|LR^wzl&LP##c z9X7TgwzHiOjLuNScQ3_=18;`;tc0RATurOLSh(dm21I(qtIjG?R%B`AewqvXaG(h1 zetCl&3{7o?fjXuG4i7pm91ZCfMFj9hm{K(qb0&VLgKq$n%&61)K!CT;4vHo=wv1wc z%LD+~t2~9WdW*SE1@5J8s53bTcR&iclP+u%2r_8`f>8-#I+u=4E1|1Y{hP7I2myid zboTnEGIf+(cFQtP3qQPYhw2IjwD-<*qlHfowLG%6d)HQcd3T*WYy10N!}~f8j61Cd zH)4b!7azo6n3n6yH+B&Ui`40w=0ENnrb};riLfp{X+_h}Bcj%Fg2Slp#-T0r3|lC9 z=N%F^NNK>F(2##9fco;at>4NCMlX4E>fI(s#IMn@c67E7x=lHk$UN2$@A8b{ZJAWo?)FN5}KxD&goaHe86II&4I$^ z%2-X~m}iZuADow#uSKv`=(jN_B3e{rG2oGA|4x~N&-L+I^Sw6tMBm`7XAzJ6bHw1q z`=%+y;vZB0Ts0T*fZr?W%Y}h*rQqCPNXU-3Hys3b@UJ|HE|cdg&zc1x70gLQ*!&I= zQMwQ_N6lAoGuix~^Wqtz_vzz~4<+Of879ROkX4#O%CRi4MM^NH$1+kW%D6EQLj?^r z;@JNd7Sdfi>mF>p;EpOMt?2ejt5E4WN9N&0DAspSm#U{nzjw)J&imIxFOwcnlZxeX z>6Pw*6mvYkW6c1qjlydaqdX7vA5MaVyB)Q(!94n;1I;TM5HYqcuC74G-OetS|F}7> zxV$wL*b(9M@#?*6QVPRTRWVVaF-d1R1LB8_E=Zwn>VO0k2b{be6>);pYMRr@O+a zlYWEqERri2qCyRe46D(QOBhw;rz5}57*t5lS8)qSxtm#iwbOPzQ8UJRkM_|!iDoBh znW=^70)gn8a)$6p%=+I3F#p-&tRchVnzs{5WY2buwKX5OI4yCOEyxBcL!rOlIVFyOk~Myr!I#ons~*V5Q5H|59Z#xUOw$cy$%(Ks$ML98vdV_mQ4hB zn{(F_h;H?FVNNmCa{XF(hG2Qol1b{CTUt>m;Qo#G>QU?)B;u5SSZZxkFfXo)8VPYB z1UXi{G-Sb2wA?RbUc8i^!eR|ktTnpN7DqIhLr6*#o8#2n{Uo%7mODy$4zr*uqBc>M zGAr46zY^I z{0Qu?__HkP7l%Sv<$JOv{*+oshG=eW)%O{mLsr5776Y;&kr~^c$KHu^*V!4{zi3Jw z2?b|d!J!0>C4q969tNJR_zze2b5MfDe_rNLWI7nG2wfH_or3)AB)UusA&hlTaA0z2 z=8N%6}DB5V{h(@oVsh?3a;(sH}|cy-r}gE=(Jujr#|_9juFJEx1Lo@H_@b#Gj(CM z6)#qf+!<%*7+R0hZcn_kvLRG&x77^od0FY`OY@AbVJ@8$z5SQj;iCj{#MF0MmSl0C zI_U)r(sfwwq};+nA`G*S#N-P9aO-sgHX88zdSpWq{a_JU5FxyDEYoBbG;e4^5g&b2 zQF%yt^ZR#@H_vz<`U^<{5aa6Dd;HLmXHIS6!=g#Dy{;@nI6i43`|i8-M^Y}^;;148 zaG6kzYhXzsmF-8HC=g5eP{~|u44WELI&3q`!l!6lobnN9$PRprua6#V+J$tQY*+o* zGuSsTRgnb~+;-%WO4>dV)4*}ug@KCt_j;&@(jS63^P8ox#qlS5Z6Q{yN|^AlG6AfK zlEmW-?EykE!!%~Kh(rqV*pvZ~>F;^bVmq1^vFPyROViOatRmGi4Kx%nxb@M6&K)q? zW%9{+w|@~)xNz1LFfl*UAX)~zA>51?D_iv6zy)RB#7Yq>ki?vRW#9a_;Sy-IsE3wV zcn!z1v8T)E;l1Qv!t*PWvv0^at1w#Yfi0sQuwlfDr#fwkwJ(2t78Lopf=3Sf>eVZy zo8Qx^Qlzc{M%4o+CoEug$iI5kdRz^-Xq_wudlUI>Q=Z(ctQ~+G38WDesA7$cjZjuP z7(-%*^}Nc^shO6Sm#?r~-~v2!Q?4|gNU=)wJatAkpoIWU=e_-X_s+U$jT~A%FrqkE zYDzMz1uZC`jrbpA85mUs+x-@(9|oj$kPK4FU`7gFsfYGZPJt6taAhSc6u&|k0WT;hI5ad=;kd6B&RU}R`%I>s#Qpln5De@# z?ReG7G;iY-=DS!7z{UO#I)KmFQ>W2^4isa2c>_zYiMW)@XZH5?)*3b<-8;`CB=wK( zG>WIjG)A@3+}+*3RD62@!h=$Z>xu~nJ`s`rXoetQzn|R-Kxa9(XIn#Q+{bjsz=%JE zUlL#!z~gQAo7mISlTo`lxhD+otxac+Y7q+;mn61CiFQk>US-2d<)nuFzoJ5r!Ne|I z8weOTTrOL3%#*(punK?^)51Pa!8rciS@P}qT6m?~(|sRdtKwNff4>#gA<3mnPR)Mu zF?X@a^;%>Ghbpz;?ZnLG-)kNMZ%yKH=WtbeWGyX5-aUhYUQ$WOSC+=WBTLs23L zeK$0|5VQtQ%)r0YPO2+SFR+x>T#$UrO=l?NcfWPQhKs1nVcs;rC4o^xy1CvfVMpq2 zjCp)aI;2u6%$HyKRsJ1!Ns18eW17pV3y|C7wX?&UXRY#>FwXnoVtyKmiG!yZhp33s zr!&Oc*%G6T4}4#7##R1?p&C7k*T16~&V_GYffy@Z_}YLZi3d?tSM%#S*cJUyNjjmP z&LPzr_vxKD4Ko5Ux25tvePAUCURx~>J!0QZOf-9?XE2*h(dUeJ+LIvLc5WUC-eCSwkuEEgFDg&+s0@gFg_&C^Nf8du zL4Adk$|OG~o}-d)MSH1N`bv$A#Rs0DQW71`a=x}@Q}&UzJlMg$t*`ANeC2y>;%N#l zQD4DqgJWpi=O~+lSdqJ?O#Gk(+s)XkC28KjZDA~^w?OFD@p!#53e}1LFQ+#*ji;x! z|1pK^cNCwVj-NB?+a3><__kl63AA6gUJH8NO=hz3@r6#OmX$Fp3f&rv2tRuOdoBS$ z<-RWFMHK@;MN;T4oK^Fwq@^sQ$NaJ^)F54kaIhdjACJK0P^k6-sJ>F3v#h z#KBY2gYUoN3dQ_(BGH@xdn4C2%j1@7ZRi1|Qatq^!{FwIX9euC{ywZ*03k;YxYz^0 zOER#h@)Q8InWo!bet1O0>9DoeInv0VFD13m6%8nNx8!SmB*?Aw!m|qtgP`&W6y^q> z>QSM4A1pw-f(C=DY}kPyr`D8s0br2&z)9ExXk()?G(Rq2#~-0f9?&9^ zL9JvJiYwlqDc@;(+HZ4N^+otOv)@oASF7=#$Oe=T$+?kyp&cC}AcBDQ?!bTyAW1gt zWVqjK(g=qf-)q|T;3&BrHb8}q4`+iQ8(h>`*(7(3s9~9LxMtkF;ynxIjD-v1qJHYAu!phq-~n2T{G!!%^Uom^Gc!@8~_LQO?L4e#t&Z z0s%AD^T;m>_U;jo)6-~&YwU4a3h#H>D>=&lL><^>Ur?+Vo9*B_SvDjzu*$aXk}tiO zXaDe#`XBmsrLGT0)*^AIV+X#4fwDR#N(g7SD7v(XssB5i%AK50*E>9>_y1t|1;td0 zMAFIjhI$E5CiGzTwkpb`zTyXq<>mG_y|K+12eU%k7UIaAg4%^X_O%4c7*R5QzlM0^ z($^~3lzH!Er7m zIs|h^V;r9jTWnDtSUw7wSO-SB7})|xH`4DT0e*WmeF?GM_^F5JqmFybTPHT-A=JT? zvbO>~%glatO8m$KnHhPs5Uxn18cAGa?E8DVM7h7tQIi}+(K?r&cB*6L#Im^ZO%a)p za`9mVZ8$|-_|+dHeP)bbD&;S8*9dq`q3IMh~=I1RmqyoM33F24cmlgL=#A zIRo%B<&~7|p*MNgYi_dqO~ZHY1c9P2^icsv>is{bw5c@!lCUipvwM~Uy zHT22(Pk78h2yJ{qUB(3Nc5?%C`$0h7`}Z$(!D>3f8@i$c)&_%EP+dW z!KE%(HATGhSVOT`Y>0tILcEq;iTlU0!ootpOQejD^oO>;9svCX8i3hH1+en5o1BlI z{JYuys|!r=^|$ptt)8l<&h5(=Pr3cUZyda1Xb9Jd~%E7vI*8BkS9iB4Mv2m++aC7Br++fZ(!^NJ@ocqca&?MEf(dH_TL zNFLQoG7j{u>-577j~(JN zS1JRC`HfwkSi90~hFCn8dJe9ht^=mO4>uM5-g{EvI?gDVKal}C&`)Ogk0iEQ2?Yw$ zGR|~;Rkxn$PK$bx+B`nF6Xy#^U4}vrXSx5)&*s!_OZ{4~{XU5qs-ebboGebCB0pa@ zai4bS2nBm1rd-053!U!nI3T|VJU+^|xBY9(8}(J5_fF8mw#t5I#Mq#DCvn{Y(O8I_ z>bG9ZZ69%8Wbd2UJC3rlwe74zCB2V7{u~9VsIKDvDU!BijQ9hK_4REYZ*7PNozhIR zzKIm;r)Tm4W9k@@mm!j_r1VJ$qarAB#Nv<;>N?Z&S(spZ=E{>`Ews2%42FS^)e+c< z{rEN50kY&ZFG^)fs4&0xzb{fR7@Jh6{?efyvA;!|WG4<%AR^+v9!IUbc>K~2T3S9p zrgcUt>cf>vW`Wg*OocOD@cVwkaa+%vc#DEXnyTORO(Z4jG^P}5?@;fdKt>+}j6SDI zELpxNuj!F3vBVzN^eSJq%DY5}%!CXKU9@O+JVj(2M_nQ1ABKE%(Qn~lB<=yO3%52o@O@QL=an>`={YX{#rJJG>EN=jwr*3)B#F zZ1<+Uy+cYsc}%e~_6@jp-u7YtD2b2UaFR zu0rBq4DF;fKhk(fe+}cLj_5KCk7KyZwv!Mqb3ji@2w$POG-}r(a;kJxO4vw3vz<@P z;;>jvn-1|DwDZ*Tg9 zN5F$`=H~9cL(Kq|E1vwJm&Z`n;0Nt(0a2-;u*go+$|Lj2O)ocX(%^pp*0)Ob8c!hZOBCVdVW zbV|7~Hd~?l3Ja@NmO3<-*v}zS73tJzy-kn3)($KxiblYBnbdW9GTe_bQbN}aD2!8j7;I-xx zh)d}S44+k*laTy;`bgcwN4>79HSLGNuH)?%vG>Diy2FGFLdk}?&OKqVTIqWE^IbXb zcCvo|&iUVcN08)2D;O9H7$fBdMCivIr2ahLtus}0T}CulLmdriB^X83Ao6k=HEOlF zbn|+gWj6YExH5P8^pQuF?eABk;R#)4k0q4b$;n8{V_s=;9$OLaw=M&0dFT&z`$Hd& ztZkJtW=Pn({mLGfj@=9PA2J!ddzGfG$#}%GTic4;b(+^|#OAM}0`)5Ud+>BTpu$aP zpa#@C7OeeDI-|6m%P2-8w|mus;)Q50ta5`Bf!Due40i+(_hJ~($n*UxzGv~iX3OH> zkrvX);i*Wj(5A7yM(-z%{JTm=T#uL`MI3~$&#HZ`w)~Qw@c_@3<#={; z|F7X;LmaCIUWtI^J7n4=L#mQNDqEAn><)Mv@-bUEbK}Ywy#6pn$V8rE0bNo6#jCgX zTftiaU5=1)PPTD;eH#rXzanHAR;9AyVCffNzJIj9^Zn*AJq!kVhOayxIge}DZ>JdB0mi&=2LX@wlSjsN^Uk;h7n*wY zbgJQC;%PRTXKlGP5px9)7iV{Sda~<(qf~Fj?K*Ujg5i+U!B#`pDr}vAy9az zx43a?X=&M)-9aN7cs`+3nFO8|m}R#w-qx3wN5#ZogtPwVRs6rhY~Cz&>r%tvR8FW# zhtcVJkG;MCR;L2=iSB&@MDR19K6O(p5k4Pc_cphV6(a{NCZRi%WpMTO(_f5-6x3tjOsBc_IU#f7F2(j}rf~hE9~?^mmL2rN06J(JP?w$ea<|%A5tnj8X<4(i=6KLN z>G>w=xu3OU~imcPF&bxJ=G;|CyLh)G2A#*oV+k)Jy# zjtuY`kKPl^+&#Hm@uJ7F1hAy+IBSvXqK#_1AKPcFXG0^ghNgVcX z>h&nE^)V}= z9Y44;+RYG=dnPi?Ts!J}o)mvMFF1kIO7qlt>+^*}#4 z-DN#Q00;n}(|1kx!&)qc#9kUq(1MUE`pCCimmiOy`EA8*zZ6u2U_TC6xoo}=edG}h ze$+G8?uQ161z^GR+4F@rKwDRuP5na3_99-W`_k&c3%xWDgdk887m#>MnV6cAN9sdU z1yDA2gEsY-7Pm_;(Z`z`lD@UPI7PjISSqL|y1@NGH8chy7>qePIh}#^D|6v&Au90N zn$itlgJwa{;w8G|&-`zD8YO{KSkP@^Y&~Xo{Pz*+EZt^wzx+W-Fab+Rz_#s^DpV~4 zZ7O{OQ3{G1hQPgsxUEU?G;Ln2+>SWkfbD!Rdg9$Z zeS+@k%Ox_(1m4Bx;+DR?4|NR1iDGK%Rku4ZQ2XJ4Y8m)>+BT+2*tX>M-uwA&#vJRA zInK}g2;GHM{O1$z3CRBgnEKa*- zIxz0Y!?nAzFDMnHG!(kJOuN}S=ECSL7ya30K=oF@nC=U=*6;g!Y5M87^b++%g`N1l z&BjRG!QKc&$`k=_zTYx&l~sc3R`3hM=#oO08W<#jKCt>@wy~vFO}x|!DZLL^xK-yN zh1sMZ-kK{f3WdMHxy`Wp*h^vd5lJ9Q17DSxDA&LP=z}Bm*kmyXBVu2Myr;y(^DK#h zZ&r`P@N3TRSI1=w{TYFpJC1GV+WSYJC-K$G%?4sdjuXx0){ghY`r*{m$P11jL+iGM z3+b-Y3P5+!epP-%SsE;w?PEA6lhJ~1P=YEe!nHwdWk0A$VGr07l!TYvTkq0r**SE+ z^o5+Dp~I4^VC#NCUZ|@KrwGk~P}58sq@&)JgpD*LtJ7d%NRkD-gxIDd-d7UfoyOgG z2nXYnFl<~oshTh;TXXz$6}k_lYIJWZdRc4cpS{FC;8+_w`Xxa7yIGI%RmmKzw*R>A z3x`_SX}kUqi1o^6KRfJ=x|(tKA%{llYph-tHZ{szyP6#h)5D`eavZ*rYzw5s_p~83 z*olXFysiOTeibYbf;3T?JQkB!QlGJMm3PNfamSG3Z5pBScy2r|^lHzF?$vjhdP}_` zYVR_;SU>Qs?CRz>j{w5@dQaFbILbPpJj|okdn;%U_`he!YEioAW6nqVO3-A?@VYZ? z1zngbaPQ7o2!Ls)kclfjC>t3y8*C`_ok2?g%(XK`v)jQrX`__{ouNa!h|or9y7$wq zd`6>=PK08XNS_ur3>6iX_+yDqt=ZH*>Fea!Gb2bSCwMxKG^+z?xDU5} z4DOs<-9EO>q->N^T?@DTxX+w_N=3Tdz}LrTp1v7;wr5AYX`c)EW-ZfkQOEdJn=OJt zG1>2}DTQUfI_6gyO{#0TeNy6LE|SZjcYlqE!`fPRNjwf7KI~e#U(P7eSu3hmwuVH< zihkvfi%c0@WhXMd;Z&YPS7T5i_WvyPg;|v@Kvi6uq({a_aS6oa(; zd9oU6b8J~6Hqo4Q{12rfh zb=2*37K}xRj_$`rRv(~-z4=K6N+57DMx~@&_s3}CUJj0InoL*3%2Mdp3goz}7QRz{`dsL8^i&=?@oa-ujg4XXD7HcTuwGd+b zJ%(2}?;{|u`iXw*m9_0NJoMd`TfEF)yysHgmvO_51DX{(C+pv@@7OW&pK~_QHt=rc z`UOTRr^8q=5fMtIZ>sb?usJhgR)?D22FR=4rHUp=)nA#8nvA+*ftU33l_+P%W3LIb z=yrT2I)4v-Bab+j**WW~<*f%cPA)om+Z+lodC?5$-DTuCH8wwgl^$(5fZ_~mf>S66*p9OZrFFGG08&73zpvzpf&vne-@2mj zj?dx>5E??#!C(B>%lxUb{xV>?4ISiG1zu^+G)=3Hd&RX@Ha4&_5n$TurER?!mC$d& zL5`==<@nHcyx@-By=dm(-0JEiu%AIqL!OxBQ)9H5sp+kE&_x71E0)cAWqO?_S9e~$ zp$UtPjqUU&!cV5U_ZvwDK!|T9#GU{l=vXnX) zwQ4xm=XQixe5lE+E0)(DPE7V(J0&P<5IJX{V4%{w(ou;~67C+2X*lPzo*|CYN`g3H z$~=~me_FKt-Gya_lDd$GhBX2i6DguiOok;W?+~u3$s8GR`!0+#9+6wyV;a6}!5ORY z3ooFM@z~dVx<^}7z5q9nc)G6tYx>9cN-MC0uJLfIP(M<&B%c1r+MX&F!E~`m;&+8S z4s(p-f@b82{Z_;X;?vt^#JQ+0mlwgI0*4hZa9CN@IURZ#n8w`vU zriX<*1lV(R{g%~gy0K%Ec69k(O|CRi0@0(`1-A+lRk0bdm=2x{|;k1FO~bFl6K zZbKVwh}EcYdm2At;Mt|2oMzBy+*30pU7i)D^$H$u2Wrb)QY>OGvS19jSI1XTvd8C@{x6G2r@Il0m#o(r)< zTiwt-^*a_{ix@*RyB8mdfA?;4JaJs@9|Be@13Z6**7IxQ)utcObZh3wWI-;FtAY4@ zziK9)AVF6j>f%Fj3KZW@MZAUzkgKDz?jx-?X9^uCPMuTWn8gn8h#sJF)B$b}a-if4 zJ_vk{OMEC7hWZpxF-aVt&0zZp5U}(8dl@5_kCHGST;|>E_L1QkO!q9?vw4X87ChKe zSZJwm=*juz>sKO)ZHw9kZGZ1%C|)U%DC|P*0U!b15czR^D$&_z-=cOFYeXGrX@1k+96bMdJo+Gvce4J^17DjX#PxQZmPW`q z`rV;jVv%H>9$Ks^ZeKsm*as(tTfk!(c3*+aHfQuRQrv*%tDMb4SiV)>$M|&O-siK6Dx|rZa)UYVCzq+(SNQJVDD^mw;N~o5^W6&7o)!O1sVQ6qNQKBJv$)>neF7w)DFU$$Ck&$;~-4yob3 z#~;udzNSQtqtu^al74NzE1A)5cj|dm;H-DcYmkY%t=7R|P?;ImO=-x+7cJO9tV{iG zVVCEKfelV2e?j-G*SuyjS3kza@p(<{k-4P7Uo_rUGO>D|1J2+O!!v{^cY4~5Fzqo$ z5DEi{ISX^6S@B`DW1g!x*qRZ?&l`U^U5_D&9d)_JPls&JG|}Ue4&{{Q1;116;lquI z{|digir=F$JtXM5k)252zYBs( z{yXQUV2WQ*K{{jc((3OmO*J*OGilIgRJZr*Lw*qaV;QlTy#{oTgkGgSEuWg6ay0!* zO@FTdYX^8Z)Dimang+gRmDLc{RH;EHBz^$<@HEW-6bEn$0LOhDJ7eKuZB4p0v#>A> z=I7m{zu7J*pxHuwl&N2+PUy|1T>X}0Eokk1f8O!O!^@xNL&G)M&+k9<5QB28@26|@ zSJ=@@anJb*MErNRZ=;vaQ=e)t>^kCN>Pw+@}&!qP<&(Mo>y1A-waQ7(r!0P==%Y4?b7|szUkh zfJ<7d9f^}+Eo>qVI1G7b)|@8W64NN zO0104nL?>CRTIcF@d7@Jw8VyMVj`HwMt5DJ8P=?{2katesd|%56>Pq2F1V9D*!tIQ!k>ZTpbU#vU86sfQ*7LmIro#Wjcu!hxDDbFbxQ7_mp z8IRCxASQD$)VAS_ANs<KG;@Efy3j~S@#5oaB-040)iv`hyB4p z%A}NV-tW7CslF|8qVE}_6(WBNy`>>ZBL6~)Ib)bKC`K+Zw~;L!HDyqZJ1ge9-VhBliy@*0Z-!AXjrhgF_8q&^&dch}jxjvDgRN<&sVdQVbE;v!KbjDYlG))->K=RfS`Q zce4y*O)K%p0kHq^>z_&YZXO0S8w#1iF;_4F4o<{`|79yOBVde3 zp?ySRQmfwM%DIXUPwHA&ea%;nl}b$33(8uz128eQ$#p(|2h+3&^tmGJ#@Mv`cr_4x zYY`p9izgrulwj7CjY_b={0OL&nBHClXqAc>Qg;Y2!4#HfZjplYW=*Ie_9*kyVpRoC zNFr%(9SO#z07J&$=zseY>m zFk3L~^7De63Q3pX?8#_Lm@7}L!IyVB!~X2-S^jkMz4Th6;|j)oBy)r*HT^%HEVsSk z^)7mBe%Y=187D{C<_JpXV0fl{Gyx2sUiu_oK}Sln+4=S+;c-)yW+2&Q07HjM%W z4jc;#W+59iP_+>2IqS~ z@ouoozBzvW>zjjhbR6Q-cj!tSY`f;<|WQb17-8&-av?x>S3v1=#Y={ng8e3u$+0YNB&+1UbU%)e4cmapT0WR zrV8VPuHJFkZ-kz|tcz5mEqUrM>;i58!0OCxdSg`O!d>&1S^h1g+j5aIF*>}KZP#Ad zju|tCDdA=NCjuRspIy7LcL|&pJ6h(0qPKWSzAG9_YCInyXM3EXmiHCEzB*a+jUX<)(k;@vJTig&(Lt*eOa2c~-JTD=ss%DKVBKkv|f} zA_cG|X7M=2zQs%n&aST#^)DvG?n$*$`XiUDjDrQ>=mZ2HArWjOV#@Z>qFvfjj18Mg zS6V-B{xn`h2QWn22>aHA8uNi9yoGWMNp^nQkbP(5z|WkPxqx9@5W(sq_!j>3(|21> z85ajOHp*a4*MQ_2(j_0`GN)^jA;dx`{nG=fONM;IQUoRV!KfN$2ThfM%4VN22t|TFs3pIGgqk0ns+vP3`j-u}ZqKC4I~|gBd#WQnQHg zqMm#f?y<$|(t9VPac^4d^$1!L&Q1SwK6!u29HNK-o$&`p_VhMjlcWofI}lJLd)BXY z3!o_T{7%ndg4#bp=SmNBq>HZVRxV_qif}!+oDaHw1A~zv5hZvHYZkW(5fSt^r@c~_ zyPc|>XTNY{#VSkd49i?W5tq)j3W(9bTN^f&o|2MsHJ~#hzD7gAZxTI~4mFB?6=l4V z_y7k)Ce$dqOkDA=CAfQc54cB1fgaPp6Y<#SXlH;VRe(&$(8vgCUx8v5R-)8G2>$&l z?;|^aXr6&Ns$GET^Bx^BvL9M#_Bn&vhD*6n(xvA0S_qV^t%fsk+aO632s0;}+;d;w z@c&0{F8bdL&MtsnA~dTHz~4WdB%uv=v3MgR`DWV!z+9k7xEhX{F9*B#Vy897uGYIv zyvI}g9DJgHt|9+|{5K4o4z2qG+@N6ynXyCgW<2*gur>pYJBaF3`F8{&QZ54D^VeS1 zPtUc9pB{_K;PzosFZ8`050bYmPl)XhEgXlU4ycfx9w)Gy{c4}nA5J;Be^|NmRJh%* zH&j}eTHkt|Dm0g|&`aJBHT?DC-cUn3#Y)7U6FU@=ha3~0TMe0;b}Ca9QavfZ6?w%o zXK15ILw0Uyhn7sQd}ujcRxVQy3=&{?eJSyW$AB9OJh5Mwi#j`7u_EILIKg+r zyCVmx(|997NzE)q@musbrGJnB+^Mr$X~mD6qpK z-A>+f)coOa^FX8I;4xLDUE2H^V-H=MQpF-JBNXXryN8@qm||}6!tTT=+umZIj!m|e zH~d_l%Lzl)5k(719shX~%VxfOEnEB@55QR=J^(*ep!gjPf8-5|Y!dL3C=S)fDQ;&_E%K`4{o|k*Q5MST2a{$85-r&pYL{K^cX#ID)qes0prtKJX z{+BK?`w4NopgR0s{PmxwfM)?XZ^Q2tqZzOtp#I9I=bsm}N^d}4c>q$ULhU0EN_2{! zux1P)cqk0MdhkM4eunlGyoOzXL6h3^28sd5nr&6&;sbkj{Yi+HbWre9Z+kwf@82pz)bed|$%T9#{jMzXNO} zYKT4pxX=5SZ^d^!dnMVFfLjSL7KA2L1BGo2r0#%Q zH>Vg2SE0GTjObtx^ALyy&!Q(;10bR|Y?gn8w6(>N?>ot8-%*ZuxGpb&cd9o!Sf@P#u-egMYf6`k#o}AK8mrQeH-b_q7=#nP! zhOWDv@h`LDDix(}lmcvmyidf%xRZYeEh8HIoQ~Db6SGCDY%F(bclS<2TYDAFB`9`U z@P`Z&R?#}vxO+UfN=44pJB8EEy{UY&MyJaHa#=Sw_c6A+Xe6tfh+MBAU8qC^En6Db8Hi}=(|aV+WdmY;IwF9 zbAzSM$n&Tt5uW70l`}+Y8?$yHOhp$!pPRw^1)+*5%GivE*mIk+N?e6wK}7oq8zM1Rd8OOk3>1ig~f<>9S3se_(1jaKsIGmXb4 zD$xOkD}@K`FF9x710p$~B(}%PpdY+^eX(N=%IrV= zZ?0Akyl8sm?H|KKfhY&GBkJqlLz@dwc>iwI&sX-+4c>3r#rlsA1C_u3oQ6U7a0fr)NSYkhvFVZXjT7-4xoxCa#yp<}^8RD&23m<$4QK!^$aucyAVSmy|pGlA6A zvgQ2y=lxAkH`$u2KLABU-{lLuz;}jap=(||Ms?8+q8I6{Ise^RJA2(<@HMWIPJMnk z0`1dRU$;c*e0Sw(dfQL@Pzc|3Mf#2^9thQIUate~8tAYxs&iO^@IJr?fC~Z;Rsm$7 zrnYv^+W*+v_tzcz+^1qfYwq&I6@c%i^Za!iAVDt^M%F5M?3ZT@xsp?5{3M>gaKAVB zo?oSe+5Q$JsRB0LIU74WYl}Bmi)Y>ZZ`zjd#X0u5#qGWVpLeXe$^W|ac z{(0VA2YQbEgRfJqV~Son2Zr6>J>PasNk76?`6$)w6`rhNUFB)=(ojxAsIkHH4~vY? z#)h%S6s`j;+_FJ`&gq^4dGF-adx~Lyj}tPfFB{35EIshLyRmy`J2#2+Ao-{B^~PB+ zL-i{#P5NI-51!7+N+h=or*zIL4;bY@a7%G>aaeYV&WwzxvSq2VPdTj_J69DdeSDNp zJxJ0Pr5+p;-$t|-NGvXQ!NMXe_UX!u}d1u8v! z5Ep&g*g(gazU-fl->S4Ey1~oB~N3^Ws)4dvaBx(gLTAzSzEd=OPrIDi8HnN zvvwdgCVHlVAmkA2=~+(|aOmMrU6s`)&qEUz-j$f@a#1S4tknIWNuj}#M4z{|qVcG5 z!F1B;>0Z(+3`Ql=y`VfsR!b~xngqfAcmF8?X;8z?b29@dZ^qED;6im;n9j16jfX>KF9j z8-E4jLs2eO%4`4a{X;0VfCm0S5(a?sSzVnUfev;UqC^RVVPGRHvEx1cRSbYE8|&+- z99^{5QU_O1WS(xl7O7u+D+$C+>@W-oNy#)3dkT>0@L6ZMPrV(<00|bvs{y@}W`^k2 zBiYR#)z$}$2GEZSF*i+K2l|b!te`vp8vy;kp^Fk|@n`g{Lyd7Ua1jB! zQv5?MXd6QRGX@RLj3^`j z!wI)8-*g4G5TH{65lgp`P2lhb$}Mp)jb~x!n8^RM6U;o=`IYUnZ3eC}P){;1kCA6^ z8FV(SAwyn(8v(7RQ@$`QY4tQn1iyWM{&MJB+JlX)E$MaZq<#wscLV}fAly979liwh z#s6?{$Ugwg5%MypF|?nZn@f{?!w2<{tTSD(K~{Gm{RR*XkhUe)n6H?7>@AT%53#b~ z@4r#+1&f0){fCu^z%rr=yOtA>h33f2QQlDMxjIlT>h zN9M*Am-;e?t)H#89(*;~14f1fv3hW-Pc$CJ356{5;yV`Cf10^d$LGEE=Ty(G818MV zy{(*gNLkpJ_)+ikZeaHo7Jr8}o*6z*FKf@!PtzsIf4lO!;)Kmu1Ur;}5Z0}jONz#p zJrxa>Pd2no^;N-d)V$wl%;U{)^E7|&L}c9De@ea#h4DIE)6L^ z3#se#qbptT`8w*@X$~+(RW)A=F%pVs+ma87q9zpbeDDT5CejY;#av1`r=?ysTQkR% z(*Ke!ZjHfu?Y$V^)Qox_YiR(yUp2$`Awdk0k5TLj=%2Iig1W(GeB9Y&v5foZ-0Mb~ z_r|Wc;OXyj1l!mWXukP3Ym*V0>B14-_AMPR&h%3ry?OHxx;cTTo!fhRsm1EQGF~3Q z?nJ-S?h5gQw}ApoI`+ z%V{@1-TpN+Vnlji4wt6K{i39uF>%O7HO0YYb!Z<8pN%-lBL};mf;rT5!s$fLe8|kY$+vdxQ z#pd_2SAXw@@y_&ym8OY+%G=@Bmu-pu#vK8c8DB zQDh`d(n6+f%p&=QQ(!1iPs2b>rU`SdYD^g4N>G(CoiA2NlPC~I8*Fn&9VSGHW67HE z08IPB1So)+T7;z<56`mx%Guo}26aq7&sS1K;&g&^J_kSHIsU}zdNir4PDu?LAm4~( z-lx1jS3CMPoRuX7p|8Lc(pKfTKR>UgJKQIbuiq8P9F7bZk%+|&B4%Vsi={X(9x+20 zVf(wG#)oe&Bg73Fi7}(MW)l>%hy&xt_C{=;By2<-g7_50Q(!=K{|(f!lvJ58^D7=vm=STvHAHkdQ4yK=(k z?EGa@hL-<@=#;}u)}cg8D6Gw$hfl_j#Q%ofxj9$6?z%;tlUO~swBUm3Q7U0)(3fx5am+0qO}iY1aeN`IPBH6Qs?GgNaJ zNVx$h(#sZW-oemT$LlbcuUEDt;%lC@y2o7@53iXbdvaCqa+0AyKAwDv3QfY4#``$< ziY2z^z*lO7o$wA1t8Ks4x{ZB%0>)=VC--zE4YdX*&0I$csU-o|dq%RFw(Q%kX3_Sl z122(^AMVgh7nL=KE!g&=KV4LmO2neWlNpN1O$vLqtwqVqhR4K}EiI*fa8o;vxgO+wRJ4m!2|Zw>758&ZP`<=N-CsY>Tz zmK6T%;lq}?Nn8I^7^9fiwQ$Sn(wqIb#hZIX<%??0sb>fLXNGc9wTrrx? z0lK89wp8G}rim5~O&UTwP)`qy%}Ymky|&V!{y4#bWidCmks*Fhqldt0E`Tm_qk={` zrX3dX6r0G;p5$U$y!u$ManX=*mh! zB((8OFjMVVXD5#FG^QQF2l|^5tB;Qiuf?<4A^r?I;9*(r2NqP{f z=IGcrC2CGP_Tjmly`e+IU4m`y_CA5Cv9?6w9>%xiE7YTiQR%X{|0_f%PZv1G4_uj^Zy8aAM2{r?tW*8%gCOl<~WtHr$9 zbt%4WSbD!Svb&TZ2qw<_V#;>oe8zRX(Yn1Fa3l%qVE)|R5ZmpeWz;6}KBr&MFH6Pu zg45{*qVoC-7O-Nqo+go8*)Ff{b3%N9J%>fBY*EeY_T+D|30)^Ob!RZiN{X#5>k}tV zGMpw9Mld4*)#LyYaEBIi63+8HA-<9i0Ma>XnxG)i(cyn3A_os2} z_5vTO@M*_rVy!cZF{gk0p(WQNev2A?MFWb)SkWd|kslGT0AkZ_#xL3`I0h(Gu!|;5 zx5bMvRqDU;!DH{@ZIZhBZz-9n7O>GrS+nMX^LH z!6pGJY;M*{25ti%W+>=&nqnWpVfp*$@%^4X4^ldxSqgeAh3i+ z_Ul95JZb1%Xjz9J=47_Z-mE|Tc{Ayeuitt|_L5B<4~iet#w}d;{^}5dTstR>n5n;f zXCu#g*6kx2Ej%FeicgCiyTKzRW$K9p+tCA3&#t>fZlwK8y49z;R0ZU!w-w;ggtoeo zp2?(XzTD+Wd8~`=-+mmF2xExKeoZzkdE!^9q+d#`hY?KP05jx`U}nT`h<$ADgD*{s zRZy;I5zp2Ye3$CCwq2*9sw~53Iy?qVF3RvYn)Vd)yTqA7ig|Nntcbd*16G|7rgm_` z6U6GQlD#5vFg)qfNHxN8PEEPlj_VJCA)bS?&%!ubwd&?^F7D+!!@_LTfHH|0&BOYK zbk<3zS%u}Mha(q+iPO^~meUUp<}43x&>ZSN50AK7){=&1$X)sB5?6&N?T)Y+(#NC? zgiEWg4qg<@TzpRmzfzH6FOM>(;6(5o~L*!qs^;iw!U z=mP)MD=3J)Bqnx7gXq7HeJelUNMIl`U(?7dUC9kva+mBh8yXxYNOL=0G6987I>3 zp+xE(G!|jXpFVu(;&L7G#3e``9v;)dUohtQZeLU`r_Te?>DoXRkUQfCdL4Ay6!;tgrEYCAhb;Zs;SKNC_>jF&C z!Yu+yh+HAU`K$SwH*d7(A1XUK(=&fPVG32oU4hX)`d}Q3O@aO%er$es&V{57Uk{sB zxvPhzqghnR?A-^w3IN#Q*^&=N|NGJ1H_9RTX3MlfH&h{e%LvEDXcCF(IyewZZ^iiqb`)F122*-!sTB zIxEva@7_P~sCW0~@`v5^u~Dn(Q0R-#c0MVn%O790{s6!xJEgyf1}Ir&VG1xq3CZ=W zY}C+H#&qol$5vDxn$|9rZNV%r#U=;xTy1FMN)mMhmc|C+txSylXYF8WKa z{uQ4%9@7okP?p(vsT#9T;8Wi2fCtmV8pH_pG-u$FyPa?x5<(ixpRlkk*f;a-yImp9 zrgWaSgG+w}R#wWvYXlRmlC8G<#C^)r&aTCz@0L;8vgF#y$v&GBb zC--%CqgV?t%g}GzpMliyqky<*PeO;{p^~zhb9i3A3wDoP@JVokwycg+A%9K=OWv4` z^YSSHdu*nKi&-)c0_Eb&gI}y`;d}th$hFKH6VvXb>rzTB1&SW#6Bqwl5~EPJr5P!L zpIUISXmcWF{9OEaC+17fChq8u|Gl65j8dIDn8H2_qwv{c&^+w?l?|06rt;C9^DUb$ zPC@^ng-3?2W%2(;9GwWPIyDPXexI_$)WY-QSt4&e7Ib!T{*ZE~L#*h2xBfVzPNaFB z(ywz=6qZs^1sbNpsfsj4bLeuP)^h0+YJZNh6MeeHrq^2EAicF$eZCcb zg1I$TR+W#?wE3t%&z^7R>J3*jyZ-MQ)~u#=*|`?~Vy4dNJR_4lS1v^vOl;ifLzZ*Z z=CqsLdMR;JdsBjYT!*@pb!v!|Js*1iTfuL5B{AwKZdq5ae$#7GMTPQ5Q(BrI(NeM$ zjTU->eD0uRD(vD|)F857s4G1rI-a7VDgiKrbRn+E2**@~LOc)I!37Ttdybi2j_Uq=DM1l*vt zGtb{#6p7BY@>4bnG@p+QOz&|0Gvy4?P49v$5LEKw7BUE#2D3aCTK-OPhs(4cv&QXVd{RbCpSl>(>pab9y70gB*D|cAFZd<>(4?Qf zWrK<>%r#GDZLh!kyjKn;Ut(xxzV_q^otWm&!CgFx0h#0%FY|P1S+?A@B{18nXqpr# zKkLh@Z8C&V=rhCGz zWI=@=kVWZMq6YUE)p+rD)~Z4#m>Ltamdl90<=x&3qm2zZB3jRQv`Q@5F%!l#tBc=2 z%cDnyZXpbh$w;|bHFO*Xi+*`3*{a$JWBfQlEjo)37}`gVd1i+Z^SLB~f@lw%C6EV9 zN{eRcCssHvdp9Mtu7!JCT(z#1SF3<`_L}HI1fS0FywWdEh9yEFcoehcapTk6UuQLj zkE6FnHS0?~>v}2C*(& z{>7hZcK_fsmwBM!vi*nTdK$++>E^os^M2AD_MB0{6!OcH>89YDlQRC1kn>D-CB7+H z!q_!!dP*zv6LB7CU)Wd6ie?Nh4Hw^>fi~jiV?49`ieQxz(XQQ9y-+sMfV*59iCvGY z8Xl({V> z_bDMfbyfk^Wr)? z+SEz^U~tEJ=7j9@u0c9!DC4{dwa}xIr@071nD2W{TdEkgGz3dYu3?Eb2j*#ZoV~cd z0baAH%S`8Y$`;fNwgZ8(TsQZU7@fpp+>AlD=Xw=Y1kY#vZaghjqx0Xh27_yalA{Hz z*o0ZB!uuD4ZDPPJ+mj0^$<}YnmrTq-?%3?g>%)A9_}Fj0G-UVYZaw`p<($mo@JKj? z%Ert_IAy)8Jh273L4$`$)l^&G(`x3V{#4{Go4FWp>xG5#>()v;=RW#B9o zM|*!O?`wrBg?m3!d~DBDWbV@<38|1xy%N-46xY2=g?D3ubv(IcZz-Df(pzGA<@7l$ zRVQG!l)*K-#$geaf?te8S9pYQI|Zwz1eu>H*A zvR-`C{cWG-pvdjOR!zm;W4w`rwn|DM6Cx^@awAV3EalsS#q*~KKP z~nHq7XwG_Y!>YN#BEG0=I&96<>LgaoGe#L6oLxJv^d~CsC@Uv%#-x}QggoOBa^G$wcs19N@WX&`dogaa z!D1j+H9cRG*D;zE|+c(K|bA<%_BP_$!>GZZSln zhY$Eh{!r-YZ}bGG$=Sk!hjQI04=}h=ls=#|-#Hr1#D+P)pg7q=f3YPy+OTza$S->F zDR5Jt;CrO8$F|sXiv=~-qF4D>RMP*f1F7yRmgK7-VnXnl6*p5Osy-(hX$$n)6QI4&SSy9z-&NUGlvZz&y4kg{cFK$o(W6w#35$cNbjiyjX5 z;f=1W$Yip`^Y|km-f~ZHzL3^3{@Y3sRT+WAgepNcu~>GTQ5i#RkKv2LOwI}isw}n` zMG}v~wv-aJzvw&U_V*H5%mndpSLjMsmK$XPGV z;r#G@09FX|%@I>mO(I}qt+Uj@^YxuZ>++x{f*a<5ehxc`RoFx@S5!(4TiE)KoV|L7 zG8HIHFzFEYe0cSqC3>Cnk-2b>9Gfs{1X7JBcj7NY3iUfvbKgu&>e!KQ&`;t-*5gfPTsy^@$gDOwwWFs%Z=yrulTu%3*&HN#DEKxQF

L2`z%JmRj_CDJw^1sbZ*B12>umQb9`u;a=&O3QL?B!!-vrbeP$x8$`%GPErWYw` z2P6JQUlgKd>S8v(=%*Y7ZyPn6#0fusNX~TAeGI0N)jJHfJ`@LQ{m$}ozd@HxnHl<-$c>xNDd>aRnj>zM$BA4bliRZZ}~;52PN}SQ;+Fz z67&7dk-&ITBXzc-H^jAuH7QT>&12&I_S)-sXnGZ_In&f{1?k}p;yPcE*6A>~o1-Gy z4^Il!!YbzTrqyARqpuEkf4*z4)Ml&Sv0@#tsaH63#YZEe1^gI|Z7pb!DkOCX%#NOe zC<5J&lgoVU>D=UCj%n+zRA2xT`GZ- zeGK*N$G^M)ME3PNqnb`4i=uj%0x_`E|E)lhC(JjxQKRPL$b#LfpDQB~>BcJLjGN*3 z#U;8=xP*Dv0jJflv+QoZuJYt&UScYF_$}6R|DC|CUxuQ}_Ihh;@!jwGv*t<&Cp~xD z!{P(qhWe$Oqu4Zb@;Q1={34m3)fCzmMSA>XtV&6PQ}(*k(%6!?OB|+TU|Q1mlDX*_ z^3dlLH;%GxTZ)b6v&g4L2lAIpJN$Kza#j1~jW@V${oP1`p;n;_H>-!4=BocDPfS$P z7I=qn97bWTHRTdx3}D5*FbZq<_Y-&chmh*8-#-q;NBDs28RR$$8552w5(!F5Y7|e% za{_&%xu<99#)d8APzwP_p`oF42dw9P3Cxg#+P9IB9G6zdxvLAS%0A#Wq@$w)dXQMa zfL6xprUihEPC@2;XYemAwTCmm%Y}_##dS9|!hIC&(Vdlt+0_bHN9S ziuN2H3IovF^IPRKymNe0eKRxT|?S%%T052%WM$XLH zdH4C-aW?j~l3x-Ob8LT&n|v~(JYo@_F-P3rn+RtPRNSoYTuKnpWvq?%TY77&H`7#D z&%q~>;;u}Rk`6pUz$YsZdTMQI7x-bC$)O(C0SBGb(iYWj6C&t6wDuxFSsDx*cg53x zrJiCNyn+8y`{&B(Sm!qylicdbPSM1Op*hN&^a7zO$_d8_N!P%JF*Xrw#~-G)!4&!> zOsXP}WZSU9nQ7+OJ`jOzI>(=%a+FQsJz%%CDHSFu=}{gZqr@tH_ksh#^}b)?#jI^8&^0UB0;iGZFpOzN zVv4l!8XxI=y(FG!ZQH4O9x8gIWn=sJPbs$8%G!=((Ey5d6U`a?h^puri}fc_OL>gJ z_ZYA~a1=beZ1q}|f&ZUqpHZ4~Wg?xXHI~L;jeXT)Vh@~3M z*BdO+I~2{^f`5o^QkRhT1!`Us>17A(H?8cM@H%Kz*>4iR-=?!ZsWZdg$0^OUrYt1C zIN4bPo~C#Z?gQj)h0~i^f>SOub->57cG?7txB1xtWWy1TIoD!)kSF2Uh<`TNXENK3 zA;bW3gf;^-vZ_XgY zLVuuX-cqyNUR!N~r&5(TZ#0r+wjzT|64YCmF2wVHNj9x!a+gXZ{jj_R~I zlMVC@SG(>ICC-GN?g|DLvI!0EezY_%!+oB@xNStGbT@+a6Xshv{^&M+&sdG3dlCbq zhK#}Awa!F}cC?%b)VYO{nWiE;3_Fxz5mVkTD(=5Ce$Rf9cH&*;>5!;YpsktS-H`IQ z1pbuo99E{5L|!Iem~PJ5<|2(3!h}%eK{DV)P;q}?QNWAAno(F*$DdPOexii*0KPmz z%CJ!O9uiySPe1YT zS@p2YHFmO2%kmb_2Vd(51Z7Z03#(EW9EA-#Ef=Rzt*7|F)@^6hu9ohh%wwJ7oyCzn z#jploR(=Mdx!}z`FZO+lBmmSN%c z4<2;pT>Z!q6c;~3&3*fC3*26Jlkh$Hx@hU)L9rgSHu49LuS^7-**yIG2h}-O(P)*p zeTeA?gsrT-pBR}ziXiwbU>pMEu@^=}{|9m)2PgU_>|&SI&4;l=6L*mkL-%O-6$#}^zX%&?UJk3`knm{WBHM&>Q{Hrc#Usd%E(okyydQSAYuOu#$`qLJz}wHN#VjVg6cY-P?f=LZ)mDmSO*dM+#e;M zerD#)aBU3jCmpZQNN2OKjqD?Jn5bv`JHiO-6G~Jj%ZF2PD`SVnV};GG3v4N8e7B0y zOOLmr?3h|Nxlg77D~nfNQU^qfgX2?M^#b8EQ8=UaJl)v7(D5pZ!H00I;bq};0;Z>R zkL_>^));uHv#i9_SMaHy2gZfi)Tz$W)~H{YB$eYRFeSHFJ38>U@lpsXnBB`2+FqJw ziM^A(sY9EZFCp-xQYd(nLUo02{I8n&1UUVhth z&hFLKpyO}0d2oN52I*Q5ja>Wxm^#a-th%sUD-F_J0uK$+ASK=1A|N1L0#YI+N_UrZ zgGhHHoze|2-6f5rd~5ribH@3>;Ew}*bg#YcnDd%gIs&62y~HYM{2hIwe;wO^ZzN+| zz8S!lfDq7cgP&Z)>l@^{;z0Llqw)rhty3te2m)LW&?Ti^dTA*96R3iWj3ZZ1zx)W! zKu8Yebyc0Y1^GU77pqyqO5fI(Sq^^^d=3GffCX)aA!_l67pg@ds|sXi!)xP(Dt=J& zzic}O*}%ZyY+vu0Quw)ib^{_c&%XQeP%Q{ED4(5u^UB}YE#;)GrR5hSB8PGVAQC;O zuJqmmoLe7op*6vl9m(0+u1$b-Ljf=baued$pAdi`mpbZNyPqJkg6g|F-ck~Nq` zrqSkG37EC1vWIhg#mAjZ{H~SDd9dEhi^SAXXX|gSrT`l;`dw-0Hf>cilXrk<=9xth zNyCKy3|)Ju=9O?P4=e%?flyqH>O^=j0N47*39Eeh5}iHUpRj#}kjrO?S_B2h5t&R? zhD3eDGQBb<$i+OK%A~_crPI8X6Bn`m(+LC$U6{!u95NdU@>zF1KCG~DK^k?^Tny4% ziU$eo+J&@+FCSK%7!K9NvF8bKkec=L_<6o!`(6zQl>Dk{l zxkDxbA0LK2b*%$bJs0cf1U}qxl((3?O6|2lF!UxHasM5>@eN{tdTo%c%u!7dp&|Zr zWr4(qWT(b(Y+u9jK8QMgI-u$u3t(YZ!dLA+@b@6fLSzLzY9m%b=V5@e3sv}<%n4(9 z&L^wlBBvp$kZijw>`FKB6beGnE|$*MaR2YhYh?%WAw&VMrH^;r+Wox{RHrmP{=J*s zu&}gj1Xl%Ad}Q1$ZG&b&DC!zST=W3DCZ+Qi;IB|)Omln}OY0)|JY|?3Jex&YK>Ve; ze_t5d#7l}1&Us)b^e!~T@YB*q$OU2I<>h5?_!sgt0aHgk#pJ=|KUfRoy98WTx89~F zpxK7-8vg+}@xdYlGCpJY;?z6sn4qxbSl$8UN0hytVaf;H8S)K?nHT_^ms*O+J(q^d znYZqJuaHFDi_ms zFclT94#~H$R{l=xG`$#o|M%fH&HZLaa$&0h%*ZLPv$$-oqpVa?OVK+cDJky!g;E)= zuzZVz&+Qy>dIEvRQBT`t7*C#cR7EWu+K*cG8Vvbjc~ag1Ko=_RIXt8;eqrY_QJ;Xr zEWL|wjf>V6R%vUNEjy7x2QO&Q_1}O%3PUQ(k*M5GH>wMtjQq3WT|80;I3F@Mxfe7U zZ_O$MLo|yjqb=}1*%xY{qEL$Tk4s|VlE-{^#p2_ZW8#p(1J=UmH0SyJym@iGQeGcQ zs{A~%Qj@#@PVJR5nJei@ZyZsqd;-18BS(Ln-P+J9iLc_(=An$Cy8*(n`~~_bC~!$m zuqhD=*ZT-+WJak=IJmHdUh{;ya)Lhd%g~1Bq$(Ef&dbfHuxt zFICMx5dvF$JL_0V^44ybY)G!Z&+U^f<+pM?X`m-8pX_|%vyl~_m1;pNFM-B*u@L%1 zZk%|rqZ(#cu7*umM;G!uj3Pxz2mcvj_(oMjjS_KhxE>)U+$+t8oK|r$V+ZUtPn1Q8 zq1xA|66^7b4Tzbv`>RA4TThW^x%ulx=cXE4E(%sm-R=+@yp5HO_8*U@80t7%j^G9# z1$x(-{|4B*!O?LywbE^4J_L6t6Ri>+H1zCScgE8p=E6(MARD3}5~(IIdAq7FtO^Y) zq6T1xVjvZB0R7S$mp;-W6zf|{Oc1sL^XHYjFFxBJQ;uupoakB+W>ND-R6f3dolR_ z6KgfxfxtEp#uN;7%-!AHTZKzsLhl?m;KFEI6QaCdMQ#K>X>X>?OAx{f-V*aI?%Yon z>p%1ncLCIRFNR}vbv3PgC*Y-lm(jBI5qNPZ?5%bn{4+th8zN**Kl)G$%qXBH=z=~O;5jWT zWwq$wK;x8&0-?CO(}u_P|K|NNXt#WahS-({r-?okXrDPRPJ#ROX`{{~E&t^c_3!Z{ zX(_YJR!CEW>hf_5 zt-WJ9=?h{ciwXYfQ8%XNEWa~lSuM5hpVGI$DK8e9TGl8lypWeCvQ?-OYu)A~Zt!1Y zo_qb{5+-OZQ4H2-7t!kB)-PiMxZ>W{XS*o8cYHb-RuR$N4P&4b@I9X2rJ@R@CLc9+ zvHI3yQJfjTrb84Kf%9GI31R1M+e1W6bU~(aIT%rybQ=ErTCyQGSc^NYfx|=wP?5rLVELh;#XHZ%3B~ z3ij-FX-(ET;A=25+skL?TTGw%5n~>{>Q|@^u&(FS;NTbWpF|z##2@kVCFulv zY#y31Y943a5`|-Pm=+SO-HAthnwqg$PEnnV+;TCam}J?5BIBLZ{d!jsw%nQ;IjQmD z>++mt{-J>`)NDPmm~q=*PG=pDdHfBi42&>}1cS%UA?D9)w|5uH*m5vN1k5)E4Iys~ zD${KSzAP+^xI4xcFo8(G$2Q|d(E5jI*mTt~hC(ck3j4S4Cn>Wn7Lu@fC{+V6o!q({ zA(vjc=hDGb&nfWgjAI1ok{M9H_k+TlkouGatSqk zI|K|J&_Cr_huSTYA>3$=K9AfGdY?(RbJ%jSOqXepF>65AdB5@TaQWWG z7s{w7(`%Bz`SGN*JECYt;93ly^%~udfOcxA*6f3yb||g9T&zC}s<^pUs7RfiIvb&U zTs))v_zzKCPPJ0N1@XxDWo31Vr_N>5o$F9B^;bB}>&C_HbLG&$?q$;ZT8W^N-QGV% zXxmp%-5}=aoxu`m#m=5>m%1Q^@ugzKhIr!eqd?0sEVj`-)|D)V{u>XSc4)U4JuR>i z$l{`kGb7e^JRLO6jYlrl`5`tzygkTiZ9(VCJ5Su6opop+FXJ`_dm< zCsNVTEN%Q~XVOqep=tq^uNZ&vO|&U#eO2{@nFfDf@}O^1$TJOhuaFPpET#BUm3fKB zm7kMS2DR$t-GkLQC;*0de+lM)9;S-)|hkJkVf z87M^S+mul{=H`g~{QNA1mx;Uf_nAT8Zus~aK+hmo$O3k~`4A!7&-=4`k#FGUIv3hF zMR0~8fSFY1A3l0PC}cnfgv{D58WQ=uEuFbFI~p8B`*K(RW#~HkhcM6o)dF1eLl^Lj z-2#Z|0hYkGqUE5i&jz@`-a5OQ8Bkyl2f8#bP2QU75^4-$TxzSF?*2NqH2I~j;0OqY z7!s}6zQBw(SvFZ6!WqbcKB|-VcgopkgI`Hm*>3I=D3F(dMbQ}qT{weuTFBSvO9eQb zAWhMcoPo00*-#6m-PtbC=4p9@3Gy3#j(`Nq2{0(zg$4{EI_HXi6s4KFXv`Fx?pGaE z*hVTjRvbU z5u5}gX;kUaUMF<<8M^70EgtC&=_YSzH(nCe{+GQplUEu%?Hbf+qcp46+l^CXC$~;vy)1KKnoN%PAV5|xC|dPlzXQMV z__2ti`5`vIF;6phX{L@R4##u_4OIDOX?K*(&ez<*4Q`=vBVSbt@l|bupJb*%9*{1H@nPS|^s>?4g858!gh7~^HpAZ4*d>tPl*KXIf~35b{L%NMK+aIy=xI45Sp(R;BlRGrqa6NDaq-1{QF z(rGcsGQniE!n&sS@#7kPQaYbc0{h~yd&XJV@_FGLfNJO-S%Sf@OsnBLqJ!+8-G947 z@S@&ZMw^o$W0Gg-uz-66)PRul)WX%(Rk%Q}^sKJF^$3;q)A6MTgmLgXdjAgo_HWOy zh4bfx4yNoK$aH#pP%ir3^MA((Y#%^xM|tjj>`nm@%Nu}C_9*~D53&DDgHo=NzzPGx z+5)q=Mrc3)VjBnmJOxQw*23qX?d>C>V5*k0gmNflQ%v;LqbP`~nHl8-lv`*f4CZzo zNJvN^kq>x9A)Brv7>nQ_bToa2IBWkR9^B7pq0p&DagNNiv`ye?TN!%F3S=R>z{Qp`5VgwdP$Y z;c1qe&BsPS$I@n0LefG;n>wJlOo=kL?zE4ZvGE=8vi*QiPF<-8>uD;`!3k!e)3>9^ zd9BbR?o!@0@e2)6AL;08ReFv#&4n!y30gdXFKdx%WbVhWdzW&oL|?4Fb@fF#U-Z-P z*D2O&^t$T1)CUa$c2#y|OSc+_`09s{JISE^~LVK%|T^}DBA>9L5GL(f$M<~C# zQlt3caM%xDqn(7!SS7Xw^rX-6_yp&4QP&9e%1S2COv&G^%8=M=t`!mz8gb0^syRNx zAA~nkJQu2}5TgmH;0gdn$LBJIys(dho#Qm!@l_EnBukmrUEWa26?Qg`bqp6 z-Rj{nxG+|KUs`4P^{rtSMk1ZWp<`D^!w7gS~UK7dS$DPB6UZrI)wBQV5wil zQ*bypwQs(kD>=o$J9&^Vr5L;dOMb*c?29O0UpEo{99BJgr`Mf?j40@>fr6UT)`7>?uV3vWiD2 z#TZtRn@G>z6b#3lnfLC%)KeU)*-3Kn55Ti@*;P++;iIYT(iS9S&Uy{ay^ZHSZ^Cr zCj8x+IeyO8RXpwBOEoIz9$1lQ)L^*T>D&ux0O)0zZ=8D4EE5WEm%M8}9pVu@$b8+uytSS`8|Ae;>kMi;`3xmS|NZkb6FM_f zHno@h^`4J`@jxzg4mR!H)|rEN7+$7 z%5KM?y}v-&cJU*H=a+k$%|AbfI{!lt=wMbEFg7XaoN`Mx5zl(veI^mLZIi?^&hPq^ z{UoF_dW5F<7rB@J^gJTZ@x2j7GbeKG?+F@B-gJ$`m1}>miAUn`ne=?Fe2$-iv3LnC&IQ&cbVLp zI(5ne^?Pi*{XA55JSjZNoH82%xO@Cl%;r@}G2NVr6>_oh8b$2)$l^~;c_xVEBm|3J zWNGBtX_Ar~c{vgH#Ym+SI=<*tB~U4dP7Gk-@2`?}pUc&GPIV~7a=%GieO^rrBPOTF zBfhp>6o}Y$-D71jUXN#qj5bWpwp-+wMice4qErkU`fhNvo~r|?YM?kle}c=(KpcK2?n-{I9>G{ z!cLv*ai*TlWgsw-ED6fEZAr`VoZm%`+1EI*B=KnHg}|AbD#_s1$}K1oFR^1gXgkUi zN0V}V&dkBr`o8yzo!fKe!OagI{r8-YTO^w51G6TZhrZVcF;ND0Z(Rs!4;8yn^7-Mp z7WV<=gHxtCi7|0byvKj&t@ibbv9x4$x`~&Htx|oC|JXp#qLP7S#xtW23h#r`@v_)w z*xA^e?vCo6!I%lIqN!;RAU{5WXmx-(MRjQQ>s{Cs0X291+R|vighFYnF}>pg1H+?6>X2Arczq0jdEaz z6ZySw6lH@>qL?{}bxQW@m6?3)vb7twvLmVpst}1Peklu*43%+(wd<#bmEjj?pm@?1 z;0$}t{6j;74T(R2y4E1I=$N?YMI)7G-Vezf$?a{+(`Sfqqvj57U&l*RarCOaRtz`q zsj21V!@FmF5mJ4lyGwaPtTnj;bFkfdvHvuE%NdS1pc^8UNnyGc#rIWl_!c~E)VDMG7XU$%VrV&nUZpZdI=#8 z7j-B(9J>TJRdVIGpVw5=A*d=xZqbi7QIE2;2tIhLn3u!b%^vMpKUKaw;0!jiNvWD= za`l(RQ=@quYCrcJYsZk0Vx|qHav{h@&RvcUI9?L}!K-3yL7MD!6+vk_s`TXU(`)zn zp6bIC=2%6Bbp^>vXZp|_J4*Wm4XN>M$!SZjSFf6nYBfT)w#);&*0_Lz}i5px3^TCjGal0b>16di$1V`5U0&+uVys(lmc==t>`*l3lKc8qp&phIzT5OU9M z_zMr|DO7+#YoBG(MMrW-uW$lQ*D+`MOe*Kj`@vYc{r>)b()*#0a(Nlxi6CU@vi9-4 zZAOF0e$$Ao$QjPxRjj{XL56|zL4)1mT;1^C;NVOpNPpz}d87On5JvyCTcfurqRK=D zE;vwZL87_idN(Sl$NomFImi(QLfle_eFSFW;1`}aW6TkS_1Mv!D^2FNLcoyW6_-;ZOW|>I65gMC_5xz3-A*RvINcimti_|MrWzmaivcs|se%{iM>v** zZ}^>U0Aq`U8|_=;CdTNolTW=ALBv8W*(3P56dVk+K70 z#iu0jpP2)aHT^GPeje$*_LUzj7{u!pKiCma25dJNEm{rG_Shu2@G6^Ls^i)R6ELUA z;AwWc6)Dxv=QUT!a5#`~yLcIxZc3y3MN9EY*Tv`ak>(hWA7F8?#z}Gc(7OyybHaHd zWcaNd;0f@;1;qQtTYQcFDs~Hdh~UlLdRg-O>#0Ua@{R6=Q=k-G)ayZ*2EBrG7Bvq^ z%z&O*EYgFFpK*~ytv1c;{y4J6>nOIkU5tJyUyBuswYi6qecTo2fkqJ$SpR!cd6Fu)L!x01^v?<~vFcv+*>f-9(oZNioUZUhHOX2e$z!!=Xa_ z{SEPSt)!VHCbikV{LiH9G1|g!K8-d43JcTJMvP? zA3JZ-8k17w*H+TI5diAVFD)-ED|6cZm7MAJONWIp?BUR?dft-2%<%2ojSb32exRQ? zm;);r0NqS&ygwT%(k=!lUvN5mq0=d{p_63bN&<04|1F5^>X&)}BuY{xQ>2v@o|2cl z=|kfdAw4}kH0qGg_x}55yxH|=efG=4Y;szf89({iS<=t6m4~I3r5_k8p!$O(X;7XA z__}c}-unyDx1hC8Yodk;F%tNQVET8ao4CS*?ss~6TKXJcHi}|vzqs52q{u<5=7p;) zb7N!Uw?BP!4vCaICmQ!pR3Z&Il$kO+dDab%D|HTwdOB_`t;g&uPfi@YFZ`OX*9<;6 zugApI+S`&)oM2*`6CNr-@p%*dz2ZkO z)-5%|!Jw5E_B+8XDP^A!n1_j4I4);!4sH-AOyg=Z`|Nbx_EHy82ugCC>L& z^pz`@=U?O4eA48<*or|2MpCI5crWppgLnBBSn52m{lkZ+z8iQv)nJZI9O#fl28YTA z=Mv@iX^b(<3@+eFHVzZEvDoe_v0$FK`1b^ce|u-07L(d~Qw}(6|2XWk?YW>W?p4>g zh;FyOGcQCL2tSfmwNRJ9c4srJA2#|JbKBLYK62Id=2Q z(24UETN^R=bG|qCKNaZF4V|n4-{=dgBkWIXs|xK9li$BLy^auQAh&<7OkV^hF}2;!P!K| zM}f^?W_EVKjBE4!rckJlN4cP|P{8Y&qe#o5+?*;hS-QUG&wMZuG{p zk0f;vZ(^srlR4rRMYDi$^973XxRncu3(_2X=9*Qt_<`F?A0~WsyL+|15Emgn6Ia`m zy&F!a9v%fhmBPNWf!ErqwT`cR=PPwJ$|U44*x#?^(+RJQFI(ke#Qsu#`%V1oq|JIX ztn?s0zCE}-juf7%$}Y{-&*jHpnE|)Z+##;3E!=3IU9J2sk^p-aa0oZWz{uI6e?FcNAg+jv8 zA0LH^Y%n#DPC0f)2csyXx` z2%?c;P{l22{_Y#XDBskI#BlsbcvT^5z3-)Q17Z&yJq?h^EO$%U$E?{nDh?X{M$3tB zqQUWryZ;ffU~BT7A1cdg^32d``^vMfw?CRdkLYRfqGj#J=U+2u{rqtvu9(&-S9wqF zB(a3MdwY?#oPfT%Yb{z80QoGR7lWuJ0BlZ&bPtPyyrdCO1K$p`oZw!VuVZP2LUN!# z2}p^;i@il!%y09pym7&c99r;ufw9)6tmrLHMI&Y=SS*2S;ma0yf{%6KpGGC!-<-~Z zyKVz&^y11c<9Ny1mSb zB~XBh2#o8YfqD0z&k&r}>)?LeN~(Nz(Zf!6rmmJLl-i?}!mq>V?bUfYCzO z$r~sQq4c@E0uywCAdYO1N#%7*>E7=qwnvcW+zDll095v$Q$VpSR#H+DvTg(NrDmX* zl8>+~EGY1{e}!yPnTZ6;(o;H5dGW{L^e<`RO()tdCyxJ!j#BIrgt$QZHiO zbup*uY5Y)o%>>{U6z`_?7VUKYs&^MX3%vmj?8Lq4mNdwnh{lWQ(&1Qi*hVC-fkoL)_i*2 zxvonWRm_MHEv^)T9IqdHYW)WrZpHLrJMc1$VcKMhe4}m;zvsS7gXL+LK4SFMss|CfuhmFFYeEh-)|%(B89mwoFjW8bJERTh0QA6 z?yONWyYO>%k^cL8Os4?+!RMSd<&y?q;z#y#8|=l#r#UpuOMY1ln=9K`HH8?{k5fEL zL2mP#qH#^XDZ*?HwOG8Z35M+1rMnsc@`eE4%R~Q1v z4cOeSfph`xH~Nl5Q=;l3GDdU)&FJWTZS zS{g!_gX%2fsx@Qh6eI*DMR{N3wp%>eo+{FWwppGU77sug2pkljRh+}2)7SX&<;&Wm zkJa-K!gvRa5P@4FunPw8#b2&UToaC#nvtT z7V3Im7f&-xoBV`El<6xs&mj+!(j)|F4&-ZDv*zy4Ebb$#G5qpy>9wz!xu92n_aFiZ zz^?(7J+-hD@6iie8mBLcatAu8H)BB}-D_Pz(9(Lo(i9n_7S-0i1h%Cs24RO$GcIyr z51x^-s0WE?4YgnN4OU+w-U)Kaf&gI_X-}{tw!Gxy16A+ldjI4kvCG1LUuOR_UjBRx zLsk*`4&_~ZyL-KmswU=Z&#K#LgSf*UVR zh48trfX{(3kFHjMR5Iz?0L%2eyi)>?;qHX>M{Aasx}w#QqNHm5dRk|Mxn-jjKULhp zT_cffZ0WD&t0CeSPrA$@Rr*n#46{?a!8O=H2rYrD?bw80(w8HLNCq8=?Wh)W*Vj0oyxcws6Ap{T7i7g3yxO~b2k6M~ z`jpi3RLSqT5=Uq-;JcKJhzV2du>+o#nc~@k!#|Y{kRjLMA_nBId7notd#coj2xAh z>@n@9XL!={Hx#zcO-t&HwD#Gca@nlD^S}udbgzrvugNhSynKW}XfUm#{EEe*-Q# zP|ly`IlTglYa@Gm`vVGfytuHhg--;+6z;{C?ZeM?nX2P^gc z0%VQ?0`@JtRvqw~v4E~QM=;xem@2=i2IkpDAh(6SGEapjdECL`p%;h+*Ee(L&JF3! zoyOZp*+qqhekVJ%(7YlH6J`JvBNGbM2|Q^jJp&P?d9G+TCJh`f{H25(b}C#>71TVzDr_OoT zkbD)rWQ^S5;Cx5(Mwuqh?eJ%?SU~7_fByVoW!gTi(Kk=Fe4h%_-81t5A<_%-`Z2wm1H*H*>&QG##BVQRE zLZ&RZ<*co==tEhOxGogw@+{U~zCn@2EMkIB<_<0imWv9mLCHr@kk8{8`-PsoPM+|b zh@^A#|zc^s_9ICFNkd6&Sz;tuh3 zk=DPO6V#FF+Hcd z*&im@Pe(qroy*VfLw_%50}YH&$8oMs4<*8XvmP$XzdY1^tX?@jhh`S{lVI$xc~vhk z%cGpDUChbH*SEjFuY0WeWN?cM`d!zpD|f9s|Mk%m-nlnftstAI{HtUIyI-wBevHm z)qnXpEpxVKP*<_GKn>JTl$arxCt@wjLgL~Yt}<&cSwaGEp|lD41xV}{}!WND9Z z1PEYx-2`ZTl{gyFxY5|Y!}-$dxhJntiwxq zcXykl!o+g2Nsugxlq~EqVTgVKniok2d9FvaRkAMWF#FvxvP%-7|N7pDAS>>`Xc3Hq zcN$z$Kl3K??(!o0$Iu?46WiNn-NGxe)6((8(`QF#^Z)eQI|p5x%N~X26VI`g!Lg{E zVPy6UjkzY7?}|#wG`VDRZ9(y&>;KW_JNanv4jg6((0@9nO|K1Z;q|jmSAU;wZ28=B ztjCeYSIu_}Cq*jGSFIy!Hv9EE8Uq$Q6o5M!dyeD5wqKdq3g`93zf4GjNnW^WJfwe% zc@>>Fojiw5ERR}C13SgHKYF(az39~XM>8f@?J>%Rv*$oOAh8$mt37H`At-6D2ewr1 zFu)K%YklAI?j8}Sy72)09Sc~Ui?@Fx66v>t{LNA5`}0r#Rk8+ih>AYOQ?AAh&_eoB zkaR)`Oh(UuM}nwOB|T@}mWwnZI49VQOFmo82q--zgD_8jylD*u$u}rNRT)kh(>4jk zWlc73vs%>{g|;s9TNOE@#qdNxo;9GD8@VYpzp}8KAhmxQp0fKd@_6Asl z{re>)CAKeyq80Li%VV+kCRg;9hLDg@M^_gB%s7bA>t+NEW|{EOlvGrlu1}1Yfu7t6 z#O;b&v;7+m-fuG8?7#UrxHnk{e(>ULVR%&3hvIjSwxEfF6c~1|T(3{o3iW@2E3FZ{ zPps+}7d_^#+eVEzfEdsA)w|h`kdn|YVxxMV1?*Zz`56pmK>_zHlc(IK_O|3_d0%qD zz{^>ENx}5(xk}SC!H=P!1O(0$zm6xP=XIrPz(>9s`l4(VoMvG#e+>PE-scSqPgwse z2QJ!2Hq04OA2*h$83kI{7f=uIPO(8x;1lvak;MEg0sM=MTlwjw^9hNOJN_AS!y&ft+= zxUxxlE*Gz-9`iXVDr1KGtJ1!ka|qm9e#D8GZCzI85e~UwlrrCIA~U8@I={9p=6q9) zW5k!g^tkqWN}BreFyVLuRjmn0A`8ZmM}8+PJ z)AY^c0ffv=txqp&!JuGfm(>m%L!YN;?ZVS7cesQ&KXtc2n%P)=q0z7L1)KSfbkIEi zWY*&Dn22*AI#mL-2HHD`ENg^B@oyDl`GE!aJ!YYUZ35fn{GC%}&&@QElJf%9M7(#@ z1CQtqRlw2g`>5Zdh9f12f>E@W#ruK!HU3&7X2ce^nUgzL)DnlR_*XQEc(|gc8n|v0 z0FEhF7;PQ5?UdfXk`@-Dfa}5L?d)IfB?14dl00Dk{F{Im$t%p~*=niuF#|b!GURzt zJ%+UCU8^7*!Wf9=z--E@ctAg2V-3iz1tuWqOu?F4cq0u2I@o>iT#WO*R6T^9*vc^_ zgTKnG_tC5yXyW9m=gmHTytMYa1WG}m_1M{B^MN)8J>H4y3CDf5h$!(A(jtvDX2-wL z{@lw|%m8q5z%lY%ou6GZg0URFU7M_ePuT%+AS!dG>vNBi~KoRXtGJb|BH$Qjh)$L{#LDd$H&rw#8NQ!Uv z@gxBpKJ7;gW!q)^JB?Lov^PvV)Ggj&HO8E6uVmX2EjIF055$RtBJ%8`aeWcs4CJ(! zLk!u(8>Q69Ouvn;)AAhJX9fnJEMi<}hW=pV#6?Qh2>EZ5HjGR;W$EeBRdkGSmf?p9 z>zdv2X~$Vouzd@smXP?5Y^yczRJ+LL<>q- zf0Yutio#FDV!vG?yv&!*d-5Vdya**iJaZ)lrcuEaU{A8N3F%&jyPjhqdn6u(ML`OlU(2kby z2WxB}Mk)h2&0&Ut)X@0Qu~PinX9XNDOwHa)hil<}+Ejn1U)ZeGw->?jWG}_7PW8*C z8Y9`N2dQW!0le9C(aB~c0gry6_TnrMxQ z^TtrdIP+vQtaim{5ml%|+DtPBUPP^vkt#O_?JV-}Qsl4ft>^Rb3Xv7J`TVjNn5G}F zbjk~((`XcOZSI>e!J{!9KUe@>_3L5G1`1>1wPKW4C!FWH7MRbCR`QcLL`N7_+_ zpXBNnX`J+b6yX~ds^aUpW#o+i<|gG=nsri&c*CguY_k}#M4yns|8kmcBuz&$98Qmc zvRAk|&~gzy-)IbF{3Yc(#CZB@|Bfex^Lc6|vGSIuL6TfjwCE8$Hr2F|Wij9J$9@oW zn&8C9uUqvwj+SHxgc_|*es1v7;|@*{v3`@oRGGY%E}!!z?0Y4%cVnOd)7bGJ{^~ZF z#oueV*gvp^lceI&!c&BKXAWqSv>oxok>CfnsF&m_9qwswBm%{qpZ{Ez5MX0Qb3~Av zq)ix5W8R#vexGskaL36F1jaZ^n$LKMMvU0YInce}*xRenYm`F2uk>+YOyCjpV*XN3 zD^W|$FskBJVNPzJBKRKMP6ES--x?|g)S-K5)ZJ|e4rm+VM(uHt^VvBN9i^{D1$+SH5RCm@_Z(gFByC&RLA<=YV5;6cJbRw%DcFpeg-nZp_es zQwRscBBdiJqtC?U{Ns0hnK3sX*>lm0O)YvK0 z8dL@zV)-17_TN|`UgB*W($sIkOQLTKPH>o_G%|8ShA|(H+0Uh}doEIbP}5vWB6s$A zMctIqrPlL$63#?68e~ju{Om2IGz4@E%1=Dq94vudPfU$ATxL&&+W+7vx(3JPTr35Aq8k_Z=^3H_#j$4R6{mdQq_f*LP#`_rI zCS>%Jqy#wt+vfZ|vs4iZf>exHQLvm36~d@E_WGqKV;?M8MSZz7?BYKaObVg)<)k+M zg|>&hu>4Z0&-z#NR}wKQh4tQ<$bKCH8Okh#o@pEW*KI#9n{-$*y5_r0Dk&|AkrK^e z{$fnEr5#o*gsW*D6=Zhp0r+(K8R<^ zRLd4F$tt9q6v+viR(+U7=<*4&=GjI6EcA}bKeEjFTY-;-95!$;V{6dFER;+i+~I^p z%?LQ2@$^v|iU-pYrPW8-f08SomXZ-{{`9ULc*)g|OC0vagVaC32SsNb#ExvvzceuQ zunb7|w8^VN0-@ZxHe>orSq2|gT>?==r6)>aene&m@TyaUZqO@#X!m$8w<$0948w_x z_qUZ)J)eXk9ds313ey41^1SmyL=pdR-m^5e<);1{d zkVi*HbGS4ODK{x9=E0Gz1?hs~ z=V`vP++`7+`Km)5ow_qPEG8^Lh2xK=hK3+#U_u+0=S+u|fEsR=$PpeKPptt*fU1SR zwn&qfq5L_&i zC_KvveZmZ0`zi2I>gD3^w-AQ&?{+^C?ncS*kQt<0QYgqPcn%bK`=W zK1hpq`1zkSiAfFOz>u<`zLdbgD059od?uN?;R%m0ndXQCbgNIE2r<;=f%nH)zfDWN z8I{D-Sp)Ss+oz=)c$G}=X!UxP(ln}M74DaooUizXmf=BDLT|V_q4Qx<$9_!5CU%tU z*KmTdWn}L}uzIly^E=7W1l|8KeKd|x??O_BhCDts?-6gxa$sy2;dH7l9fWj zOF}w#xC%QJc~DNa@g6Mlm6#1-Vm{2@%XSAL3%_Zq|4lEG>geQgje54<9LwpWPO^tj z^m?V#Z6Eg@-Gp592odA7ML$s=2vJ)3a|#CC2w*Sa0b4fe&sxrzJsjIxq#b;HW#Glx z%-#^azsVD5-QzPf_e`%;dl7Ahot>SV91}Fxdg)?PNt}8b=-RB@YKY7mr@=BL*jF72{@fgU3Xych-&3m3y8`@O zyh{<2JhPFLb{WQFc4PK@R<+3AZClw2+K4}A<2Mm9(O1~bEW{tEXZ&nVBQ zT+wA^ZCO^OV)-b?okFJ2r@2XK%4UrOX(<6|V3RgkBV*qsP(^n273_UjF)c1qx<`6T zf>;4}!!Vondjdt25~>_be#T!WfwpXt;|l-7)LTbI`F&yEk^<5UDb0`~F?2T!Ev2A< z(%m6t&^^E)-8G~j9ZE=-qzH(BbT^2Ee%~`b&u=~NTJnd>fu){vpL?IZuj_LmeS$tc zzTa$a_iidfTtLn7lVXk2S~G5XgaS`aKMC89i5@R8%_VDcsy04BMJ5IYrRGP$N^fjZ z{$5M&=#!_^$!9VvP+)3@pmyLr&>Stj`P#JWYuxtu=|Q{+(UG5A1)@w-co>kWqhnt2<}o;tfq!274C2rSYa! z@U^%xQ{c+?&Np(crUB|AGE(`Wwmo&FDiH~>_DJMLE-X?g!P3TI|s zUa2V`+Cb1R*74b1m^DQsXV0O}lHajtG72qFxw!DT19Y15qFFNkZ_jvtFz3e6Ad8Sa zEYs|~;(C8U;k{eB-Slmz;k);O(kJGwI^;G=2NK~e`3h66yN>)_B`v{*2gfF{rA@y_ z`p<&3y((v6e5LRhRzF_zN<(E*Rlkk|tB?82DO!o@?2{!Ci7e(nEneRJx`3rPizU|u z3DJ=KJZhXF^N}NcNl?dvHx{)w$CkCJn&;~DHb(y)5BsQcCbO}%xcheOTf-N6L+l@r zN~)Da-tBJ_aapGl$#oRW?68&Y=QYym5Xs4byqmrl>=_=wXU(Yu3=PV z$XKwG6&%3dbr~c*Yc9gFL02&r_K)OTY(>tbt2aQ{Ps^HZW4UAvCV3;ND zv5IXsmc5et%ys3->y0O47Y&xR)DKG_4<0=D@%rX~tAr~>1I#&Xj#O~U__m8L8Lzh8lxqKN)?Vbg1pz{UPs4>RXkavP$EHk+0^ATU$S@_3!I{>+ zc*4|g`o}zx)F{87fA1Q1{(08YL4p?+!WHBGie$mp!;ED4l1z~~oH$h0bTDmEN>jrbVO0S9(I;FZBWwI^aZbf)6lty7Py=)2I zBe5ruY3NXyDnk;oM&u9&<4q8-qwF}iZ4Kbd1+6V{3ojETjo0uA{NwYtNE@ARUGIHY z|KT0u+pggDUgzt5B&p<;R;p=jlpbIHE!onbDo;3&NGX}lvb#H)&ErR~*#AiY_t#PF@X-p+@KiMn&)T=9rm=azTwo%n_ zS952=rX(rOxfH`w&HF88_h0qPZ_`CsSkiH1Lh=@seo--#X-DhW=Lf0fv`% z+}8)me1T}f=unUJ`JvgvO8@YOiu1}q$(^uNnhO8Eu>iV z@rL_^x4!6le*UZOJDy;`jfzξtIFJbXJj(bpui-w`SohbNt*(D~VZu1GY8BW0%c zL{H)EGA(nKlDGCi)q45<@_246U$NmAgXbps9t+Jh4@D*n-x_^@Bkq@dvgT?dd;;j) z4%RAadxYvF47@Dr#nW-|X+zowC2mc-w;8Jc(*k%-uT|) zMj1w(O8Erq@1ajaq71UJ6~%b{iir58UP&L6!9XHjN>;eF6bHZ51=PJt4z_9xR$PzYyf z_jcK=UqNwb+7OVC_zj=OOeWSrm%JH4j7nmpJWxVu%$LgB2%0D5>?43s$vvjdQn@~VXxuak#lU3o2tq2jgkkp_m>m6bVolp{dYB*_mZVC z=Of%k?4@3B#(6DuWo1oACR(o@1fX2D78b#1nx{2T#{rT-&R#iq&+%w*18ol(dTLKa zO^tze1p>-*3%*idKK(H_qK#{QKv|e@kk42#93?n97>iL$}Ql3C>opT{P5oQ1xq2!?uGAt$5&yj>XI8zDba1y@?2;ACk92auV zWpn!eE|%`&1xqUBPk)TuEsBWAzM1owxUewZ5oUGeTIM)bX@2H7O9GSRl2*F3_gY@J z6A&Q-94PB`sBBSipS!T-M6*XW>Ffomc@&u=S4Rl>13y>gk1LOOhTpMM5=DRIVoiRa zpUYpU{cTVik<9%BBsMBIMNKojct%`{7kxvn_nkR!dQyYq?;&2BQk*x!l%}BnCtK1N z+ww13$(cDXNCW+TMGZDaQ-*R02u^VeYbz;}=|H9@jn+M*8&E)AE)Zj)%*z(fD?QsU z`6l;;Q`*-F4oYlz?H%>*M@IVdkojny@1OnGQ&fsQGd@qCjNGPOE(Nud=Ucf?uXty! zBy6RWZf*1OWtfSBy1636RXt3#7J9yl1T13w@pAgzDlGLL*R@g?qGs)BLa4-<^=0)& zHmmafs7rI1mM%pEW0D;OE?>cs{C03u^gB{Yt_0oH0ODY~)-V5qNQFZ?V!>SG z6ztO6v#oKf1yOX+cX~#~3iX>4YW@xqbtw6Gj818f+kd~@&HynN%l&j+-Tb2B3H#P~ z@0ntqJdX$W$Lrn7e}9LQ{`>!p7}q(Aj_mLAqDP!)l`1g#*f=@uN$AZzhuHw`$iyXW zlkd*Hj6$hLrnz0HLa9>o!T_Tr7c#;Dl?26KI6V#}otfa89X1@`jY$)M56?j_~Zx#na#4q8w#o%YDnFh!OWO^9KoH3Yka9;p7z+g$|N26$M=6 zdh`Z^r4qjGF;0AWb`G!Ov^4r_T_g`M{w(1Q_~M65H5*7v}F4UqH-B>p!+D?HhlMF)_8~9ane^5jIkR5lPQ-P7v|L zYHB4Uuvjxizx~!q)MhtcXiVk(k)|n@2Rb2K*bwKKo_;0WTJBNzAa<}mc@Cx8yimI2 zT-#a;h>%53831N5QKuBXQK$9r;m@OnIj`KVI%fzAOBi;p?u30Xsz8cyaptUr7OMch zUgt0zNlbo?(MCA$iT`m145sU^Cn&TSv+qhU6Pm7ag^4RFGvh1pvUaJ72z|AslE*XD z#!=@uR_bPECbW_su$s6(>F8~LD6;eNCOw1RAa;b8L1JumrO1#21-F3>#vmaV(Y*#b zxza-bd?qV<983cAP*;Fy7(*HY1SC0zl{0@3X>il2u$GpjKTLq^bX>0cDh4QyYmL{@ z)g;hLs_&%1rPazShJgmm^|155*Z)`=zkdA&8pg0S@!Ki>KjbKf!RJ z6b<&*yQQyV!1)}wbjD~p`-;lo^~*Fv6Q&l?oG)kIbd@bh;d?{E_xXNJpq_HS$aDyh ziM6eaw8)Ipj?-hPK@J8W!7<6&ytluzACzz8yi=>)Oh6dIMSsHc_$r z`-k3mJ+Va|^dmiV*IMKB7FWF%PjepbI_dtr{O+Ai+>;bm%!Oydktz&J;SqYmt8ZRK z?l{3jXz%)M-pr-&9MZ2(sb!-21ghUC9Kch^fZZU8^$8EA5H@oey+~G`6q>1#tl?j# zptXeWKIZmldD_0ADFe7Bzl?vFW;))UC&JY2n>e#a#gLNMrP{7e2yWVz&dCC=)4i>e zr?2K*5jV7sZkZ7@yM&Vh%D}CMc)|gpQVZV(l6Bo1lXSs*O=e|j? zrj1F*hWYuql6hyc@J9@J>&KK&ytZR1)6J#jdC~&g&f$OkG@*Z)w5R=MKQ8rMoo%7X zgrHZlrNneiTB@73iT0WR5VN{PI$T<*<0RhgUoE@)mHXcq*|l{e)!OJ4>xuLuzO;W7 z7qrh3{1_8p27CGD@})%JFW$~yPMxW7D{yEoiv`VT>-Z}K8r)e`Q$sNz2ox%4`Qz=n z?q6#dg6HH@!JZ@^nKLCvtmzen17D5M_ldvh_QGO zQmY`Y!m-z)E5BaJYK^5W(9S(V8@C-}?>>iLp3sE#d@&Nt9os36l9+ zk@J-aiDOh`iv9Q43XPc|MCvm%gt*ezgGF(?cN338(+!*CYxVnuwY|;M-lsltqAXU8 zojVG}W|mKi#(~GYaBdpCol(nZxy3F&!GiB#*78p8d+)UQtp2@IIc+OWchVTh_>+@^ zV}dY49Ge#3WKtd(oXAD4>~ZJy9o_fq2}A%L!%6j%&0p20pzw&@@t#@e8 z#8^VB$@mu0dakaQ2M^*@M{=c&+>RaH5?j!qo%(BSe0hKN?ON9mQhp=Pmb%ApN5|cP z@6p;s6vUhzQidI#jVM{>mu7(z$pBFK0pq>3&uMfBUdhRcw-NObi?{HFgP((9DkcNmO zfM@v!;E&$|K#~Nw+%YMTGOLq=4gLJj%=3*j0IWzZls)9;RP?Mr(%f-u2dqy|8 z5d3;oV=s!&NYx0R-uK?C^xoT|@ow5_%4~SbU^>E?GKL&0^XnM+)i0{IEhJ~6JWIK+ z#wS3dLW7ES-5!hy<5h=~Gh1Q{T0mB>$QI)HUcSD%?|t*IDa(v^KyB8!4J+2Nzc@W5 z`q!_PKmXkXN*+j#m8q+e4AH?d3+q};Z8runHd7rT1l&;UFN=%^0e34G)RL5hwF@MZ z>_`#rxGwv8h|}M^TVpb+%`%G9?5uLkhyG<)!4;XsL|8%y_3)6OaxLEc&U#H=R$*urZdE&^ZLYh#bmKub$h>*peQ|3I!pKAqe1D6yg9Hf`l#%&z1W=MfK=)}UdqztakBh$21H3Ev#bn{@n~HUp z_z{pyEYWZz!Gqqcii6okU32rme7zm$HtCLAfAz_^y7K=YbT0Xe?WKeZ*t7~D+~NNm zr2zSbrceY0OgEq@FaPMt{{9&N@Cw9nf`nF`YaHa`4?O6n4}9n6=T~m8&b%daN;^|^ zN;3csrfI=-P1`NN;53*2&%Wnje5GAmEyfabA28Bi`%Txl-C@KXF81U4y_l7vc6VTt5YD1-Rby&;uBbTs{{w z=g>NY)+{+`isO18l2P=aIF&jI8m`mc<8Ez%sxS8PhiG#ka8Tt!LQ>;MuZ(x@9kcrb651}Q(;V48%c?_Lj2fVMo@>2w3|*U6fe_ITpq6Qm z*TwiJq&tH@NDBjE%^=l1ctrF;fb=mFiGYj&`*XM+PFxTf10_C=r2=H&clAKoLQ(62 zwOi@Xgl7^Y{`)BFT?GAFSM5l8_H*XvJVmdVnirtt(MQ4no*TG)V_x05Nhf=jF@6lZ zL15cOZuvXAy4JO}wl0%VL~E*YBm*&92(bP1eL8S)TLZpTH6#8EITDI!>UTgs`uAM- zzjx!W4!v&wEdM8?D}93f{xO*8NW8ih2BpK&QB-s&kSV{|Ff%#-TpdOnGsKJcg&JjM`0! z0(5;-;2RoI;{7jiy`MRq(`{`Fk4?EcPdfP0#{Y;FnzJEFJTYaGbB`{RJkE+)KEhU*pbI(%f29z#%Nn|d&V9|DvYZnJH4x1E8}Sy;|UFp-MCuUOXor* zHeiH)V~okz$;#oNBG1~pPe@Nq8LlWfl3tKp&)_|)hL5Farc`XO?r3FAZ8t$OO7=v<81K7N zmb2TwK!Y=f-B!BjG*_kuBs{D`mm_)Ow6dl^h=x2my*1n)g+fgjg^Ls7t&*A;4H;>E zCFXnK6CnPFMT0}r)it-f8CL7Xm!CZF0$$c zv)8W^kVlx|;g89_g{(C@%^-}yE}(|({@NDVYq`>_HMBeYe1mqx9(ifa|Gc-9EEs10X*teY8{;n!5#6FEr*oz1Mks4=p}KLqk^q z5XuhB00I2kUA)&L+j{h~mmx$&H{n`Sx)}gmQ4ZEHT7qy)bfA^*ybapfxemxV+I*gz zxtCD&RnFI|oPNNxHUfMyI;7Y)4BTK3dYD~Ce&=dhbd|$$csf!+{GyaCoX znL>-A8c;Wafy$_Iro{YcYHp7uDBOGa#aFWdFG;^5v+Nh%weqtfmPYJ!xN+C7vi%}Y ze~9-v27fANUXAi?PH>a5=gzoQL>Ql(eB?`=QS~yQnWt|nw?a6pUdRlmuo^s2i_!{> zpSDZ9OO?FC+vbW)w$WNp^yQs^o<|G94A!hQaXhD|tx=pGd{S&{M#g?IKHK}~?CMN` z&61SJl^RQf(&1JA9h|V*2GL+QzaDOQxNv-7FQDKE;mR*zc z8>Jwr{N*!yJ89k#D<_w%fe!zO#d{xV>>@W%8SdTOen?BCMDHyKhU^3GIO}r`xfs(+Vd};tkKm07nd5 zP(J;=sIdbcr!QZ$aYHeBR!EmGLAPghK^)NoMD?GsNTly{q47`Eoqw;bWlz1Lpz1Uc z3bJ{nkGMWGG$_A+tZ81Pyh_eC0z-R&FW$Rtlmcd-$@AxSZf*%6P{CeUgU?s)ZlA{} z8dwQr=AP)E^aqjrTi4p8Uw{y7H&6otH@!xQzUN;pQ+;6c0Fg@%z`z$xtJUP&=g6J) zefe^JY3Xlp-en_rG-%;xp@E;@U3k!w`B9C1=*w@^Y4*rV`su^Yxwxxotpv>Df0pZ!;Romng|0Mi*azmXbg}0V|`q0-wBvN=+ zM)EyI!CFxS!Q*|)g~}Ek5K;w+z@L{_Y?jHc)|_)sB+O|kOEOD;u`)duTq%!t47kMnkpbA)DC^$!&(r=82V&s|C*XmG;3y;}mc!H^CIHn`LLQSL? z9kPOon}1x-B%@SVD7=D}D}X>v&qF3{#l81iKW>7IXQppyLRehk-n#)FYfsv^cRG;J zt@$~&cr6}nn(G#}SZ2Ja)pV{X{2(SW9Ec}wxoJdnxWx9e?7#hD4pnYbXJ%~&^i4h< zsG!cJ&&SwTRqB#i3SnfmTWpE$p>G8UCtw67MauOH?9+^ebpF>lF2CMA)Z*@^^*v#@ zt3I1y{M7pIgdj0vXGnRtif1@$W;G`}xakrm*<^qrA?TQca(=aQ50H(o>kQ8FuQL9kmMXDQf) z9xn0ZT;l{BNQUZ=IN4K#=Vx#T{%m8c-eVbowFU*7mTR;&4c-o?XpJ&5KPfBZf(6@I zTmb3hR`k9PM?WM+C1tFun}pqTw&yIU`?$O^X{t}#&PH8P4`OJfkk2y2QU^^M&m7fG zm1vS4GD`a*BxR(Kg5BgY?MmX%aD5&iS`-{BQ#ZJS$qoVYyrcf}yP|jrCxz-JMuG=- z`Y5>O3Hw?xPxqno;T}_sbe`XPNyI!<`Myo`vqq#MJ}3^eQ)tmPFDb?Q2!Bz2EHWz2 z>gcmAd(BnUr6jyt+(RQ2^N4IvF`wG=s}8-z?ygnwfCe69)tFTtSDiiOp?-PzI>ECr zV22P_gcB?*eAIF|5)cuKcP+zHCyh!^5>eJO1c{|FnB80)cuG}CeIFLsh=bl`co4J_ zmU{+w{}3+!qW$B{$s6=tiE(>bq3^6mgAj8E(LAY4 zo}1_XyI(j|o1%_d<1#-&3}7XS5vS|ILU)O4{no|L?vm(L&rEo;wc3azfh`cN%nDwH zkI*#4siRB(-z$+4UYmrV^}BEck5*pAfzSGw|Ef#-mqdiNZv*{VjyR%zxfZlNjABT^K^M$N&OA<&mk3J zu{2$j%f>+2BI`9jG|n=Nbg(Xr_knI&D-sH%v#1Q!1h!Sbg@{iyrtFgr0*l^)l2 z3tK{aK%Q;8ZnKjRy+0hO#gnC^Z&P97p2=`6bALpiOwq71#wl*Uprs ziT&iTRH+vSLq>%Kntz6-&%cSeV?_$QC!Oahz-qHVlEb=vYTpwh%2!k{jY8&X-Dd-_ zJ;GQNH1sC0NEU_RM#GRNsa(0@A?EjcPJ*&m@MhoznYb0aMGg)qyR@k8#Dgy`O}`G+ zCPmKQMHj=BJ(PK|$;tJ3k1a_|@D)t6SGL<2+g%gd7a8b226DmEQR^YtMcTGTIu}XJpd(_6JEYV$IwKRhP1cK0LxN! zag{DOB)|&;-5_TAGs)xudK+iJ6K@APW1LnV6yIgj;Ss!~{tv763$O&qH&hwq}D$^$QX1GeFu6;OXq z*JTyuz=MRcg~=Nk>Z76^=mwD?sG;?N;cRi~@e$o>0hwGyWelkW2F5^3q6M-!C8pU^ z+6PZsuT^Fr<qZN<=;AgeFJ}KqTAr`#u@9t zOWsTyfs9Iv0J4(oq2GSF`OM;-&j#wOr{oKmkaR7i5$9^;SW2pJ%v(IA$B!t(jg_(M zn4fS9bbNvzoLYe-&K7t>CiQ;+=V@i>izswuWm^ek;TG!qx=%h}e$L8hCNmIRLRsy9 zB0?|SpfxOvFOx8sz}MjinncV9E7cy1_yYz}u_o|}2O}jl1H+0GK|liO^GqEzjvnq7 zF7Yxl<%gD(8XG_TOd*Ih!Zs}IuFCgb6-zxeUDhMrs>YA3vDKqcpxERnU(+OYGnMw+ zjkAn@<`vdm36E7+^`}jZ>b74``%7&Fv?x?klaRFG{|*N9-dKIJ0><;UPEPk&u+as= zf0u92{UE8Upx2#6?BvnZTq=5K9voU%@~;U6DBI7^c68rldToszylhZjy`fSeBauG7 z^N+TLjy3|b)~o0Jqat)fvVTt!&d}2;-MrYmdwf@Q=6XZ~Ynn7yd5ZFHmtzs={{}Eubuxv?h-ye2A20Ck-jJ+gqm0#Y8-5v9xDCL=aaNVc79I zpA7C0wE?A%$RG`FiXy_)Atv>;zR5QtWG6T=%7%8thkL_|zV-Bu*FDP3)QVzF zZfCiCgQLl#b9n5XA{wg&tYfeBSfks)9!5fVi54*;Ve$w!Dplz#@uU@w`if=0MznZ| z#gV877E^mViqS;ms}^JV}`^r6gNZNXkE~vN{m|Nyj?$4D^C{()2`R=HXob@BLAO&+;41jVT=o z7Dq_DJfugbgtmf-;-!QcYm#4q5Md~&HeEj+h@!v7a%D!!4NAqq=i1GI7U)uHwO$AB z^Vk?M8VGP(#ZYg|>p870rpE=zZM6DZ=HlYwanyb}<=UJ#v!<%o`~5o|+GC1N81eh! zWZtv7%8G>k3p_>N;}#bex3tv%dzcnv!vBD0{uF!1FU}ZGxG1jLu^|iOYSdewT7^9h z)soO{5?1$c21GPWqmRZ@msxw~nbg~j-?p1YcbYC~&T(51k$X7eu3=j^$`;BTDHaa0 z@m03JH+P8k??C$G^&k)vMLj4K-;yktG^`+OkK6gsXZvN~+*s6sYUHAAo;a?-*fe#yMmt7PeNwZh|Dm4EfaPaCsF)YEmZ-Ur7}U$CzlP*mqkf^^JS! z<-A;Up(}}B;)x!Q=h_`~a~$|mE9oXZNExE^+(r?1xz7#I#!q<1hicxPBnstBsDCS|q^E{4CAM_QluvDU}NX3MM!)nfl*t8l>3ymEx?*`s~L_l35?Ca+bO^wI><6zxm!Zpfr4}LEn1qiJ+Go z`)oCko}SB+{Dqa1&F%kG9N=K-O&A0#jz%1Hu6b2fR-#!-Ab7S0uIkD`9=-Jrpf>?k z^HQq6!;?O8`S#0l(Bp*i3LbR+89F{Aw>gk~2}H>NtFX+T&7Wo`VLAY0%A0Fm`;XcD zj!pZi_YhB5K1?Du3a4Z!)LN7Bv;@}ki`ceWUh|W9msT!w-?psF&}3zonr2y53l%T@`Oo28)xJ%geju!Xq?cOlBQucb zaK+%=zEyYw|7k3a2&GoVKI!wnRM-cC^*_OV-+V(Gc=bd?DjbN$qbCh$iRr6gov@zn zRqXP2F$aEe*DP)3-2y^ob!zm)cveK(;m&$5E^+4;IgnK>YOr62$E(soDk_7pV4iIr z!3y5wR7>vxc2TY2vuUm8uig!9_@8@6a3P~Dql##Z#N?A4nzF#n_k{^#g>9njM~y~N zRgOHBRGf}IW_);wK37|WLna=!9)w~5bKK*EfkgfBAf%r9d9S#lZb|xc@ve<0zH>`I zY!*#8^Tq{5&Dfre1y_Ke$%+C&QHi1M0vlh^CVTIj-W^Dr19K%zRkhol=-ppZy9uka zp|iPiaH}eM#OvW_lS|$H`zc@Nt|Ju*U-AP;BJztB#sA(Uy$N%mhw=Bhs9OUsI+iH? z{riWTTU(dhCZGg`c4W=W82vpw`g>?1V_Q1Cf(G%3)c6wtJLdRqEyc|ml7Fu=2dZu# z@p*mfr8&OV)+ruKlp>SUoaNjSsy;A6=T(ZrOKKQj0m^yZkWeJN3>av^A~Aktl$Ng3NTyB$FaC&$Aury>2#qDRA8h=-36L&(Yz zgZ-L@beKF7S`c7y*2|o~!e1{-z!URW zyz?N2*)4IB$aJ!_y*W0u1}SR5#T^<`kv!v#>j6(l6fZ?`rx%M5nSIGmtsFIf{qDA# zu#E1TfV?7ximHK;Mhaa_bv>Aof8V8R&sB*UouCt>kN*(yYIRTzPeC*bOQmq8%3v@} zKr2}wrdCb#eLyJKeH?jqELn=ll%RF}((Lq#HIjs(LWqEJ+6unvkQ;Dc(1kcFt z>R7wW#PHGeQC^|gv$wu|beoeKbzuh+d|Dk8ew{NopT;$1#rc!e7L=CbGAOL~b;cM0W7U57Rn(^m`$f zZB=~ppRw0la{StZ>CLSN0BimYM{5d(%%1Sy;V-NE`w@shSMg>U1$Gan-sct72mZ2D zm)jPkkK4XHB&;!kAQBsw0nZdOhL_%4x3qEG6-*3I#Z*-jdqKXlcxH*=pOOczF5a zg<7Sxn=;u`^UaU+m-i+ei13u~wTZUHnEIK%MfXr)@V##er%w@Nr)<7IaoD!Ky{;j_ z6MIkViRbUbD7}|&8N;nPyyEy%;At`T<$_Zs5`~7T=Hs^Fo{5ln%aSl21)6(>j|608 zzfe9gQz}~OC(<>@O8+?*UBvrv9699ZXC7x!3@`OkX2r$mnIs+Xp&@edZStKrUADHK zkJHuG%PLEHfJ%adGaq}nWCigJXqpGe3{;Ejl;|tW5(X_;Ozcd#G|>12ZX-jgxz>do zU=c+OTl{-47tt$=j%7IJeS(pgddctikRcwjEy@7Ii=I$YMu3cAC@iVK8m0A*Gh-rg)l=2tso|B&$y5^ zIDkX%v-k@u==31W_Y%T0Sf?pWe0{M~Dah|d3&frLxiju{a{HDmCdw)p z8(tSuToz?asuHqY-cDq#!jUFqlF8*|ZxPpX7nPpPQ<%xqlcZ!-GjQmdrsIZJ@K&A_ z#|%(JwByU-K!f#>`cQgP!gQniN5%p|nviqv6s$-RShMs{vaWR0CEy-Pu^Qzt%ZaJk zI>$Xy7xJ``41DO@^lST9Lu0KI;vJ?Qkzi5N}{t|2Ga@>41ow1IgEdzH*y>`tL-|e ztXUZpnHBix{T8T}D;$P)Q_z?9e~;uz9GN0oZ9CyC+POE|BYbO{EB z{;dc3a6NLjO4on>cF@Zqto|u=fMOCH!Fn^)&N(+B#~}eeosA!lnpKxtiul_5{WGN! z1o!s^=)7spZ-Bm0dVmcNlYU{~j8)idKx=D|sv>TjakXm_NHvT(o>vs!=ZK+*O-Kh8#o)zLWl0jkbb7l(36M`0ktTms>ET1qybkQ;TO zLZ)8xtX@JYFo&EjlDQ?<+Q!Mkg?f)aZ;k!Z$-{CJgrYv&l}$Z@(ZEOF5%vpH&euj| z)3Ccd${exMnJwef7V@n(wP@D;1;R*C zisWfSM-eRpwIp`nvut$H&meqa>O(Z5hCqr4feogHQDK>=u1;7)Wqc)_^@AcsByq9663ZasczI6y!x34o~nUhdD;($>qOUk+0ZOXCnSUOLO zBcAVG_SoC@FAS=oWJ!grA*4w|i98$W&x}_qoN88voocLJ`-fY$#<^yKxC9`>`rlfv z(l$0W_Mw%q0`$Z{^7P})e}A$iydnTai<6B6oWGWNi=b3OH)3uw3(RZKsQ{iJc;(Yi zvFrA)?fJt2EyiDOs15j(uhX z?+C#ASks!MDj+9}h*U5Qp0w^y5OUT?cWtO`(%c^*3zH3$a^b5wtZSZTM*uzQ+UR2; zKb`x{3k44GG;z*Qc5Nv1yY}67CVhCxkhO@XkkM#3!E5et&b^l3&Mx~O>Ss2iZ*ue7 zXKi<1kUe}RZ|{J)Y$M!Y{JgVEi9}Yleugck>kKD(S_%@2BdpDW1nm#iBuc_*d2Q|% zgc2#Xd|X9&Sp{&6=I@Y2WGE)FTdNcp)AjfQH=M-yHRx1cL?_PAFW6ewJc>KziUEqL zU?!NSYJ=~kv6NTp`$lctRBbL0FF_#kc;_j`;@?D+6-5MwK7D}$jG~dY`bJK!KNj%H zA0wEGBxQqLX$FUI>%jV*yt*xg?ej+phrnaHM`{efGRRBeNaO1h35sy!lDfSZ)Gq#jN9{2*>!AuVd$y^7;&OEFa-?38Xa*Qm?9VK|Dq+=#%ldexS9Hp{Yso z{G%vqh}A&#`p-$L-=7mX8QanXFb!$N5Q)WjJ;HiLcq&F*V^1=kRwd>Pu~BOWC=7nE znVjFLb8-`SoUYnzRfqR=g4OpLPcFg1HX}V}fbHjyS82hZ7hy=LbE8!5S`WTb$IGluInMXB~`LvSK? z@^n4@$6cOk|BVL{9tVwDV`Ipnt>ov<=yg^CDNnbcoM8v4>!s)*U38L>R;}@E?l@Xh zhK^~@1AHLv6pbI=)7sto#eFrne&^4rc9j3yW-*^Sh4K4;E8Fu14nDsnXf1P~#u`dJFScezXWEDCfMT*q**; z%sC`AcwCkO3rp%EQpjf>fz?4-xM6K53mVA^RyNIi9)c80godE5L|$K$bgp=P&-{#x z?|m$KPWdDVn6+Y!*j3U&%*KxRPPvbe_b7X|SyzsTiZSC`ir~o+=3^pHxcu@U` zTquQ=Dx{z$@eA#)dF9AL)^zuen*ah;l*N6k805JiYLfo2NN{V2lUN_R1{vddwu z4PEQMv7eZpSys0lveQfZ##xqxR59qsG)(6!smQ0^P#=w2ST)$O(FntO8^))aZ{VC}{FkMN`yM@N9t_3a;T{x2|9*6S>1?T;l z&$DrL<)cmZjSjF#xp-SxVLf8h-=`M_MQhF>@tdRMb%pt*v4kIGRNEz6Ju@s_QY~%h zO&&)T;mz&}?au5R=9E5@i=A2i?DLR!1T{@JxrT{JMkzVAS$7#@PJ&{+oTNaPBifSI%t#P|vk<-gt5bcw z4bKhU55bNIIlvx7Dx>V{J{VeD{S;3&kf_5+X2$z)kmx&&>X_*x37U$~;&~wW{X5E3 zT#?t1?jsRy(X_p7xOYKVhK3&Blh)f9>PZ)=Ip408qDYCBI<0bJI0o_iU9IyTrgOzkxhk$oC9u2T{Y-mT z%Ewo%d46#THSKCi6yV2pf7}!AmefRlf)b0{KzXDXG(^gG@c;4$zGP&7VzTw-_Eq!u zw53at#U1vW4sxo`A8?e}S1~PVWCUXD+-(iLrPba9NXLy03KU|k66SZ^LDZGycSY?- zfG!H2x@69wPC!ldt9GB}WhU+KAE2bTWf9Uf*|(EMK5nm^b~-L!A9{7_>grP8OXDkg zxnj9Xm*pNPUGn!DKZNv^)W^-2;4Cn0y;u14z!i0xp6k zm+}3%)RdHy$%NO2*u){sc-(?Zk&3UYg9*;TNwHVVegRoF z!Y=RCuMMj4dL`MsEwrZpOQwjhu<*M!`V|Iu)9{N(U)P||q)RXCQBPXe#D#qxDg|6^ zx!W)45V{hM5oQPsBpWX;&wA^e)N`Q@wfaAr<|# z*&Z^q3pZY#el>VDbbG{fzs>sb*A6i&~%{3pZ12^oUYeN5F_G}M{I{6 z1T<7yYFGIhuqIk1A7>tEo{QJ~!G&6qNqv*TnfD)LOi#<(sSz1%$XXAvkY%N*q@P2VqE55G4+e5+a-Q389EhRnSOuA=@ z?BPM8k>(Q~(0kCk>YnDgWj@!t!CIo9{|3wY9_+H^j1}GCDR%*}jRN0(XfStsQwns<*he{XNligh+#iBoB9i$$E#NK52&b9AV*a zb?%cvkE_g;tehU0*F4#uBLK^*ZD_Qyo~*lxmVf0VfEy z0%_Ph7h}TN?b*1Hpx_CL(anSkt=U8;nJ<0V$Y#b1IsOGE_CJ8+gphNLJfZo$N1A+2^yCX4dj z)}D?rD@kPErJhavpo5d6ToN@nxYzIXa+cCCNO%41cx@RCmFVgArYBTGy^u&pgt4^; ziD2gY|9JPrNT9hWgW}tJ%ah@a2H#N@)5o&Yr>dmb3Vt_LPa9*JnnZscF5aL5#Waw; z*B5&ZPELV#u@vY9GjRmYM(5>@SGHYqSxH(P{>Pv1?(FW8Vrnua1>b++)5nA7di*{7#(;_x~i>S|_ z$p+i4(A@mkpvQel#XBFCCTe-_PuB^0hnjLkR`^g%&p?{-dQ0J0pj2h*ZNTJv=(uKkmrl2lNAd~1F}<&^h}bzy}M~KyT*eE z?Mc`Ndb}{jhVg?JC&MYc&);Cm+@sbrdlEaol_!D0=Ie+9{-e#om8r_4KH~keW+WWC z^c7ae3lxJvn>i1)z$%j3a+}S9fZM;_0Lzt7epCxp|KTyfU>dMf(z1B?@`IuRI42X! z%efi-eqsQ8>+@ZG#5Q`)<$pe@CUNxXOv5bZSXAn;`pq!3LBw-S;pSZWTo6G*ijfBQ^h1ZT3Ya)?s*OeGCj(A(a&zqx zzWstCSuHnBcI}5YE!}kBLZWF)%b+VnHIx{)#ck_C|5094E*Lc*_P`YT6W@ABD3UjS z%Ng1iyD^2*C8wccG{G49Jj%`m9l(F*FX-V8#hHfHI^UZX7_zSKE%acuBI{lu$jrPy zIea@;7is}HX$c*5aIw3n*uciZsHkw<-q}Hw*WxEEDAndC>)J)@>IlLFdgp>IEGM}# zth1dtG(USMV!~YAXiSpy46&ZW6)plj9`J4Qn|BWr-8cT=Eb-;Q<#(upp%Dc}J9ukJ z?N`;0t%6t4D+3GQjA&?VthMNgcv%1gYoU<-iZuyOSM~}DW{kGh?Ytx4T_qqPp*u_#)tJTB0&sbb;q@% zj@%#bPv&mrBN;P>MmCd$Dx+Cq3B$u0^aE)5XpYp&spVzef=66F(KXE7*FDB41wILt zpig=0Uthz@^*l3Zc9dfbSv6Uc*vQ6{bf^Y5?inML$_i5tRUQ~OSU&ucBlGUb6t`UWLw&1D?@uqmA?A%es zWSfc*^MLP8#$U}wvNuU*He5~Vl-DF8h*fE65J1N|VMvs~v&JPlshk;NQ&1WMO(r+u z3+I^+UuFPsTV$g%?{rt~!yls95S(e@A#H6z32Chlbp%E;A8d#gnz+_ap{w})103S+ zFVa`AiiAZ(DUNUO!-C+jbYC(v{-2k3jq4p5&NlhGwk}rAu4}ckOnG{G2gQ>n1y_?P zwBq7OGoli|SaaK+(gY+G9^~`*3!A81;Bcq=E3z{J#FNogF90Nn9yT)+sD034bAgC(oMn0%Sa+=^5xW z&o~5vaXQ8A2uk)%sQv66q7Saa0Hs{i6_r(%rC`s|09+tAXT35jw?1u7&{%$%6m~bI z@XKEljqVaTXVeDEKVoL7(`hGN7O47yBD{m%DHrE?-!j|!z8ik4F}P(Z{gnB+z$8&} zp~Z`5(`*kQMxUEppeFqro+~GQ?phQEv-sCP8pI4I7G(c)ma~M7S0YDt_T@;oe!^q4 z6uO_xt3JyiRKGXvZ zRbL?j;gDpsu(nSJ>pxWvL0Tm~*aWuD3~MeGrU$JYCbjOB?X zZ3V$GO-}>b7EJ2A@fX|A$}9dqp56ki%5D1|Mg;+-q(MR&lx~oa7U>S@?h>RyQX~bG z4rwVV>5^^{0ZHjbR7ya?Z@%aLf8Tu$&+%M=z4v<8nsbaX$C|UeYi~ay{sWPZWyDZntC%@lS)8q9XC-ec zj`PNR_`uHZyr2jp_5cWNZWm>5po^bgYlqPbr${$@1G5(iNc`w^rFi~xe!w~Kd`>{5 zHx(P2qaw4r1UECD{XV}eV7LCJ*W$&sc(EZMwD)n`O7gE1jLNgIw>O8gfAr_i0hk&c zzoGu=^Vj_)h!eYtmz`p9U_yQN1J8;}i7}Ni{Yl>L&Ehw)PA^uzVnFx7E^K!;UD?eG z2Hx5c20V5twaL^ZfpDXHiKI+KqL1wCUR$`Qc=2|wSwt&}s7zB^xL5=`e2B1oh&X)j zGe-u~4*_V(W$_YmYM~;DEm%@x*x=Wx@^PihWE1NYLo?*44&?0p;u0BO#ap*m_@S6? z$nNt0ya1Wub^KqqS*rK1S2M2K+(OHXn7iK2A>F@PSk;nn5c%YbX0^}FbXNAbXk(4v zjSPfJ9b>$=WTN)tF`8$3KO zf8_2>baVy7!Sp)&DfXW&hsrQyBSAfxyL4h|>OX0$=Cknb`)6&M+S&)mkToxn&&cRF zcf&xEQa^t)d))DIYl_zlM9%NXUp~3jXgY5crs{$6RB4%m{Ip9<@~y`N@8>-GD||`I zx9`*VYskl$Rr?tq_sPAA`AH+hCoRk+Ba&t2$J;sW^+s1j<;y11*0VekCHip*Z7oe1 zi6l#~hpQ3t)(0y*%VD`yU9yCGX6smzlUI=Ty8SVIlG&oko7PLN@V>9pb&?uVH~QHN z8S$gBsUOv8G*~41eeRa+l<1_!P}d+X9R4L$eXzC7Vj(2wQ68dDv;Rb*o63R`aW0Mr@B}H+gMzNX{F3LaL-!#}r+wH3f%^hIUBEeDWNUwQ z=B3yXjo4`iZd>ud%y%aNURt$aD4dy9Y!olH;5wV8L`i6p^{Zf1NpNsEX+Rr>yDM-|~} z!skCEe`gwHArdsS-a~zB#nawvM8u6f zrr97T_ghRUcl5*ex&8c+tTc0~6H4=Hl)joBqU+a1ED~9`Ut#48a(gWN?f{ zdT3WSDYTEIu-KoyRYCg;mor!GvC>v}$KOQg=7qmp(B>~#9T^g{sym%@g9CjWf62sL zpV)RNSGOPP#4KCH;g06BI0>sJ4{_4U%!sh)!kDRpc#6B2&#|NlrYg znd-OWO#Fn{8Ul}d5*1@*NQDGDPqzfCwg`(gGaT-R#j}}^C^-y0iq|3>lCE{QeudIe zjZ)55%lfqKjdv9B`0SYc`!X!0XRj2*U|FqL^pcR7N=WPeziC4oULF-TT#B^i@^z~uw21uDqPPR`>dO*%YIJcL=v6Df0XSva( zJvMK2T_WtDQr3GqY|3%vM81KX@W?NIxdUUrDn#?!RBoddy-ZJmccnw7BJ04!7Al<- zI+>WDENd#QGx^$qw_Bma0xxHzj767ZJOxFcY%k*v51#tGm<7wIt*ph7`Je1|J3ISc z{$})r5I}rC!9E@ZqX%Wez}f>R<2na2QBhGdNs<3sU#oJUTW(ObOlpe$m-v{z^YUbI z6kz=TR5_m*D$8#-Dd(sPZmh5DpZ>SJa-)5ZMhoO+Uq-~8#7AHyM8^@Nr8mO|x)Q&w z9dl9jV9XqyX&S#qyoi*PEn^;IWPL)okl~w2zNM4K_{{47u>Vw0!Ar8rFW zVpCf5-QQvU)6=@&+=nvvJ7{G8;Bt#`KM{E=k!&$jQevLtjm`S~6Tc!My@gUi zPHk#Wsdm*tH$iH>JLcr^@#&2K3%xrM2&nRvHaDj$%5b{{!#GBV9U-L8+7?l2WIy`9 zWexRAgp3SD2`~h}whc6!<=r&j9=!;$=^qjUV@J6ho zIpLuN{wh7=3Blb(Ia;?DnzXX4X|%*ccu|)9n^^RE1uacMy>-ey#1*-Do-~ukN)4h5 zIv>VeD~D-gyU&N z;o$Xav+3!&6A$BN2cHz)d^vsiqvoE_IKj6Pd?K2+Y2+MK^@>$CoLs3^i*5A9E!nd| zQMxTZrG+;}@^YJQ%4qjns?+zP56E5xC(cEgD=+WA*PLn`SWi@>n3j7-8$I-kF)^Aa zz$J7)C#0K^X`qmYQ0cCrw%UcM!8LKG`XFt_Wro&aQrSHTB0T~{LCb9uhb~hW&~}I2 zgUmS!E&@{d{gzM`J=PR{_)x)6c>u;IRyxk{^E=HywzOPN*O#3-*5k1b!q|;75ze0) zD9oeJlcHz*^EwhMQC?QQXI#1nzdKj2T8Q#HYM>s`vC^LV5qsgYE3=*Sx!~g&P7CmNP-2nX@*_`o!MYgn9T1VYs=+O65I@?}ZIiXW^Jo#`< zR!Il91V6Et7NiXnoJx1KxLpr~3pW^(IaahScGA;}%S-Z$JjI5lG9Sq~a}e>>dbKR1 zwjG&C|F@~5=;c|B+cJLsbo%pS2Ij$+8MUUte{gL^{J*uvs7bI*Gk7+_2Lqg8SJzcK zrUQ5hM!xFm>Q?J0i*3^`U{vS&4eC=A>n!h$bRTL2W?n&$kk;FityQas8omS$bBxK# zTw)E$(`(8UJWA}DjOk-6`nT%V>^OdxW7i{-XWnXp*HW zt3^Kp(__Uy1ld36$nG*xy?Up+ltkn%DkW?UgEXoftbI^hS@Z7WvukziKF_&-3tv@B zTf$R^WJssXVterIaORYPj20g>cP}BAI{!O;d4Y3ealO4S=fk(S!db!?+A*87Vw?EF zEUItW0mKiKr(ba3rDQ3dRK7D9xBHYD7ax_&bnX&O;Zz?y`XD6L^xzYU597-$`8<-_ zkMZAE2d}-LlkexBMx*Tc^{$xx{(ULdr*$do545?R$6)X1yZFxczs&rCV2K4^xS3jA zouHJ?Uu8W?1^jEWM2lBIAi0V6|BoM2$9>{g@vySF6P7LIa6`8NhJOk!hZ4j>=(us? z1`=B)CMGJ~)(7)&XwTsezz_^l6Xi}FZq{9ne^q(K9BmflARJb5hB@{81z%_hqiuzA z&N~=y6uW%;rtOaIBdH;S>&x74bYk-B9q;z>4_N0)%XtzAomzjbx;s zG(z<;QB@>kon>ALIlG>0JUyYjWYVK}2@S%|4m>uckut;jB#*nw`PR#l_wDV*48|{i zI}YWxHmA$%P9;Y7lFlXeY*sPf_Env@?z3<&i}l4$k@di>4K~AY4m_{#9OY%qUKbJ< z>)8Ev7(*%2Zz)CC$&$@-tPga`&j{NV6Gm2C4@oJqDhyWR#)xa@JbT9dDh zuD;;s#Lp4=h3;z>QlYt#(x)=azd&%?r&O^LMZ-#C1Oeu+9%;-X1y`IgVC zRm@?$yH3$z=z1UH*2(zHWY1vjZc4q)9U?6)FA*b)^@_x*!AMC?3agH4ON#kp{F$*3 zR1vfmBQ&|^oLGs$P6TD|3vwKBmJcHHV(pUY(XjHs6Tyr_b$J~ zyAK~?(QXqj3C5n5S><%qpRWw^O9+ZZ>}~#Fl*g}TrIY_U{DQ;ukI=^v!Z~FLufS>O zvO6*|k`Z`yR=~ba3Ffzc3+~XaW%Xor?j*}9=S8tPhnY?o=*jk3Xp=%%SQvteVe|9- zm*N*e(CgxjL$hzbgC?@x^7v_UN~-0O36{{gWpW+`yh3}^UKbtPnI&Bd27OgkY>8$x zQf_t;-D_g%@ibre<#QA7;810l*tjH2Yla(qh*&xJGWLBS_^rLo&Q|X__R{g0tL=yF zrMWs+io1PvuD0as>qMH9lgcj_O8%r#qRA(yYP}6l()LMarxW!JXyh!eLomaGv@44E@8Lxa1*Gq7r;B-Xqs*eBev@?5m+n_BYYLgwJ91RNx)C(~2Nsu7lyl)Nu5FDNVwS7i=e{MC1U&|<%G zs*Sgh-qh6808Qu=40~NW*4^G-lbD=mb#9|xukdY#%qbZllrJu=R@=V7 z#NslIiT59&lp1|4AB~^=gNcmn9v`19ExEawdu05wysWIbv^kk(kCLOt!^}fs?!X?q zCKC37>O!260-AwAca*ECx2uBVqCbdaB-G*-Rt*y@FFNi~9&Qp)&iD1lvN(Xw$zZ^a z7N^s@u2yKA-Zk80JmN}$B`U`#^vbc&)!|0p^U6pQGL&(GvDu^;%ZIv=itp=UH?pXF zv?~fdC-0|ixC6F-G->2(2Jv;-25wx_(b0*V|ELi;=%*98_}%qmvAuo560`F>xTJ(t zxAH}zidZW06?U6M-PkyAURja>;}=Qn>g%C(Qc_Zr^FMnR%ea9{;5M;#a8S%x3W)Ri z*|_<{FxZ7K=+TRwD3WIf15D3AHREz#5Gg4w?Wy_zs8Q|o@`~=}cwbF;c=%MSAw_(v zk|Lc7yO6w_8+FyI@A+ov@;&&{Od8R#y@GB})_z;J@^xeyIic3amOH4+(?GHM`!R6E zFF28ovMQp-glB$j|E*4>Z5nu3Lnt3UcY#I?u5e&s5F<(D^F4h#JG&=_S@$rUVd~D& z$;lyNTn18c0Pxr}&8m0^KlJ3SB4ZbwyG@|2Eq{T#CM4ZtNq2jEM=9s;ckZeSaVK^vN?GC`K2MlD*>Qr(#HF zTRIN2bxt2@u`JbX`XjyJeu9tjGCtpvarh6~bzTpT#0-PZi7eD=v(@9K_vM%-a&FPM zduB(UuFr1#S^0CpSLsQCo~KLC&((Q)wK<@;C;R-MzgkkPC{g|?X;bjJU_TYd`iRm; zHiJ){$9K2%+A?MfH|VlZ;2aB*kMqvd+LItRVW78@z?cmoO7^InoE&;)X6BpZP)z-j%NLWBx8OfqL;eVDu`^ZD%V0((NNx%<|E+FTmW_W1st6@q5@ z=;Qe4*u;o}2*rFd${21U`S=l{cs^W5LrPHFdpn7CxAYrAP4v*%>+j0@Z2HU(R4aNr zvaz*B$*bTj37)G?QcS*;5HZ50tI5usqq>)_tUfgzKD5_S&3fdQJFjmUjTL>X^$UU|c@jx-S<`&vz zdgt5i&ZjP3y5eGDpWFP;r<*(;v_rcHC~sLq)e1%>MvjfCwSh70%fy7{P6DE75G4=w zd@WG0b#TaUhoG`Pd<%3czoi@0Uf<89zq(>k^mWuJMw`VN*d=s#Q{|d-#AlGxCO-zf z%fdqN^QlFoqO6>@f#x^9@!83t;C1`0jQW(>UMs&Vl&{U4cVg(}z5D}8(&paV89#Op zM4kM+bo}_#&*{J_t@wrt7qlNaRyxECAF5OgF|do2bVKbS?aC|oGC>>5kQjManh_i8 z`h>^xu__D9?+VFZX1^=Rcwn=~q01+|Ud(xb25IRZ-0uoO$2}-__D8M-kq%Yc*xD{5 zlkUa~m7v-0yH|}IsLTJP6Y^6BG6#o-0B5Cb>jfgcsu5rn*M~UoTpA7hj!TUTzz8s5 zc{}*`O)9u@@}cG6$=|M&gyMD#%0W$Dv3 ztS)8{;!gJC0yBDhd#74eLXZ1CL1*+-`u%->Y1w~@!ot#GlnlwkcySwKq&fVuAP0S^5MdG8Qb8jj0Q4S?nTXdnPG}~~kPfj+p8UbRl zumQ5Fm1GGm5&c5ssJu~!s<-y`*1-wE4W=Vn3Y@6dMtBP}Mit3grP^F@WYf~q8+S@d zA!@8aMPu$wtdY6|Mf=r+7HscC_Uo!sX%O{3p16t)b5OpaE>*|t_sq7Blo8IQ+ zf)dj)0c*?wf*({gF>rdcjaL4YqN>+4= z8{hgA?eDt= zK&!M$hZ%0|a(%5GeB^**%O?l|bZ7*(S0fn7$2?jm7~VqXAcKIjb$3rsYOY;8U)Mg# zqV2&#xxDYBy(*|+x z@T&sH{#IUGwa2bDbQBP;1c#)bm~rtC*soIf;1&P7js*Iw_uuUz>kTx~ETkxf3=S9B z`6Gdx##LO^@AI-UjyHl1xDBW{?u{H}pP&uCw{?*7@O5bvt+69a%Pr9q;8U9#Q}`Gt zF6H}YnHt@=AXwmD-uqjz^rka7;kFtdc`cmTI(n(>=90h6*S_8fx0=stZ)5LseT{Qm zl#GXd6Al^!GWoo#s|#f~^Ia(;LQa20$Tq-HK1`R_;&YI!@W13avn^yo%V24`=39ro?$&%3>3G{aJ{LJ#CoSa z8APa;#bsq{8|ls)$nbVJjVXnCI|&P}&&Z-bi#f8h zzWs7f&*OpyqwlVk7E-=PJ~Ik>cd1|ye-ESL&!+gl)cE*2C{X*?m*}2n8%FtH>PtlF|>k_4Ox8Y)rFD6d@;mCT#Lv z7uU#z_jvkM{?7}rp}sgdvegl?<#WebkL=1NBDP0iORq7ZZoyk~VnVsTMeWVW)h;or z={KMK9+H90LliJq)VM5n;_J|3T>k{E6^lzt(}i-Z(h5^5)$y$2p)3pYhfok85}Es^ zfmQ+!a2s@PD1b6wRTURZZct)O%xP(9nJD-VE)x+E`N2h&O{5fzTxNij0O%Wmh5YIM zqsJeUEy>y!RY0qzq@+aLJV?_RR{f7#Db-r86CM=c+R_?-UshV=JHx#~U@k2y``*#E zzaj$Gor+fX9!VQHGo)xp8Nv*KwOx~P{#D|@PMd*!kvosN*Y*G3BC>k zMkftih}y8Ix1najs0pE$2LxqjZ%=mjE**IcNOTJSTlYd+@(0>wur1KAaB!-9Pn^PE zzJ%$ow8=xQ*4KUYlJ?L1G_|w<8Az(A;KCbsE>_9`&dHNNzr24ATm^4rk2ZTiRcrCF zrN3y~BRm-`nMaTwnyr9@6ee3ko_tjbJm$5FV07PV>Y2B@JIDvYoC+{+S~yd7$^!-7 z(|`Nr<*A<-7}#E5>_S|R4eDFXDJpsi-~4f9TfuC{RNoB?{nTYrAz+q!_SLkFL~Vqt99s)nIV7B93bwGcdV88ZP? z0cJ{2vR5ZWQ%Y}pVmRf&)lmlf?`gj6?C|3FYRqGsIE@7QRpO2mC__dxl*r*(Rh$g2 z7X`bB;LoW@q=?eXr=4ZGQ^+}p!}|<1XM}h2dO8OLazsr0zkgB;rFG%V-@}kw62vLA zH6y)Q=eR2Pc{qYaMom?VNJi~R0RGXZpc~+i&4fmZg-YoQ-xgNt9C^T*U>+wb>*2u% zzCFL5i|a|2NYndww&ZXF)dCDU&U4S&?<$V3RrOJ=!Y^GZb~>z=qhmXL>oV zB0iGD_Efjkhfl}Y|M)?t5Ae5Y%iBQPk)DG!jAb1EO&N!H0mfjt3<3~W-1cgx+<;2_ z1{Z5M0wuuf7P_hovLH0LWWs+nJP*xsn;3MeuBh_-WrXzi(Fr{UH7MP=EfpGf75V)g&n~R5 z_tXwO?lFsp8S5~ztfl4R{bHi;&&HSb9~y6hs|y;+Rjpo~(<6`lUMCns0Kmr>u=g2y ze(!s(SmaYNXVs*X;d z_(hj^rO)vWNJW6J?F+_jotm~8|Ln~PJUb>;jBBW8wcl_BlnUC28z=z3VZO&}L=ikW zSJ0~Cyp4^G4L7u=sv%y(ED??>+wsEH=fVFK#=IWV zVALPNF5r>F5NtWWj9g~Kx(Lj>Cg9SCs|0ycM$ew{z+E7A&hI;lQy$P=v`RM`I1cg_ z5xEyx2P6l8AhCGtIO?$M);QhZN_TvGT=um7r(xjFe+asTz8Q>{b_2Adc{dPScfrL2;0ZqF-DHV%e3I6TPU zch&T^cpo-^vTYqu2iMTWMo&)#5gR6=79f{M!1{jC{_o^p|K_3J&u7^WY#%nL@B6eO zT`%tsJUhP(U~fA$gRhkYk$-c`h$jrb9{l&Kfkj0i_Du;qoEoS{fUE18;PHgU%tzaC z#fLAtY|~^R5JM*yIZD2pE%0D_wNlI3|}T$QdWgaVRf1KLDR2gQ>?Cggtrh<72L6OCt2vCX5UK$ zjDWUj(b3VI+}se-dHMOje);k{@&x*Nn%2GkFL8pr0C6e9?_dC_i@_bTVE9$Y_#4n3 zM!^gj(Cq<9g_nFC!Xk7qgExhI3g!M#SfR00FqZ5$mlx2Xe9`PUxj%_)sT zH5sv9-+wEaWC>Z!*2zh1=lP}$j?yiMw2cRK#<8oz4!0Mv^pd~|RMD)I34)WGTY?4m zE62J2rPScjO<$#vmpd$kw|L4EVW@kf0Ztbuicw94%lm*7v3=K%Cp6?S+?S8Bhdkz69VV|A7K{*%sSLF^oe2>U zkzvHs`1kxgX#3qVbkf3^g5W!B4$4U5Mw&f%gQTWB5E#5ap`ik2U-rMIDty;s9p?}w z^{#VEJQ7JX@55_0e0KskD|9%_13pRxqZ5;V;KNvk6k`p07-%jLkOjccS>aXY zIEU!7HQATZa6bb-4my6{kWsUmjl0}iykdj1RdH^BnEeG7{dhQ9kMOtM$>-{Ji8OG`7V`2pbv(K|t;ya)Q@+TmF$0q)B>8pO=D8{SG{?8gPimgloz2-3X# z0?fh!i1{J@aj02UKa)&kt3A)Yz1_V$o6Fj&tQ)GX9`dp;>fVW z5M%{B3~(@hE)qLt`7ClcY<@)nz!TxG2pOZkSVBLW-xQM*qyQtbk=HUBXibCgNdNqK z&fa?THTA(!!T>$8J>o?FkoundWJn)@mv*7BwyNxaI+N*V(UW-{hZFo)s7T}0`o(~U z&7S`P|NML?Tw>>c@z2*PVIcnm4}%6X2(SAQ#*-l#_DI@$TBsaTgF00PZ=>Gp;;B}; z+_|fZGAAd^d;Lkx3tpOg43A#Whr+DgP~NY*idGvJSN&;+L$4)mR$9d>YO9HbEVKPT zS6Xd~`2MoaMlm@%Sid+LSJ~llefG@!;uOrb+5b?N=A7Ht&wsV|jg7?vvf-P%0A9XK!)6Ojfjl2I}m~ z_;SrTNw;QeA0Q3jq+a5@)%23Ypt&NX*X0PsljL35*eGl(W1y#hPxpjhSAswb z&6r_YQg=@ent*^nWMt%v@E1p*3&<-d*e8g$gWeQ#SD@NuSrUi?Cn?tH*_mmTZvW6w zmswS1;J*N*4eF1X8Zr^D-!k9xChaT_H%1y78^`LMjhp>ny?W)a(9)>1?&alWQmY>n zjuXBZ_%GA@aHBYH8`$@lUG3WDra5=2pvw{pIxf{3f+ttHU)c$P5Q`kT;Na`;Of9aU z&+3m4lOGHpdQ9ZA;k83>5q97D@`LpioC~-zsS^M8Z5Vunxw*R}BqZ<=ILTvv%+(_} zavyT;((bOkr<18EP4n};m80$P{K7)y^Tbk#Mo!v6KY%c}&Z5XjAQwxq41enfC>K6J z?RF|AO?PeXq#YTb9ic)p`})>c9z6p?d}`{9#a;rktN?{xr=>jsG@g}}<>l+Ep{*@z zW=0F2!vcE4KpL9=kVi&7`vq}j!wd^}2{AFT)4zYAJgea2Bdn#RMIq!C3Ls+!ZI?)f zhK?=-hO5*-;CZ5;Ft&UA(S9oS?_VEyn@=PquY)~QFce$ z-rfD<-*f0+he-1`Lvm)C7#JD3LE{g&Jl26A?E3sUBPS<(H$GfAKsE$0WOH!0V3Bcm z|9r-qsz@R19)XC6zkaFc>yrZm%7-co3=Kvqq{YQFu-W0w4O{Wh$wu3Z^ANys`M|g> zObq`f-<~W@7Up(=$0G9Y;&5$k&A?p<`SlyasqhR?jg5`lF8@4*Zk_V5Y_MxvKrQt0 z_O61RhQug7RsXgf=*`7$@K{+H2XYkc!-wg^!-_BgR3IFO(x<}*0E$tCHEdaj`G)vJ zCKb2S-=_Ek1OvmvYoLO5jgKdSckf`vIvcjC$Johi!pVYf9N5A5ZE`Egtab71w?*cUf3l6OfR|y~LqJ#z#^IUU139QE62`IZG!Y zAwjqKIop>?)fLDDd4*qD?%$_nVUbrdcA+67BSQ>X8G^3Y#l^*w*bN6koS8r)W>U_0 ztffT+CIOS)Xfn2dSd{T16(%;e7?~(ySD1AMZwlERiHu5}4*ZAUGpqp`so*~^iLw6@ zCaZb*_>@GIK)3&5mNf^YD#hXb&Z*{1GCn>+BF zrSryq!5`fzrV<-BIYofU%}!`96-jkMnpxK&o{XK_}-k%WBu6$ zCK*u$oG$anbbf#eIwTXni~YWQ*pYAEbi=!qS5dJBU~}|iCK0eSQvaN(wM>@E8{>ou z1@YYC$B(>Fi?4X@0?`W(56{GNF;m#XY`HTGeg*Pwaj3-i z)c4Q(O*B;0N(eDPSqiV(bt_G-!Po`6^YpB&&(UN&v+mU1-rlT6Eh!$m-_#5ZM`}jJ z6rMb}g#DQO*vlMbTD z57j$;Z-D-%La_DWRxrc;`%gx~pn+~wQ4!M@&cEYbT{pzV+oL|T=Q1N429gHM^MO?l zGEAd}{{fM@4ds-fHz}Zsb9`&(C|8*PHr}HcW+M#PHu^M1GHe65b~>fZVg`*=IC8y!ulW~@ zGJ2;|VbtB*n~<2;1r^OR82K@)=>)AEvEd;BS1p*i1QAf=?^YhfKEMHk@HzIZq>*Cl z^J07QyD&#CK0Y3lntvwH!ny?-F@I6q= zyH+zZJjBsH%rh#I$8PpxZ*OEZPCT}``5}+hun7Rd3&6vnVPSmREmhwSK~Ql<_C~X& z5`sek9kqbGLhu&scRMa0Ef zUtOFT2@XWoBo0N)Sfk0nD~BuhR8`r?PkbIOaQaxRjQbem7vKR)L zet>%Tpx`J3T$+UxYg;K>KDt+Crg`C@?UvP$l~_?907a+Ygtu`sH?+ z{(gSQk#zO+w1(ZFQ}7vp6j*bzJ3A#okm`Z&oqW_9V^mSUi!}oZ4P;(;U4%nH;1$r* z=rG}Q0p)UOWkpg#;u`d@XByN(Mdg@FX+jN+%D1gmPOAleV4ze2B>DMn+U1 zqQhdBNQ4;&oP`Y}GVy?Cr&;Ye>{O!4PZIc*$e_w%XL{?*-QZDAOeQ z4Oz^ybk9Ul5v$qr7b5@;sK5L9`(xg^)j2wf8zb8ljCR|_)s=>o6$^qK&$u;sENq zjUOBj9^}1$|Gq~8GkFJD81%sx*KX)%6i*dvFdCY%{=_7lfYr#l^))n1D8J2$6wLGXyXv zBrlIHiiAVE=u5V!ZxS$GIAS1F8kN!=01gPBv~%Q2S^DuKIy-xj0o}P=`vJsuhuM#> zz{l$f(Cpyw@ab^5(bK1;H}O7vgsM%I*S^`x$_mEq+vX5iu&6{D23lDnCFSKY;h^z= zo@fn~w6%?mI>D7i8(uSB@(M5in(AtJeh?)2CZ(Q1sD;eG*8PeA?ohh@oEK{D!Ew~T zZ3Woj-S{>P!ps|E?(m`M&d%yFQ@b(p`Sa)Jj^AMi16T*_QleFQ3bKkm>n0qWM_r!Y zdU|ASZEfy9rsMC>$pXt5gv>%F9w6fX_b3NM8kjX60;?qK`BM>g+z;Vom`6V_G9ptk zReC$FF8|#-6d5(p+3olr?=CGpQdL!rqO5f^&q-rU&Q?dJCmM{E^qSQbMWUA;eON6 z(b3S=#d!DG%^@}<0a;jp1Rxdx*M-x#v%4zzLu*72N`mNs~4$>jK4rD%K~jCTt%oe>&QmOWt4Y zD`n9`@%Zz$$BgE|1BE?B8+jKO=#45iQYS+mQ#hliPGSxVKAa(xcyZweIOTH+m-+95 zgU*>5J%2{PiNHo~ES2QHfx@LZID%S$a%4R8jFnGh}j-+@|sLsjt@cd8-<|y-??ivNTX6CUDYw_nw>Um)G@Z2G{-3nKgo^ z8c2*^Mgla8Jpt$?qVk-d{IUkn0rG0%>(`&&Nrb!ze^&4Co%F6Hns;jHLpdbqmvT4oU@I4iEz$pzJbShx6 zNIO3uH#*oZ0)@=CtUqU%?yvMfHG#)QiRnp6=!LYI|H#d07$TtSqsL@+tDJi*E zduVN-V@{eo=AC`i-_w$(p@&bvSQonu=NARLxP^R_xw@bj*yu(ZYIqCGQBLc44Q&D#jwx9r^X=|#28sKb?1HXom5e{$5 zJUS}s(#8gIE+E*@(9*7?O;mvj1o)~nC>S;myx8QLOkGLIlT4=oJ_H6MHr%u{au`Vv z_!~IKG@1oDbfQOyR#uj>rY0dGJ_5sYP~QYS!_Cc2zh&dCm)e)3aaw%y%- z&Zh#JLAv8ZTJIkjSqDjQ71}4z!WM@5AE2eExHw!RqwO2)&j05HFan69`t)fOz<$Uo z?PV{{*AZ3?bM0g+rjU8xJfJRF#SQiMH{74nAq=CFi>-wF_K4I4)dTP4Fp?i)MTZ3i z1@TEq;XP)iI}^o7Uz`!DmZ*`1p`Lmm2a+&R@Oc4Rl-#>jqPmK_Cm6=vw zijSsnfIZ^YwY4IV@J3FIY+@o<}BeueN1{E#3txVXF1b8{a=a=1T$^S}?v!EhR1 z6!_SKLqZy%Rpb7jKiVh%;PQ%8=_KSoU{aTs#-sd$-$zH|j9PtM7yVE6p^%Af^LW5a zA=M1T%ei_Eh`LDb9v&VZYWq`AU5*P1AtpAqdJmREqr0I&t6r>93F5ozC8CHNQulQbP@I$)~Eo$Q%-XKLC6PE`sNh;+Gmd6WK# zRS}LK#2Q53fn8K;sRt`XBGXI(snzoOm|4U8Rx>GMGl>i2iZpG6v zCUKz4^}nV8#gE@%`V*AN_1UKEYG=^`cXxL5N5Vc#+D-n_x3;!Eo&^SoXh0}G7FyH6 zT~n9V3ppP_FoT^tR8&-eU%>8BL%9-}TWK+n01rh$OI^JaexeVM+Y5;3qaue`aNeGk z+83dKGFrUtjYB0e?U1>;vLfhr>JoK!{C$3YLU|YFi7E_s{o36fg1LSX5RVW+11Oi{ zfl%6r6=dVdI&UEP+%-xVG~NGDG5;r20B}D53W<U||xIXJ8#wLv6}CSX#2 zH))5A#F+Fu{!%%;1(nXNiDCjYG&JD52T(WRAJ{`Q?PTMC0RWy*4qhc{Cjr#)q4}pU z97M#i0P&51gF}UKJqgewyviv!z&?0o9m5GV@?Ix`gB=P%0zrDGj|%y}cc7>Mb)H}lLEx|=3NGAYQ&b|e z1|7N=cpxc{6&3=K>zzT8g!Z`y0O`~Lw|gqXae|#p1XkATCSTr3*ttx1bOeE%z-jxH z9<=9F0cR?(J%Gmf)KQL5CI_w&Axb*H6;4P%Ru5}9reL9gdUV+E9stLmi+NXH-h2S- zVzAFE3Va$q9fGGbGBUhYUNNQc+N!4?G|I`y6mMH2Y&hUzU(Ul=NeLTzE0RIEAP;oV z9-n&W#VpXCKyX0d80ZRX0EI0qEMBLk$^$7u`z292$!*b(2YPGdfW=A=i7|8q6jRgq zMH(XuA|E<{RT;1vZ;cn>0%vYsGW!h&zdP{8z<+#_7sz46%a`at0}y=;(RT%fg;zk3 z@%I-6+y{sCe_{!gKGI>|e{s@pl+9aCdg^2ff**phGBPNT&fj3I47@`{6$|_Wwjffy zsL}{W(x5D3J5qq8&+{BC@Ih2QGA%L zg&~B<%oiY>Ks|_y#^)4MI1z)i2`4EA#0ao>nt`VWp)DXD;}a8y8&xndFrbxA4g#c# zh>hI3Fz)m~m4sA0prxq-;2fx1FCl^&{}w~;8eGAg;y9*kzXXspW#g!n zR8{eyWMN@trEX;Oq0msb&LLHpRt?HaPbndw0*;<^N|()3Be?{VEC?_uU<^SX|Hl+< zI1KD%hRsP3`Vg&&E>5HqR4z;$9LSs+>gtkKR*W#-4pLZi%O5xbaC(sv6C(UbN=ad2 zVQEf100R99M31LVjbTvDki-6J$4h?w#*I`_Uw%jzNSPV%LNbFw5*~bFNYU_gkar6C z+Nfd^%2+M;d2+8`zmB*cQ+TX#pe}($Dg5U3YrOgI-w|yNjwzxI!yKG_IOaxGyZYtY z@Lr*t4$wqI&4;fr;y4JPDJoGb_V6?nMy za0-_nsPu#+Bmyj>CY+o;M>e1htGKyw11(Nz8UzSaC(3?) zB2d|xn4C1_PluEZvODBe3@j{*iT7#{8ESjt4G0(&?{RY{z&$2}9c$?60hhpx%v}Q7 z2Q?YUwU&@2AX0+*xV|m}V2m+wJD9Eqe2GxcLjU>mr_w>e%g|6b*@}?0rt2KYSPjN!noXVEfX{uC&eP(J(u^*2Tjpg!(`L$LqIAmd_3guy~>8 zKS)8j1yM&J@qpl#A?y(e zwH*kjLlauCcZj4a#zk24jZuO?CX=u{OMGy&y}i}GGYbM98TtrKTBk8QUz=z(BRbD z*cRKMf30x?8}V(~ygQ|nJ{_AkusJ3-RmKF;N1&AV45~-qfc<@Rw1%t&=)WLALn2~K z#6(9&Kl1S}mG}v~=-3-VBVS(?8)a~hnQa|T42Z};Ibj$g^$$<<7z&#}hV~u6p<=Xa9Q9=AyPVJh+QDLx8 zkfJHn>t?gSi$-wg&e)1)9@KxKm<>v6?d1`iNYFf>+@n1wi`QLk7vNM^HvwJ! z(emLN5BCI|+6iSkEVyeMYYa*!bEkIGQJaAb2*D&)P^4j}5|ERZT67n)4CLsZ&!m$9@c7;-W{C_Ou zHXtG->O$OUD06cdKe!vm*o=pc{*u2)({`u|Bn?OkTD6tC>?70X3nF$FB!t2VyEZc#aHoIXo(W6ln76qn>#OETD2$mjPlEs zt4E#e7P4yb$15$pT>nv{ZqClXX&pDLCdujF0Fld9^{Kl?E)&h|-+u(Gnbp#V{ons* zM~@x=8v4Kg&tpOm4xW(snZMhz#faTB6O;(+-`NV&*q`>iEad9vkOQ~zuDKx^Lzki>4 zKKpV-E(0r|%WR2)3$tLY$T46tVxxkEH#9b`bFnWBnRuu1drz>2hYqp2Nw!f!=R-=r z04ysbBV+YCgZE~8BG;imTZlr=I>(D9jWBsoM7pq(jR`@s2GC~cZ}_Y}(B#Yo`VU5_ zh(cd}{20hiqx2yw>#@?RGlywut)w8G{p4os8mnp{YAgy-eHS!Z zMz9~fX(gz9cKG?dt*+kuMNbeh4ITe`Es;T}MyOLQuyvt|2IXF=6Eyr(2Fiyym+sjO zC+^IcG)Y2~SOSjA?~)82JXmPADd!#M-I{X=Vx1&M{1?@qx3@%ALFGOh#YCfT-)x7) zXO?%T)8+a`oXW_krIn>0kDYuL+D)Vha$@t7@v6Wk?ciK??2uWRdD_dgVyC}<9fI1% zE57x+LqF3JTt}eoaSB$P7xl2DqXAjvi-UJDA5DF zeJfh1?Ck6YCiFCPb-U45o$Yh^O;KH*L##v6>NO=4MwNLHJ)x9VkhB4hZd$}4HF@Jz z(F@?ja{SawFRwUl0-Rl6?4c~QYdl}i;4dO^*&h45_SVgYwI8|ZyQ6Thp#Rz(I%>>C zF6}RU1a8$I#SBID)wCYrxieO*=uh3}l=v?&V*xr0QH0FDIID~#w?^mf^M_{6Gt++8 zp+?vZWDI_sPM=YH(M`mfIi_9UO@P*^9O(Qf@T5N&R?+LK0WTPfB^NeV^xp`NS>{%n_}>Z5-?`<%K;mI z)Mii#iuU7VaF`j2Q>x8VPcz{uAv{Hr*S^zmBV%L<3n!p?#o?Hi?YoVGPW3l_(*)O9 z#e4xP=XL9CNUjqW;ycRSzKcI^+h{`7RW ze^(6=T^k@w&68Y*Sl;*5nv0B$jZJ#CH2QK(uGWPwF;4vJTr?5{-vlsaB>%Hd6)yYP zZ2YpYYB@?$;gOBbfkO4>J`)jEewGZd&KGaD>sd|tZhIcoKFIC%YNwyFb>S$F#hGR) zHYE-!-5_A1qSBY^KoOt;;9724Mx4xhkewa=KJ;G$D11pn*Ad5agW48) z-lpfLW)o`2ZPad}_<jA$KQ0Sbbu;;;Dn8;Tc zLZhsS9m2VRM_5&qU~eua%Ju7MIJT^}=SMCeJkcgF77hnGwq# ziXI9AYwy(aeI`x}5xT&TZB0R7tv6TS-$?J$W4N6J?E#vhL%_&pX59c>S)$?TUAuMD z+49?+!lyf`!`7eDh{d2ki-HZoO79YtH8nM_Z!&uts9kZ$SZ#G(orvO1=6{n(d@H0N z)2B^?@ii&#rm8xN@Qs?W{L!JlLN)|4Z)If#FCV(CxhX@dfi<305VK0qIRym;aAr(n z2+bRn7{zaCMTIf_0O%nFe))$F1@Cqyz%eth;QGCKk;h{CY~t_v>(>v$5FllnOh3qr z6!WT5(y}5>j~>|Y3#9?2%IOJPPO{BJX$S@hu}GZh1XoH{w@!3VD=E1%eeQinT_Fo1 zO4hXMzz5Muw9Iqh{Ip(tqi6;V41(#MZ+4GgT`fE>2v}90cygkzMpChZW)@l}{7n|h zo1ciPQ1n=aODUw-WP#~yK>L{MM077g*@oEhN}*UhO}$0x-2kdmj>_3|ew;u_4d5=59;p4|20zL8l8rs?&Ns(H6UnAqx(9n>R zlT#l$bT4^;Um@NHYk+Pq=_>-hiA_Jx7i+wu&APxUoc%iKI59(q4wafY#|e2{Wu?8q z?VMBU&5~}77(f0rl-s4OlJi17s z)V*V89LJEQb|;QB!;|{+s^R38<$IJmChCK#xLX zT3(z^B_7}}%(aIH&8nI}jpgV#luOXz{oiWm5Xf8$Iyb?hqfoR=z6g&A-#P2d_#nX5 zK+#I?v)3LvbUAHH!_V>qRkzr^EhD?G?`N1r*%V)x!{R9i;ry51>#Wp8Pi3C~(*cYr zI`a+&2Nze%-9>mbb-(Ikkw}04_;es9CMGe8ntsNr58*teZWMl;nr5ZdZjM4@J;nD<3&WU=DGc#8r-2u8h|2Ue+ zPKqgX>Iu%WmN$56d%dWL0Qlny^Uh6fgDQR30H5CvfpdaDAI!q*5Brw#-~=5(izX06 z==!aQ5cBI@M_LT=SwBMQv7Q8QdyfM)Z@06HTdjk}b#E_}abW4z*PAllzewp0^|%}g0U#>8u*;M(J_BasbLi6;%LvcDy`-R{DG`(3 zjTP~@vM6?+%i7vY*RRi=eNUEU;G}#xE@GSO)>DVjH8Oehlf`t(Jzy;s0f9CfcM(x9 zJDr|-K8=^DRm0HLyZ7%Km&9BKhD{&f*mFQz+bZ&^e9`69E2K6o|I5s3}T!?lFHB}>SWxG-bMvu!c zCmIJ%H@%yF|h%FUXUb=9Bq)NUQKrH$k z4$HLDd$9#XLnyihcm7}uDlIXC#cV}VauRsMid1hY8W@z)Pe?TM<;)|(fFjP*6YZ9v zp`qsP(2LJkUt{aLe|po{@zn3Fh>xBViNND>oWP_mgoVW>w5RmKTSP1@>V3~Yw4O$@ zWMJcR;ugb91}e%Vqxfm@gPGMI|NQz(8ff6Ga^rx&@+K zWS^1+3l>~onW5s>zK5VKuO0uzKV1-rob8j^OHnZm94oiOE9459r^if2K91a_=or1uP;^Xy6 zZ@D!U>u<+Byp@;1M*D@PJ~!*`%CGMpn_s&vs+Mgd|8_{`yK)`EP#7ljl7-R)u8(4P z10Kd8CzI|4)Uzr@k{)eQQ&yJ7+{HbCxpnC9FhAeC*TN`Gd7hh*v9S<+%gf747;zhl z7!@Gz;`9y;4pSAzOf^L{f-uy5|@;2KYmnZ-*aB~ ziHz}r72)fP2g7%>e4A*Cp+}D%B?V`)9dp0`08&RC8lJY1YIe)-o0b=8GuT`20NfU? z+Dcc34onpCXf-k>v#U0VSx0t-kR-yErdVo|WSP&w7GlZ~`vs#&3DG)reEzy4gL?qxe7+DLS z294bRZ*OeXAJ#G%U$6#1!nk%f0dY^l@Ycs)yEZgQ(G50`cNU)Zk?I-_7PfM(bd^Ap z2t8>V?Yoa&t9xp(LLLm*%B(XPybt8tNC$;}mK9(9H8Nz3+f-`_^#5+&;p+@J0q6;) zf<0Ij>S1GJGwbB2T`Wf`gVv*Dn(`wSrxO@jIHof`|%Ss^bZ1M7T*z{EVA7#jJn0aCNRh}4B-O@D3A)oTUZ z4H#w?zOcBqwDjyP1%NtHNKzCF=#*CpHA7d;1D(Y5!Rud+(9%T-K4v|g{!a@q(kwjo zv2Q%P7KM8@YhY$#6vk=;f{S>J+cu0VfA=ou-ANWH|IuuFJuncj@M6Ih5`h7N8f{9h z>x;e3MOQH7zf$3td(G=(guQUX_4}r72ggLSzQ-ec#pCv*Y@H}IC=3W9LhWackD|5K6rgHJq z5_aykafGj(9)#^zK#6QgM0VNXDkrR&I_LR=g*(*qetc! z78W{(JXl%=ebz@yOK>!EX_)ez;YpI_EFuOn(E@AS}Q@t$O-w4{fbwxhHL4)iy-@!H9FV0EbPt6NrIB0fAn zC%rM{O>LOPrI)dm17ivt17E7CtE- zN=`nFcw4D=?`@{}ROOym+yxkp-^yCOanEjT*aSfY4zpl>k&uoNf1#Zd_ay%N;Kc`b zW_?~q`~ZB;?pN_A_kyN8gI$!7g-&Z{4pv)id^_9z!u9LVYrR4!{VC-;5vYVbv+XOP z;7{$XS79ZV)t=}u%hj_ky&T=6Prikd(=f=A(mmR@=StVZv{AJQ!boV(3C=wxY~FCH zuK0}Yr8?t5Rql!1lt0HXizz5_O!sEmX=(H;rs)6)$e-wmCjYybIkN5i8 zv4{2ASW6M7tY`F=pulPOZ_s)-w{qsE`q2>r^a>d+g?mnxMT?Tyi^*|}2~!+?s8eM% z)3VdAu0&f>rOO$d$OiO^T(-YXkPZ z4ef?{EPCQQn-=6j_Ae;dWEZhdbqJ#ch|xX!X0iUVnC*Wc<}5i)PE1tfwqDvCFcwI4 z)Q9eLjlj~krl;OUbN2Y32p=CGhc-Uw0^l(`{{ZDT2NeDN1`H6u zQekUzs9&T5MAo>3q2e_nW3$=%YeiC!4COA3%=HydkGIQorK4E)i=Y3=Pt}awoaFxD zu8?a{73O%l;j-cMr0xxvH)U5(rc0i|5}lwe5t2HlHu~u6ztSoV2@cKx^2r4po*h&3 z;r*>P6v3O0%&8|_eug%;a!KiWMGT79dSIRWQK|#O# za~>mb zF^yUoSHlzoa|q|AUlPpekgPnfA`8$>G4(!I+~52ZFOPW|Irw7D*$NDN05B3Ju~&_IxN1P#w#t!}k; z1tP(+rWaz^YG9e{vhf1G@#4n#2=f1|=FB{Qc@lM|*z)V7|5 zbUceGZC$e8w-vd2O}|wF`~EVJdBaoh4rD!gq&{X$4^F(K8zyAF#R{YGo^Kk-TU2?- zBt{#f@OcmUna)d~`eywB#i7?#_8jA+AS+E;nk%ggdGL+m6b0dt=0A6u&qEa2%MDFN zw|`oHoiE_eKDtn_-n|GaD7(aeK^78Wq$}0LJh6yaKR7pMe-@8GIeKi0LnS?@e#E21y zmQWBqLbPeIR>-izkr10k6o!L}- z4spXMLoRx2qy~L0ii%?8pOq-UPo&BX_ zkWM7&JU3jK{JR{ntb?}!6O2fI&Ro8%NhTvMqoBN8L8-(hxL4BLv_9!870m`z%t-eu zh#T{yRc>wm%9Q6t7(}S9WusJto&@ep`Pfvu`l?*z@ei4^KrSnW+eY{Jux-TBWy^#U zngA_woRAHPnB3I(=OsG3nOcic%6;T@7(>lhyPgRd?{ye3G@D9_rj7obuv_k1GmUCI z+&pRkL^}+BXKGbOet2ONlu#51CeCe4j)@tGcr<#*dETn1EMwlWkb(EcOlFZ)%KN5@M9$ajvC5W5n79Q7 z3Qvb0aE>pNJ%hA_o6?Stcbq8@L0!l04CHa8lZ$BqJ%z%KUQYXp6>sS6HlM#G$3#V5 z_SC)I)6mVKtdmvoeZ`UxQ@fKUyVz05^7>uC6((M=frB3Z?fGOP(+!$9%3vwWS?T4K zm5)%U3qu?v2hr`OaWO(?L&-cF4g@uU=gW@>@v3d!^nB?M8>p&!9qE>kI0#1=l-=;q z?u*_tUM5san9(VZ&X@%Md#B-RI~o+BNzqB9$BtBDXU#V;n8Ln6mLY-NzRvdYta;sf z)MgWtAf25k85?}hf7~~hJP@IFDce4t%9JWHx^RMf++ZZb(V2^^q> z`d1r&0yCP1CG{^HVwu$v)~AACK)N<<)+|Sz8@88TW&@E9Fgf##8)J*ij7jr=oZ0xj z`mq=}pRieX<%7EHOd6Vc_GlTNtLqW_y z@YIBBc9WOUz^r6kR7^co-4ZiDby*W%ieZ~}-`LRcuJ~F$1pnFa{+N07$_-M$V!H%{ zj=UrWFL$~DDg!Xkbv&T~V_rKs_R55$S%Um)w(k>yQZl@-`^UU}%q$Z!rg(VNzc1;h zu;!6~*hH}?pnLpy3Bh@e6E>#Um;faU8($%p2KZJUY8##lTVWG*3FZla*^TRbd1u=; z2s3uZ^~KA7%=`8Gw`ikbwNjohgxHL78NFeNMSju>c(`uXNoI6(&sjRB{ zOh9A4GNJ(YEhg2jB&G6U@$s+Tm+kc1kD)@Rrjq7A+xGUJct%KQJ0>HuKrBqCQ9=`U z;DE`IKVw6X^$@(oP#+jBm61NG`k=wYO*}EG|x&Efg)3M*6?M*USWhp`MokoSv1@@e^ZO!hE1x_w{annqMW= zeZKr8Xte^aWd&t* zN~jI`k&so9hum>2M(kPJ_LH=j!Y&6#WuylgoiqkY9ObA;umQ-Y? za?TGF=FM%xbF03dOf6{lJkT|r6RTi5rj98D^(w6MlGYqJz( zq=bVb7~TihGFz>{x>kCMip9^n=OG8NmMR|deCuw@h^EKuifteE)zAP?*^g9C|G@ff zKC+p9Uz9@^4E~ezc1qa1`h>1~xlV^z{>UjPJfMO&9rv}JZ|T=dQAcO=CkOEdA(r~? z(3zXOYkySNp2i*=bWcuRzN+qHeeQ!Z`6VSGQqqdqQ{chJxX_1U|`KvB_jVs5XwKk~O$_^MlZHvg=v&;K#Q z$f&X8*hxL@@1ZeABOhALBEG#S(_5;cQKhWqd44o~ltyTiU&!iR0hO-9uR+{D<|-?m z#I|$#In^lN%-meL+B2!HVo0o_wxacf1gqK`X#*=vLYwY6$K6{QBc=amOyK(VN{ZPJ z-aa!lGCGW#N2d0O0Y|34bqKh;7!NHDR0*Dlu5X%!f@1K@b8{y}<&V>oV$AzkJlBwy zo$Yh{csGeqcP|)x?0#2tJCp8RKNAqpuXFeAmDMqprlwNixr5hDF_Jm0(2OaRj0w^CFLLU}dT{ZS8HOfjs*MQx^D%KW|n+7k>;+$8wPJ$zB* z!gJ+8VV2zUOMCisX4Q>=0DJEx7A8D1)4|6Wn3DC5F_@s|_{tlEZCAKPVstNk7YSxv zKDiD%v1g+{2-DgXkO_pn9a9FwuzBag!`lhB9flbbhlch%UhHhl1nceQrcDx2-Y#9b z)Jk{z03LF?mS=H=6qjm0>YpxCggWs3lVi!jA=5PW?c4Y0*)#XZ7bz5DBY;r&)uDBR zj?G{kT$vRu@rDaqHEo(vz76|bP)LYC@r>hcd(kxE|5f$ke|Pe=zWxEhSpCT3=S4+( zv7cFj1hakhuE;*7U7(*ogW{Dk662e(a=T4bI-1>9DK^?3UPkU`YKMz5huwX>utvbG z)Cuu-&s3_wJN(2yXcuD0$(>}-*LER2`eUh-IEuI8-SSr62?uj%Bt_Q*RU&4~ARYt} zo`X8>>WNQ`OpP{e8YengG3agY=(q#WA!=*=5QZzeyCzswDeZcsfIAy!)XKA=B;KHU z;%K0$P;|_S-Op7l?#@W=XDZdV3}UsCz=zt^79}tTwd4LVv0xvxEZ9r)u3TqgpWVup zqOBA5R1awod{O(ps`0!svtOcCfuk-Mhf*^i|M^r&gDeDupJfDP^+++-Lzl~Ug|_Ri zvs_NliZ~XeIma#Iu=x#07cqR<#p=xrF*2Xd4MFUD3FLHl$|gg0DTR9N?LW>;KuM74 z%nO`mWF*~X{WvslkK6isvtr6nSlov>@+QljyMDcs7^VPU7``TNs2Fgh86-&ga+pNo z@=&SiT?CAUy;*2-vMSq0%&rRysaKA=RG0v(ZN*ePApHfcz<}R&7`K4HJfL85Y52L0 zZc-xt8Y%cr)G3JY5qfq(guVVrCutRZ{Z*xq6!x?f#(wvdWb@vlR$h?lhdN4mXzQrqo%TN zYSrOgvRznmh?QTw@P*Q#km$lVHm24R7tiJZ=(2KN=fi`2CaWL$B0DS8=Pi2f9RwjE zrQvLcj(CmThnqdX+*>y`^t5Ty0K&DkH*~gcW!fb>FV7E8Q*NLPT1Ou(Dp5{KLWOP- z@6rb&ki8I^yTbbum-mZkRNr&(F?mX-opLs)AK61V{ zTX$AaFAi^&l$dC>e@GX3s)G)qQ)lRXKh0QEp@xdxa-AOHcqCfXrED$%2Qb#{!y1F$ zDFvyJmY@e9k|$2<;4i&0Cc${|AYd@w0}-SR`raLJadAdnd9?LATCQyfsf&(XR0a}OtIhPus*te6i zviK$9XDM8#GCgZ)X(^GcjOoGD=Gz&&WVLvONNZW@vLG)Hd2ouodSxVK2Lx2^Zi$19 zhrx2E?o-*x_zEKRjyxVQbq#R=Y2$zEmhP3A7u;BYgfFowB?nKO2mo-1d|qqJGhzLs z-B;|=MU;C;=F{@?1D(PGB0J;xMbFLbhmv2%-urEvz6RpaV~DVc=FLtg$S&IAg4U5D z8jeXcOnTpI{olEcVRBb|n5ybt5DxKS%%jc-I~?L6E_SI1+KspYGxf(GCbcJ%PpUn~ z@khks@nenW&+pvSP%%*qyGn#5TuCeqJN4+% zHmSJ7sSH{FduhL7dOJ8dJz&^s`1)F_28J0q&&73n-9Yl%kOtY=>}H;t2wjNGM{iCYt2{d~Y#aZ%{a8aj6D7)D9qbI08xL`x)tKlj27wCC}$Px6ZZz%z&1vv)pd2G znKf&M@NGl~&#prtsjEsv$4kS0x6I|+*o&-L@SxKpxo_v;Ew_I;OGE=^TFRhCjR6}u ztWLYTuDgfFIb_MeZFiR)Fz{nOrL`D4_v^}QtnaORN({dXah$gPoB>CcaFv%MBX3{c zQ_fY5x<2TFmN!pKc0aNK@`-5ue$to<8%vQQ9b#4RtIu2~UMgBVUTzN_WA)-PiI1QHJo zz&rM=L3VS; zq#P>~A+Asj|U- zP9x|fBZVS!+RT|ryUFT`^|m0Xj~Jmq9T)O&PiO#eBRisbu(?=sjjdbON}?t}t4P=G zV~bHIiX#_Bsbnk^%lC4#tG=oTD|6;#PKh|IJVg;H%!k%`Zq(SJAKU!*<1@mP#N;(L zdA}P}8JE44+D9X_rx~GF45x8of&PKV%WtUlOqchSBv^GY>?Ap@@GFj#M@6#6Qd_)& z?Jcjs`X;0@5}3;-%eu<9MqQ!?>0|T$DtG()lBj5?qI}fl4nAIv+VRAMEn`~>3>g`T zgvco}wK!dZ0bVMA9qMwN9Fx8(WXpgrU^v)?PN?tdxPTQ zuz6V4Nz4v!XYEdb|au zNvZEf_F!0X^}gH&jZbMvl5&f6(Ay6xvvBe?);CBsfwY29rn`-O&1oar06WFdbq zzN9<W+2MgQw8FOtn%F61qJGAZur7z?KMubC_h+rnZr2kusL&=oF%JSRBl)4IbAY;sJ zDUaWZO(?!(Wm^KD`yv@bQ40YvDzvOfq0E49nrW@__xEOdr?tdwty9RcDLMo~fFgyt z6^sR@TX*}v?>cudQ6ld6=YqjqA#V4goItcEW{Kwo{=G7zQD;TA36(l``?lI&gkTDl zFGYDy|7^xtq{&D6z}f17vCd3rcIM8*caD z>C<}wa+Wf*G*|Oy^ufxF>bo_7`wvd(ey`*IX#tKL*^U%NY$m2nh7B8Lzh=$$jFm?c zjmDaAqFxvI)*xb>O&Y+|+YD=^VEPTB>OWEW_b{Gh`!PTAfI|v)KmtE{?@CKSz>&K{ zP&2)=EY?!k&Ir6s#B*Wr_~Hd6ZJ5@+%EUf$t^NWV!!fP^s5cOiZMlx~YNJteJ>1>x zfTe#jSa^ubBcj}ljpc1-drY~q;4YOn2SbJ{n0}(V8A}gBqNEC&l zxOd%EsWE!gs8U4e;>eA4|32#xIPN)^`{`|H3;JC#ft+(#S05D6XOKC9tM5DS~ql)rotN`zY zwwV$}B3cDuS|zeF>Q=)Dv&rY?ey;5ix~Jc64a!JI-JYNZ2v>FzJ-a|S*gHEvgc|au z;!+hp_QK>KdRPadQa7Xy7d+bVJg$wHAM~1PmT@}<5E<-9gfZ50D$h#J6lVE z1cPVazq_*?2I~Wau0Vg?TNz4#FSgC~wyaWw>?6!el@ug6QlA*TrrUpQ8Br4C?=6yB zL()8}5Bz6HKUzBWzytjJKEolGYj6A2j>CscEiHFrPAuiCUJA1vm^h0Ko*I7*C#8O? z;tIb|=PaX5q{#3PB?|;qgMXsjBrR}3e3t# zX7pa@BcA8x_V>7A)0qU=pKVDLho5F;rNeJ3{Ov>;WG#oEonmi)IVVif z`iG3+B%g_9eva7O8Lg6W~=&5}ibp;|_#txHxGL72LeQsqXjq zIV3mYo>A_!0kVK;7rtzj)z!2e8m2G7|Q8Aeki9Eacu zI!#d&^qu4H^mo`S8&6A|3 zZ>j71)q{`Rb&i`HHg5^OuHE&VPv`VkEWXbAf@s-$$~mzu2?=H2tC&>>a#kp2dl4nY zSPe$*(h?zkshFaxk@%f0fAG*DA4+{`iKv;lnwa$h0vy$HUqO(aLN_E~TcbAjU4*WYHhHfbPFK7vS9TT{UsUR7{gIr!KL^ZbL zi&hdN({}@6^sc`cx$pAj)qeN-%&?YkY^INyIdjiQndMO%Lz}Qz8LRDyfl!)5>hl)!Kl%n^ayxcS5fP^(7pW1Wv8@<#pxq7?{;(>Ffi?G{v@sP zoeKvoiZEkH6&y_BBD>wFp8;yKQ!zWSr8+SGzdrN#bf;e3u9cYXxR-u)_=@H2-`?G_ ze2Jedn6M5@iLiDAildM@zk9!wCpStidy9 z_Ctcim0vR(!a)83x&_Xxg-#OSigTd?_s{C-gN~Bw@r3?5jlENsg{+}P5TXuYO(67a zQORHB?`;hIctY;%`IvTXzGj_$H>opc7yap=2cH=y&*}3;VZT&G0o+6=9spR={Z^D>NxLL$q+HIy72WE3>i9xo<#i#$Kez-c|gi4|5 z0*AZLci5o`<uAt5xcW3V4cGK@Q>~#^jr%j*!VMOHR%W{l)QFp>|xqLsmUis*$SpyLC zfVpEAZsWdKLfnVKUV@f`94ftWr-q_+;{Hsn)0*MNVOP4g?jL(XcWk$|hqgKwu2r;d zC%Q|_Sz1xQNGhwU{voq4(jle|qB@>Q1%V}N$dt_E+H1&b0 zl~qySYqS_3dw&0%6ZthcB_$d>nB7F^4=lYF6Vn;!eFqPNID=))xp~$_Qx6e6)zu|1 zrsnSql(JLvoNtAm&DrtwWViNeT>?(6-M#b9f$x_>rn&Fz(O#BK9dBjSZHgk_4nmi9 zr>R~WT;MD-OD!9?zFkYtF58J}0OzTHI?1fE*tS)oy<0=55SSTdxTFVSGYgz`883&3 z?GSit45)^1)FPDjU13Rnrq<(Lh41It8#j~?L9hWV&F% z4q#UdF1oTt1)#=W2cM8_VKW3}&IRh*mLLs5kMHsQ5syehwJC}~2#a#I40EY0?E4_A zpXrH}uzRg>C`J*)q*-st=WyFbc`o@CW{3#my!ntmOgoC!mh}|XpzR-UTD5~>hEwn> zkIGSBXF9B_tF+iVM`63aU&Oj;mc_~^wtbHYDYI?lrusIe{4we>g>1;h zE`coq-}8m3Kx`t8CuT~a@!g-At-S%kL`^1+*#HhV9B`!1gbBj4=Pq|#3e$a_p2(Lr zMIg5LQD6%*o-wOv6fB}{=8>Kl@1-L`!S`RELfG9}EktIvL_@9>5+ja6@Mb1PP$r;O zsNp^LuU@;>7?6;hI|80uP{%<2tYpLa^N-B5U_w@$($h-J^zMKn!bF154CcpsdM#-!)w=bsM?doSN?7Et+*%E=6il>WW_515x9k6srb_tkIU-4Nq>br~SxzU8q)fxG&yN@XvS#y5Mlq2o z^rlFKZ--aoH~)tmGV|rnIBz-UJW$WO9#DaPM)D&BK%#y{T8tgU4k$+?l`Rhj<*gBO zAW@&@cbUR^vO|j_lqjO`<)#H)JjMIKgx_+wEvJgk3U8#qH;o|wkSDs>!|f0!JrUr< zLvf+t)jT$X25R3_w}d-z*BWD6@P|;Tso1&UVa!4kZl@?PtnU7%C?%Lk1K^{M!c27v z$`qV&vU76YSs9e{k|8%xKO!FQKu4t&)ql4JWbiH?OQ*92vFV5#pIY4_0AOK;EG}U1V0kV;1X}7unsmYa6%|?G zh$15qkWru;Rq(iqGHlo|-BBVsk=eurQgMp5Q6vb8d96Bqm+zTz*iI@4yGn^2z^mvx zg<^w{AdcsS256Ep>;xK8eA^_ZVDGUZ=7MFLN=-{;><6VI*g=+#_;j3vaKVD9*pHB^ zt0-(La+%Fxgta4=Ak@LUEm${9eYG2vf!K@;KEE6xN`7D#)Vsg3}arF{KG)8ooh^*DgzE`qc}+0s#JK&T)i>d_3l1 znTyr%e#jy23aQEY>;Q1yRAyQZjQ=VpgdmJ`+Ukak}E1#Vxdog(%znlC{eqQaRs#3C_3|zASbLozwEJXxLXhvpVUjDD0x-W;lwcA&v$me@vw9<|5mc^ zfy2Es_f}{Qj<~nuoZ__o3PuM*y3LsKNx3N?@&Yw2q5wIzq?Cm72hiI+T(OtyKoz~0 zNgX>_J23$0!W7bv69)ug2nSLw&SzlBS?R7bp-pdY$ZEDjon`RdmpKN})`=r!MJt2l zbbo%Pdb3rRDHS_wiHc&UGgj~7EcxW3FXU?&u(j{0=j`6|#5l;3ckfC=ni~d^^;#%m z{*FE{bNFqNHs5q##4rE>eg45T1 zTRx07qR)uea@#(=*|fg1^=?4wB@DM_-qHs15F9p3TyUT=ZQ7J0%>59ZP>qx+ddWRm z;Pj;k;|1`$@tHB*u^6co2hT7HD~z#g74rs?79yUq_{2Ppz~?wtp$sYC`nDf|eZ+J; zlkoE5M>)KRwyu1$6$uk`TI?JVL%_$?q6E9lh*U*ue{tHlmZ5>m_d0-4S>oQ8*K49g zE1gd4{-Aq}f;%0&BLGwDqy}rN4_U3)ae8B0U|Q+D^x%wr!_*4APGIvC(M;38{Admx zDp+8*)=7+1F)9q*DO#2`Y8xcr@gxAPC0iCOI9ixLQe_{?l!psDW<%k$gPr8;j%Q~K zlJdKaBg=Yzug-e<^ke;I-0?rHyClg@I9WJ0`p2{$W5*_4(0cE;e7(LX{I4eJb_xD^ z@A~~t{igOjS2wru+mT(rOF^VNg4_hxnS*H3l7Kx5Lp_1Ipo~Z1;o|j%AS2dKX{lYD z;g&e?6Y{PGg%jEu=X6RF&^H{>Who7)Y+WO#eya5;Ny*-{KA3wH&=##2uhZ}O^XF=A z*VX0XKU_QoX}juFy*_{WVhBJ? zMOxdwF3UPLe|9ICpMU=J9X|Z?)jOAJ_c<57el4&asmRW=D=N)QC;feBu(IQFU_c^P-i8tG)XA z^^;jrb-DY7)y4itjkc^~>hvwAmb!i48)q?8^bUl9G1M95Yq$OB$=gP(Q~ou%_7@UJ z`E7p+ORUt!t)EbJ#y_!{DgLKDPB)_-`N`>N{y1KM&|poeL3b{@T?%I#!Xz)5{tgfh z^=jtz+Y~pH3l#0Q<8rI19hfeAzw{qHie{F8WRjWL@wz#Q&YnrdUfF`*EP-yuz-=%F zuQ3zEQ{4F9Q$&bLT*1r0<$DCzEe^qhfD3M;orR@K3W-`3mXU=>1{vno;gWz*s zbi+a#QBIFyM0lb`GuYc}TsMd}*My=mYli_+il=H9lTh1kU9IZBF8W&WkLz}-L4@&m zsJo00v{Oo9m8=`LP2M-v>lm3t1?4KxnFOH|3xsZ7xO#!Gb{}Qm39OQ2#K>x?j?I+? zWA(y{c{E#T^ZO1N(oS-^@ssv9%lv;>%P7vM2|sf}OoH{G$`1FWLqG13OMSh)l?99=CS1z_!W}g4(JtOQcPgfi$vjnzV$Z!|}6PCF86-U_pA}P?Ah!aLe zsmu<^EN*O|krKKq@+5{J>5Ru0`4tzh-xZ8y<4dpgh#y>Ug^vkA#mCXh*UZ)&NY8N? zO=PAJ9*)9wLRR?c`GV7a(0?#dUU~r-CQXivL?44O;Gp(<9<(~2UFmq}B>{%^EDbzT zh|Dk#$c%N{swE3CbKn_Cbk=15ZQhTAc% zU>-Y1pt`HfC3!hH-^SK5Aiu*bT)5>m<2@P*lAXW!Pp=MbIBJiCQvFVKIqVtk@s`fc)x1uJhYiB>1m8x6Duv4we8^|uYwosR z;L~8AAM{h3#$Q5^DZD4pfE1t6W7D%SKygyZL7dXGOKlnXh^@DuwmiFY$3_2d%qbZ54T)}{*$2zIv>$E@LJxoRxxOtx@b|*$Wmc;iNmxUWxPNsz=9^x zdVsD!M~zFs=E%SEWP?SE771GsK+`Ybmg7*KgldLfjqJ**D1Vw^d}w{B?68_-JLABI ztTYCAuvYm8^9^Bi1U5}}7Q%hhh*XCFEaE&E$|eXsk(k9(z!N=5ri$SZG*l9A(NvMv zIU3fdz)@Jf3xpE~+OrW688w4F(T*XL>4WDipCAgagVZz+A5JAR-CeFzCW;BBbVrgf z;|=`r_ov$&0f)(jhyiqAfB?>MIu@2Jl(0>*7cHQ0j0{ak_*K;yhO#ExWN8*`WvJB9 z0Rv>AS%mhC7xtHqsP?>u%#Gq)6md7>;wDqKfutiHF^_!+L?pCzqAZ{A>s@C-GJ;{z zbAyE5Kiq$2r(V4jB*M`q8#om?E&kuFc(~me8^MYV{2zW)BsbpEKVkFAu+W-fY596# zL`cBzK&?}~5(Zv1otN!>ZhG1Y{ZaBud~D_gPLW2RE?8dFbm9Q8%`~4UFiRGM5%igW zuv{{Yn;T1-_t97^gK{E3Xa2f;;erfS*gIgN-)yd%4W8Iaf*XWyNMrS?pQNoXx#qSa zCNTMfaZZ~#Artm7F`D}FWoP~i1n2R>+-hM`E{v=|{>ni~Cxhg&5-Dc4!>=-fVyG1; z+F-B|k3VV{@wUiZsjbDdn=pw+#i=o3gd)ih`c5eEOidNp*CX&z5_#bE?V{e0h0_NA zUHR8h3?isKPdra8SX`mq<@N!-38@DZt$?G@SZpeG(IUGcWQM6vv{U$tIf`TmaX;(d zjpb*6GAP1@Wrt|W$i4#0(%elELHUyzjh;xr85|NPfU38EcCV7wN5%Ax0(e2N2}?74 zYr_W7fhHeEAqwcNWq}sH_ch&dAU4u)Q|7H>$@mSL^XBz!+{B=bFw1A&$>>l6J7 z0Hv5W{wF*a>l;;}*~UyGxGo!BJJ@MCLO{fZhtLI3izYlX1{s!_?p^eMT7V5zS1zGj z5gVDyTl)0)FrXajcwWgv>5k*QnRXLJFy(}SS$a66HCqX7pr93m9E<5>$*NDgd*Z>Z zw)wN60Mlb)Ue+{(FBpt;NeV>|$}Brvu8@J>r{I3CN`D7J?L$ZtrxJet`uk2hTbMXJ zTCr^P$+l1aW-Cu{s_!9q^H8a0RK%b^nnDj!TJ6+W`#X1iPlRNGOea#a94lmFYlYW1 zoBP*e?Mgn2h9O)#z^^AFq$(QI?ky|0ocK@D{`>`HTrP~;Dz@Dwt0!t~mgl>SP z2E$IH0Qk%iGUBWWwjKt5f%(ESNsQ5Dd7pkV=eyw0BvcttUjnD(^<5oBTlL7 zBEPdv!;rBTvE}g9H9Vh))W+1gQ!&({o3^SF z$wZuNhM#+%@#7nOl_!Wk`pMtw$D8As1;9ZRseQSDgP4G=V@;N&bGXc1*ZDZomIXksH;zw#_&fE(FW%}N??Rf0Q zk3C1+moc&=Y}7;2IhmUSbDq@jv?pD9DbCCj-O`i{V+MU%WX2RSWGTX@xNl!qM@Pp4 z2Y(`w)K^S%_~?FuBMSV;_^|~ep7mkfC1F-ZU6l8u~LOm?!&CBHgh8V z$P0Hk`}bK*)t^267Z&KW#rK>Iy+_l{Wi`T6Hs6{>HI#HJQ5ifypfa6sp?xtBZj{@@=}UY_8E zoDI$G-2Z<5&;>M8d6Rd2R+oNwapy9Z&7JfP2(~4(XNMMz7M$@8$)qbs`;LF^eKTIN zcUs%+QGv3p{=6VB{ZG7FeDJ2);C|^csY?;w%(%0#q)2N1vT=!y`-g0G4pL7oG2hb% zj_qWp9iP?LK3dWK12t4Y<-?ZY1SF5srmi(9nlM7D0}|zeJ_ zJZH9agR9(&&c2Gh-YS?ltIwpuH2P0{>pW|4n5xum%PUVS^ON0G9<8`B#B)N>tVv6c zPJGyL-z4{dj>+{Whj@yfPUAnlyLfaShFizZ>d|B0yAzV1J;uKZY*F%7j&BL;T-Mbu zIhyO{Tj~#Jzi&r&dT04x#};2{(H^@SwD9VqB)dZ8OuLl1#5@1igjjQXc_VbwwGB3F zofE9KrsYP!VK~PnZJDJND4p6m1k`I|PUV~*V`L0nn#TN4E&lYwRn8Zt>|t)QQGUQb zT9ap;=;(avgm?UK+orI*p{-)MNI%&u?|Ac zR`l_s2+P1|J0C1vHztzSf`V}=C8}~mt2Y^l72Cg0mb^to$$@`z2R|sGI=A)nye+V}5wmNb2j z+feG$Myva)Pv95ggmiotHugGi7A_(#8vnMP2iReMBm(qp(c+5RAfHy%t8T#zs)a2E z%nkHVV>wjy{0l`LY-wti9Z*Nsb+6_p=%^^v_WtPsee{AMx~%-zP&gHT3k9N!`LfB&srDS7p_~wyhf4pXq)` z)%VZZnd!wn2DPvH;Fk;ZN0R?OcH+Nawp1d4#b^HA%t@tp1!KgRu2puO5)mQx!7-sK zeV6AW-R2;t>U}Jy-kQS9#a}mC1+1}1ui`S1zM+mLCos42&(i=u$uzgV*I^I)kKRV6z?>=5zb*>Pptr$C`ANo$_{LX;gm?m7P@O{Y=g`r zAt49YBMGY56HFCDkkLYp{aW}FX6LpH0tOUeyL-S&x9sHycj}tVraH0$f`r7%>svW9 zL>$yp_UThc5Yxhi*@xVB(cE)`t$BH*{@UxlX&G;nH=%Wkk)RsC5=K_PiOjl zgEe!e+tXZ3W0ekVBGj4onIK{)ajScZL7yY*q-P{XBkiJBljdZvb!weugpe+C85vp} z#@1_nkq^^V);YiUy&f=t;7vICyu~I#kMpp1GAC4V0_uj=LxVEa#Gw9Y;c)}Z8C?%t z-^$z+DEE>B(d2q4qtGe{h|rnoE%Mooq5%=pd=*)~>UIo71K6bFCKeorWUlcC14>3r zC52=~%+&+}D=ROTCgqQF+h2eyzL#_8DMHx|u3W*4{qY^93>Jm;zyOleWUskT&h@P71PkooO#+!m5cRNzIP#hhuJE6JzC+bIQ zt=+am0dwIP5^ferd5fCw%DX!Vi9>yMJBc}jM`F(cJe?jQ-P%ytrlU%$Z;oAGk!G6z zqj$RPrv3#Pz2x5M_?zBU{AakYolKWKZAvxm$6Q?&F=Nf1UQXGoqgPzj?E1+e=t^w4 z{s!een!7dAFZ?t5V5d$>!+q>p$@S^y)30B_@~o2HJ-(;^b8!Cce&c(O3@X_CBPnFd z3fZp($#+6N{pmZss^rcco_hEspWDgFRqQ40-+a!@x*f=gfvDMRU|L?H+c@}cp#!3d>ph-T)m~6%hIyDu>B(1apvB>Z{ zJ1(0xe1WOyIZ%p8Yfc^cMbo)LCn)E|3u;_8Gs|3Kh^#E#vGxtcc((@|C6Yw+ zM>+2Ye?R}{cJGW&KiW8LSigMlvchM~_LyNLDevIp_PBqbW}iNWKqzQk=7aHSCA?Ew z6w$nGyUms@DM(wl&LGkyF#>e#%$dj&Cr+GgkFq%r;CnHqNnhfVxyXpf*Wtf5-`1*7 zy;D;1{>)J017$z{0KSJY)F>M~lGlehWSf8I#1vd3Imu=O({EcwFMTj*Ro1g-3#Lx> z!&#%(QK6C8$Vt)*EG#xWS;li~*V)NMBB}J_1hBKiGP3tO+qw}kbrY;2&n{z{yn}z= z&nYiI&e$DFQ+wcP&u^&Obw-w(96D!RYfB_!2f|1|z) z@5jPVi*+#P()@X=IyT^5vzjv@6W<-4IcF@dEPlA@wKkHoJ>?Y?77|X^rDHE#{Qeh= zOnO&U<{QLA`neUU!s}$O7@A(`^vx4OSf%b(z27WLD0W7d$g#+?$mM_1+#nJ?piGC1 z7-7m`ALdr;c2Wjh!3bkU)zHnD1Wv^aHxHgr^Hj$7?d4Jum#aYW2gYG7a5gW`40fP( zFECScZvS~SLFw$$Mkvo%huo`Y6XqW#iE{g%FU0vjNWtbiJJ(LnN~yV3xIEh8UH!(< zuJ5K9e1ElUFe0O(u5+!du9@3-O%b!jJ#R`&p3fe!oqsCq^z$1$XwZlFuD&Ghd2krd zqxm9N|I34=P z%$M2O=XSPJK9jd*XtzCdzE@Eha#4dS6PU0yW-4Gz`FM#W)uPKssg`xPM=Ryqy!uZi z6DxnBwysAeVTzxT>)2qj4*#-U zUJZKE5=+^2;hjt#u8dg?m@$K>uUhw~kzb#U0Pme=lF1r=_ndx%22H2dH%tfoye5pq zapUF}IygJ$LEVks*0dR+&+y739*L}3Uhjm?)vvyKCi8;d@kY< zV9qo=TE1>fad33ZVOGW0tUXp0AF$nPx7n89OIdA_E-IjncBGkI+ss#25(6T zKM04K&oDx(sBqp78~YsZ_e@^a;nSzD(X(7;K8W$3!(%_mStPiI(Px~6=?ux+z$@Qy zP3*-}ti2a_%bv#+eS-Z$>&1&t5hWLLzW|%)wAyqn!|Dax{4(>&(}TCYT3c{q3Ye8) zc?pqvhKY$eLqLJHAmJwgNS?2Oc)E#`=h=+9InWO;K!|fW=OlH+osuZ3zj=V&mkiV- z5^LODd00!Iw_bB4CgAp}EH&{2VQ#KM*Pq;k`G!!@Td#Z2)n`ncNY43D9aRQ$zzh7= zz|-S6`uQl$ zo?}|qwO6lUr!u;IYxCz&9oqtp6x4Yb`l;1O@_p)171DwAi^?B@2M2#nWn5%l?qhuP z{$A@jO6*2~qffq9iVe|7R(H?nQyD%L`#dlQm)f!iBl(Qa&GO zu)3t9E0N5rC{pa*I|^%rd6aIbQB%5blGc0c<;MSJ(v79y(vXN5Uss~-g8(}t+rPXF(N@r21rU%v!%_`3isg)i)Eb43>el!oIYi1^KlER@> z)9NTvM|F&j`6UmNQfXPyE=wu%m>(MXy*}|b{JPlXa;eq#`}y4W`+nc=`+eW5JCbVA ze`@kg`26+dxl2?|76Ezv`R}BYaS2YV3tWZRUYq4>b%{{}(pD`tYB}gdmP5tHdS7E4 zP=#Hu1Ri_s7jHu4ueZ3_T2jEastcDdCtq6f&*>+Y6W1KQ%c}8s3+J)Q-y({7cV1;H z-)+cv6p z-I67T(0s4Da1%g29fu_6=0_A6hoPTSA3hVJ>G{D01BAx_%*|Q1uta4_&`5fx@mVjz zm|JBEVeHjMoJ^=g&IafAw6to>u!zZD=N34_{br(WRu5%Y%B5Rrmpt~k$M*gHa!X=e zds59a=Vb4DMk4FSU{_(Vr(Yer=?qz~pO10V7W7KJ$1mKKiI#3?iix3$?;Wjqm~QoI zM^{zrj?+H~3x@0tk~_Wjf7`CiA1ai3`21zr}_Pb)Ip+ zPFhvOXus7b0@SRYaFc(PuG7t>b)j~d(B+yGztu=MnFHox7Sna;VQY-la|S2cT=PbZ z_1t;$a!#H4QoW0S20WCX?8p7)mMFZ)FDFkg7t{9JDG~AsLt~f&Z;Lh2hk(n(DWh@@~{Tm+0g{CI+9`>-W z;L{3efI9E@k+H+d&7Y?=rM!nwImlGG8RK<5<=gO8gWHowFQkDxK5n*=*(ZEmKzTS8 z6ojNjg?X$adZ5Hu#11@FArd}ULwzJEP>wrzVa|3Uzc44E)3UJ?|b@hW!c zCzRK^pX|7>3xfb4=i49WWM+C=ZG4_T(K4YbKjud@839;ui1NW}f3MTT^r4zQhJ45; z6((i23Wbll|(SE`ya-51y^_Bju1eKF*HvJw&Fob#|_A3KcPTx5(3{M5?%jRz6`? zOFy=q`7bD~_iXRPKKjq!tF4W-qq|2=Z1y$(ya zV{=%0{dykyNPpbvYeCvI*RMyYCZYGZ%zwK7K`t#F(7x@yWdu zK}6F6*VxC7+B2?_r7koQOSg5uF3J&ZuskA-5p`rY ztvu&&dlG-jAdYq~-hABWK+Cqq6BBZsV;q`PE^`9|<$chyD}m{|IjdIb0Bgjwq~zo* zLgE*4bgVIAf{P+%_FM0~lR>?ZjcI)}y+5eZOn44ZK`Sn+^CKei(B&QigOr^;JFB?2 zPvVVx^TWfnY-iNLD!*%Hrag9S7R*%AAAj$zUvU-vUPsMr-%*%ZzYKwun@lKBPQo%+ z!W~5VyNK?1+4-PVoyp!r3HNzLbl%S`DIoqI4Sv(fctdF*g#}_Zz-Vl|h7wV(Ie*dh zq*U(TEgoW`a-h_eIXh|R&V!U?;UGYY)fu0C7I!?NF$c-#42-mxxY$fo4(eJF89Cs$ zRO<3h%Gg{;-34f4lIp+6S}Y9pGTavjf!;w#%aM(myR9pB>v|djG>f`+eC0kaKCp0w z$}_F}Jt|=qduY+9o?kIO>O<4kL*T}UlIFqkd?BZ;Ccdz?XL#~Oeuc@i%pTHOyP}5l zkq6dHhMX9?=ZoJ`MNHHt-fYt*$icsqPL8yqC6u5fsKU&ukW(z_1^E56`$A&`H^FK% z>?XZ2(FVDt14Rg6O%_hGKE6|{O_ukd5skf#LU9#i*|~mxIV1$kygoQOY=|M-`C*A8 zFkccQuF-|kICQwR^-(o1r9y@u|H{|Z2~pQ%JLM|(>Dh}7#)(FaKb8g0WEl1EJhv_* zGvn{i97LJ9j0Y4O0&?-msy58=coIUE#B<=nT47jwIxw6&UjCKN2E)15As9W_j^F1! ze%~eeXW?XYx4y^g+-V4sk^I$%{SZkey!tSm!eM#+(Vbsk{rUg=&s!&5Wg0)P*a}0W%FKnDXma>@Eu)!@u@O=RCQ7 z9vT|jlz*|Abm7?jCD78{|3|^zpI~F3Maa%GD}vWUaZz)S-kZwnYH9|pSy50AFbxhe z7crhZi0ECk9!P;+vqC~Lz*PNwdJ1<1c@FMD;z#u$E2~ewKeJeAqng0wAG`0;L)ayx z1h8LKJ4MsfB2KyCCe$c5*F42Ue83Bju^diWa#X(oM^FrJ&9ufw9m{y1bUP%uZ{6!< z!lZ(YLYS0$c}|*R+0&<%8`tA+%xCv@(2W8ahz;vxTFR^#>;zPpM`NYR{ffrjIod?Y|8Ddc@Ik*hg@3B4d%PfgZY8o02!{vOF zKhz`PmdZtkr5V-EXa3Q*f7<%P4`ZC(6){|vjt?Ng^-N?#-!T?RrQ^byo-?fr#Qlu> z{MfqiWPrV$m!uAwc@WcPCb7(U3dJrxyDpfoTMkTo*@-t?QUzrv(2ZU?(4VY>uc2dkbNH( z)Q={Kf@h}SD)t?SqN++XX+B+ZKkdNAuC?4F5)>)cm+-{TEIc^&X;WF#a^c*$O18V% zB%VhTGvXwBxozz1lIq&WxmXI#Y{`L9TJghd+g3v!({6at`JSdvV=Yb^oBYn(`4vvX zgvWs=qglkcl+H?X{QXCJ@wloO_IOp5wjO(aYGxbcZ!{Qyba7k`7aA zY2UPR+HloYUH5yVwB_ZD0*GMAyz9)L_Aci7Y&`N`V8SWsNkSlcY%N{B01nTTsm3u; zx2Q5|sazFBf7n5q$d{Qo(swss#s$Aabu-oR#)j6n2z6|N8wCpF4iR9#ij1tIJjr5n zV*nP~eFhAe;4(~Tl3=^qsAT3bvTaR{oJ#~hN=al}ut)c?Qxu{tI0@D~>}-fAf?I8d z2VytxEnm^N_i{@$#X=?$gWWWJwd7^mT0P@;RsglyjMXy1)Wt>scXYim49`qyBYJO^3D z?}twwIy42N*%@>;w7y2FPf1kKsM;KvgMgUyQls^gwr&AYm&Tc784HVed46ZmVItYh z^7f7gcEV&Kch=H2S;QRx5n;s6uR)f=e+Myvlce#u)p1zYmvY&nalb8`7v(5tppXC=^`cr-Gm@80s8GfCMzxo)5c z(#G&7jx&rS&f|`1-}a^M|Lmz6V=P8~2h)29QcB zgkP@Sm9@yG3%O3`>BRZ(PMBZkYJ)u~;csnMD! zay!1=S7FC>KyO`PVb89=1J*yTg~U)}ACZTL2<#m|Lph0i4L>Rwu)~LI$c!DJv)+nt z7UjAXw>mvD(^_JAbk8Y+ zgiB;yB>WbAQ5_}G+KC4YQB3-BJt}dOnBIuoX3(?;8P`gpvgE!ky8!(hxFqMhH-f3P zL62Il1((`5u}AUm+;6faXfFp6enwid%acN`ApOq+8=joFahutRW(RlSpF%}pDEsy1 zgP+sVJfKG9Ip&-Jej`+)g;VxNMR%UuyAdd}yW4s_4b1rM-~H%Ga+r5`!9k{>Jz?eK z!_>F-6J|DGa-^AIOP7YzA=G1{xvD-aIX~S}DEv9?O~KU^TfjH?^O;D7I=NJ`^yAuM zHSg_~dbxFrP<+GQ7>*qn3TE&s$03hWG#pJa6~!AXBZH)ADWDYvq_;#soYy%VRw7l2 zzoO4mVQTjF+rxk*P$0ucj)a+>&W?sEhL~#cXy)aazdumiKl6M<>5Z3tGiD1>QOc)= zb0j-B??X?*r{AYdy@Sv?l-D+;V8Q4vAUZQhUwlg$8oqk!tCX XV{v7Hr=t%@DB<-lAJ4qWL7V;u=(I2* literal 0 HcmV?d00001 diff --git a/src/modules/micrortps_bridge/throughput_test.md b/src/modules/micrortps_bridge/throughput_test.md new file mode 100644 index 0000000000..778bd6ccae --- /dev/null +++ b/src/modules/micrortps_bridge/throughput_test.md @@ -0,0 +1,87 @@ +# Micro RTPS Throughput Test + +This a simple test to measure the throughput of the bridge. Sending an receiving messages of the 256 bytes at the same time as fast as we can. + +We will create a new message for this test called **throughput_256.msg**, the content look like this: + + ``` text + uint8[256] data + ``` +We will create it next to the other *.msg* files in the folder *msg/*: + + ``` sh + $ cd /path/to/PX4/Firmware/msg + $ echo uint8[256] data > throughput_256.msg + ``` +Now, we register the new message adding it to the list of messages in the *msg/CMakeLists.txt* file: + + ``` cmake + ... + wind_estimate.msg + throughput_256.msg + ) + ... + ``` +And giving it a topic id, adding a line in the *Tools/message_id.py* script: + + ``` python + ... + 'wind_estimate': 94, + 'throughput_256': 95, + } + ... + ``` + +## Creating the code + +First at all, we need to disable the automatic generation in the PX4 compiling process setting the variable `GENERATE_RTPS_BRIDGE` to *off* inside the *.cmake* file for the target platform (*cmake/configs/*): + +```sh +set(GENERATE_RTPS_BRIDGE off) +``` + +And then generate the code: + + ``` sh + $ cd /path/to/PX4/Firmware + $ python Tools/generate_microRTPS_bridge.py --send msg/throughput_256.msg --receive msg/throughput_256.msg + ``` + +That generates and installs the PX4 side of the code (the client) in *src/modules/micrortps_bridge/micrortps_client* and the Fast RPS side (the agent) in *src/modules/micrortps_bridge/micrortps_agent*. + +Now, we have to modify the client to send a *throughput_256* message each time since nobody publish under this topic. In the file **src/modules/micrortps_bridge/micrortps_client/microRTPS_client.cpp** inside the *send* function the while loop should look like this: + + ``` cpp + ... + while (!_should_exit_task) + { + //bool updated; + //orb_check(fds[0], &updated); + //if (updated) + { + // obtained data for the file descriptor + struct throughput_256_s data = {}; + // copy raw data into local buffer + //orb_copy(ORB_ID(throughput_256), fds[0], &data); + data.data[0] = loop%256; + serialize_throughput_256(&data, data_buffer, &length, µCDRWriter); + if (0 < (read = transport_node->write((char)95, data_buffer, length))) + { + total_sent += read; + ++sent; + } + } + + usleep(_options.sleep_ms*1000); + ++loop; + } + ... + ``` +## Result + +After compiling and launching both the [client](README.md#px4-firmware-side-the-micro-rtps-client) and the [agent](README.md#fast-rtps-side-the-micro-rtps-agent) we obtain a measure of throughput for our particular conditions. For a Pixracer and a ordinary PC running Ubuntu 16.04 in the client shell window we obtain: + + ```sh + SENT: 13255 messages in 13255 LOOPS, 3512575 bytes in 30.994 seconds - 113.33KB/s + RECEIVED: 13251 messages in 10000 LOOPS, 3511515 bytes in 30.994 seconds - 113.30KB/s + ```