From 75e7297704dd864d456b75a5414224aab9642ddf Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Wed, 6 Nov 2024 16:48:44 +0100 Subject: [PATCH 01/85] Debug wrapper WIP --- build/docker-compose.leaderboard.yaml | 6 +- code/debug_wrapper.py | 123 +++++++++++++++++++++++ code/perception/launch/perception.launch | 2 +- code/perception/src/debug_wrapper.py | 1 + code/perception/src/lidar_distance.py | 20 +++- 5 files changed, 148 insertions(+), 4 deletions(-) create mode 100755 code/debug_wrapper.py create mode 120000 code/perception/src/debug_wrapper.py diff --git a/build/docker-compose.leaderboard.yaml b/build/docker-compose.leaderboard.yaml index 32fc98fc..126f3d09 100644 --- a/build/docker-compose.leaderboard.yaml +++ b/build/docker-compose.leaderboard.yaml @@ -8,4 +8,8 @@ services: extends: file: agent_service.yaml service: agent - command: bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && sudo chmod -R a+w ../ && python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" + command: |- + bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && \ + sudo chmod -R a+w ../ && sudo mkdir -p $${XDG_RUNTIME_DIR} && sudo chmod 0700 $${XDG_RUNTIME_DIR} && sudo chown -R ${USER_UID}:${USER_GID} $${XDG_RUNTIME_DIR} && \ + (rqt_console &) && disown -a && \ + python3 /opt/leaderboard/leaderboard/leaderboard_evaluator.py --debug=0 --routes=$${ROUTE} --agent=/workspace/code/agent/src/agent/agent.py --host=$${CARLA_SIM_HOST} --track=MAP" diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py new file mode 100755 index 00000000..f1cecd9f --- /dev/null +++ b/code/debug_wrapper.py @@ -0,0 +1,123 @@ +#!/usr/bin/env python3 + +import importlib +import importlib.util +import os +import sys +import argparse + +import rospy + +DEBUG_WRAPPER_MSG_PREFIX = "[debug_wrapper]:" +TYPE_PARAM = "~debug_type" +PORT_PARAM = "~debug_port" +WAIT_PARAM = "~debug_wait" + + +def eprint(*args, **kwargs): + """Print to stderr""" + print(*args, file=sys.stderr, **kwargs) + + +def logfatal(msg: str): + """Only works after ros node has been initialized""" + rospy.logfatal( + f"""{DEBUG_WRAPPER_MSG_PREFIX} FAILED TO START NODE - NODE WILL NOT SHOW UP: + {msg}""" + ) + + +def logerr(msg: str): + """Only works after ros node has been initialized""" + rospy.logerr(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") + + +def loginfo(msg: str): + """Only works after ros node has been initialized""" + rospy.loginfo(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") + + +def logdebug(msg: str): + """Only works after ros node has been initialized""" + print(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") + + +def get_required_params(): + try: + result = {} + if not rospy.has_param(TYPE_PARAM): + logfatal( + """Missing parameter to start debug wrapper: debug_type + Add it in the launch configuration""" + ) + result["type"] = str(rospy.get_param(TYPE_PARAM)) + if rospy.has_param(PORT_PARAM): + result["port"] = int(rospy.get_param(PORT_PARAM)) + else: + logerr( + """Missing parameter to start debugger: debug_port + Add it in the launch configuration""" + ) + result["port"] = None + result["wait"] = bool(rospy.get_param(WAIT_PARAM, False)) + return result + except BaseException as error: + logerr(f"Failed to get required node parameters: {error}") + raise error + + +def run_node_at(path: str): + try: + runpy.run_path(path, run_name="__main__") + except BaseException as error: + logfatal( + f"""Failed to run node module at {path}: + {error}""" + ) + raise error + + +def start_debugger(port: int, node_module_name: str, wait_for_debugee: bool = False): + debugger_spec = importlib.util.find_spec("debugpy") + if debugger_spec is not None: + try: + import debugpy + + debugpy.listen(("localhost", port)) + loginfo(f"Started debugger on port {port} for {node_module_name}") + if wait_for_debugee: + debugpy.wait_for_client() + except BaseException as error: + # Yes, all exceptions should be catched and sent into rosconsole + logerr(f"Failed to start debugger: {error}") + else: + logerr("debugpy module not found. Unable to start debugger") + + +def main(argv): + """# http://wiki.ros.org/Nodes: 7. Special keys -- __name is the node's name. + # In this case the name is set by the launch file + # Todo: when using rosrun, the name also has to be set somehow + ros_node_name: str = __name + # We have to init the node to be able to log and access parameters + rospy.init_node(name=ros_node_name)""" + node_args = rospy.myargv(argv=sys.argv) + parser = argparse.ArgumentParser( + prog="debug wrapper", + ) + parser.add_argument("--debug_node") + parser.add_argument("--debug_port") + parser.add_argument("--debug_wait") + args, unknown = parser.parse_known_args(node_args) + + base_dir = os.path.abspath(os.path.dirname(__file__)) + logdebug(f"Node {ros_node_name} started at {base_dir}") + params = get_required_params() + if params["port"] is not None: + start_debugger(params["port"], params["type"], wait_for_debugee=params["wait"]) + target_type_path = os.path.join(base_dir, params["type"]) + run_node_at(target_type_path) + + +if __name__ == "__main__": + main(argv=sys.argv) diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 8d6072e7..f194174c 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -75,7 +75,7 @@ - + diff --git a/code/perception/src/debug_wrapper.py b/code/perception/src/debug_wrapper.py new file mode 120000 index 00000000..e4e2c378 --- /dev/null +++ b/code/perception/src/debug_wrapper.py @@ -0,0 +1 @@ +../../debug_wrapper.py \ No newline at end of file diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index 04394ee2..93ab1bc2 100755 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -120,7 +120,6 @@ def listener(self): Initializes the node and it's publishers """ # run simultaneously. - rospy.init_node("lidar_distance") self.bridge = CvBridge() self.pub_pointcloud = rospy.Publisher( @@ -246,6 +245,23 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): return dist_array -if __name__ == "__main__": +def ros_init(): + """Initializes the node for basic ROS functions. + + Must only be called ONCE and not as part of def main() + + Required for debugger entry""" + rospy.init_node("lidar_distance") + + +def main(): + """Main entry point of this node + + Required for debugger entry""" lidar_distance = LidarDistance() lidar_distance.listener() + + +if __name__ == "__main__": + rospy.init_node("lidar_distance") + main() From 4ef21fcc0fd686663ec395a781a949e4cfd9debc Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Thu, 7 Nov 2024 03:16:15 +0100 Subject: [PATCH 02/85] Basic debug wrapper working --- .vscode/launch.json | 23 +++++ code/debug_wrapper.py | 123 ++++++++++++----------- code/perception/launch/perception.launch | 2 +- code/perception/src/lidar_distance.py | 6 +- pyrightconfig.json | 25 +++++ 5 files changed, 114 insertions(+), 65 deletions(-) create mode 100644 .vscode/launch.json create mode 100644 pyrightconfig.json diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 00000000..e7ed6ee0 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,23 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + { + "name": "Python Debugger: Remote Attach", + "type": "debugpy", + "request": "attach", + "connect": { + "host": "localhost", + "port": 5678 + }, + "pathMappings": [ + { + "localRoot": "${workspaceFolder}/code", + "remoteRoot": "/internal_workspace/catkin_ws/src" + } + ] + } + ] +} \ No newline at end of file diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py index f1cecd9f..88486091 100755 --- a/code/debug_wrapper.py +++ b/code/debug_wrapper.py @@ -1,6 +1,5 @@ #!/usr/bin/env python3 -import importlib import importlib.util import os import sys @@ -14,9 +13,13 @@ WAIT_PARAM = "~debug_wait" -def eprint(*args, **kwargs): +def printdebug(msg: str): + print(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") + + +def printerror(msg: str): """Print to stderr""" - print(*args, file=sys.stderr, **kwargs) + print(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}", file=sys.stderr) def logfatal(msg: str): @@ -37,47 +40,25 @@ def loginfo(msg: str): rospy.loginfo(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") -def logdebug(msg: str): - """Only works after ros node has been initialized""" - print(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") - - -def get_required_params(): - try: - result = {} - if not rospy.has_param(TYPE_PARAM): - logfatal( - """Missing parameter to start debug wrapper: debug_type - Add it in the launch configuration""" - ) - result["type"] = str(rospy.get_param(TYPE_PARAM)) - if rospy.has_param(PORT_PARAM): - result["port"] = int(rospy.get_param(PORT_PARAM)) - else: - logerr( - """Missing parameter to start debugger: debug_port - Add it in the launch configuration""" - ) - result["port"] = None - result["wait"] = bool(rospy.get_param(WAIT_PARAM, False)) - return result - except BaseException as error: - logerr(f"Failed to get required node parameters: {error}") - raise error - - -def run_node_at(path: str): - try: - runpy.run_path(path, run_name="__main__") - except BaseException as error: - logfatal( - f"""Failed to run node module at {path}: - {error}""" - ) - raise error +def import_module_at(path: str): + basename = os.path.basename(path) + module_dir = os.path.dirname(path) + module_name = os.path.splitext(basename)[0] + # Based on https://docs.python.org/3/library/importlib.html#importing-a-source-file-directly + """ spec = importlib.util.spec_from_file_location( + name=module_name, location=path, submodule_search_locations=[module_dir] + ) + if spec is None: + raise Exception(f"Failed to load {path} as module {module_name}") + module = importlib.util.module_from_spec(spec) + sys.modules[module_name] = module + spec.loader.exec_module(module) """ + sys.path.append(module_dir) + module = importlib.import_module(module_name) + return module -def start_debugger(port: int, node_module_name: str, wait_for_debugee: bool = False): +def start_debugger(port: int, node_module_name: str, wait_for_client: bool = False): debugger_spec = importlib.util.find_spec("debugpy") if debugger_spec is not None: try: @@ -85,7 +66,7 @@ def start_debugger(port: int, node_module_name: str, wait_for_debugee: bool = Fa debugpy.listen(("localhost", port)) loginfo(f"Started debugger on port {port} for {node_module_name}") - if wait_for_debugee: + if wait_for_client: debugpy.wait_for_client() except BaseException as error: # Yes, all exceptions should be catched and sent into rosconsole @@ -94,29 +75,49 @@ def start_debugger(port: int, node_module_name: str, wait_for_debugee: bool = Fa logerr("debugpy module not found. Unable to start debugger") +class ArgumentParserError(Exception): + pass + + +class ThrowingArgumentParser(argparse.ArgumentParser): + def error(self, message): + raise ArgumentParserError(message) + + def main(argv): - """# http://wiki.ros.org/Nodes: 7. Special keys -- __name is the node's name. - # In this case the name is set by the launch file - # Todo: when using rosrun, the name also has to be set somehow - ros_node_name: str = __name - # We have to init the node to be able to log and access parameters - rospy.init_node(name=ros_node_name)""" - node_args = rospy.myargv(argv=sys.argv) - parser = argparse.ArgumentParser( + node_args = rospy.myargv(argv=argv) + parser = ThrowingArgumentParser( prog="debug wrapper", ) - parser.add_argument("--debug_node") - parser.add_argument("--debug_port") - parser.add_argument("--debug_wait") - args, unknown = parser.parse_known_args(node_args) + parser.add_argument("--debug_node", required=True) + parser.add_argument("--debug_port", required=False, type=int) + parser.add_argument("--debug_wait", default=False, type=bool) + args, unknown_args = parser.parse_known_args(node_args) + debug_node = args.debug_node base_dir = os.path.abspath(os.path.dirname(__file__)) - logdebug(f"Node {ros_node_name} started at {base_dir}") - params = get_required_params() - if params["port"] is not None: - start_debugger(params["port"], params["type"], wait_for_debugee=params["wait"]) - target_type_path = os.path.join(base_dir, params["type"]) - run_node_at(target_type_path) + printdebug(f"Node {args.debug_node} starting at {base_dir}") + + target_type_path = os.path.join(base_dir, debug_node) + module = import_module_at(target_type_path) + + module.init_ros() + + if args.debug_port is not None: + start_debugger( + args.debug_port, args.debug_node, wait_for_client=args.debug_wait + ) + else: + logerr( + """Missing parameter to start debugger: --debug_port + Add it in the launch configuration""" + ) + + try: + module.main(unknown_args) + except BaseException as error: + logfatal(f"Failed to run node {debug_node}: {error}") + raise error if __name__ == "__main__": diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index f194174c..39d97263 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -75,7 +75,7 @@ - + diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index 93ab1bc2..84afa1b2 100755 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -245,7 +245,7 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): return dist_array -def ros_init(): +def init_ros(): """Initializes the node for basic ROS functions. Must only be called ONCE and not as part of def main() @@ -254,7 +254,7 @@ def ros_init(): rospy.init_node("lidar_distance") -def main(): +def main(argv=None): """Main entry point of this node Required for debugger entry""" @@ -263,5 +263,5 @@ def main(): if __name__ == "__main__": - rospy.init_node("lidar_distance") + init_ros() main() diff --git a/pyrightconfig.json b/pyrightconfig.json new file mode 100644 index 00000000..5cafbb7c --- /dev/null +++ b/pyrightconfig.json @@ -0,0 +1,25 @@ +{ + "include": ["code/src"], + + "exclude": [], + + "ignore": [], + + "defineConstant": { + "DEBUG": true + }, + + "typeCheckingMode": "standard", + "strictListInference": true, + "strictDictionaryInference": true, + "strictSetInference": true, + + "pythonVersion": "3.8", + "pythonPlatform": "Linux", + + "executionEnvironments": [ + { + "root": "code/src" + } + ] +} From 4a55b03832f96879d7847f779b8907533359c217 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Thu, 7 Nov 2024 15:32:08 +0100 Subject: [PATCH 03/85] Revert lidar distance changes --- code/perception/src/lidar_distance.py | 20 ++------------------ 1 file changed, 2 insertions(+), 18 deletions(-) diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index 84afa1b2..04394ee2 100755 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -120,6 +120,7 @@ def listener(self): Initializes the node and it's publishers """ # run simultaneously. + rospy.init_node("lidar_distance") self.bridge = CvBridge() self.pub_pointcloud = rospy.Publisher( @@ -245,23 +246,6 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): return dist_array -def init_ros(): - """Initializes the node for basic ROS functions. - - Must only be called ONCE and not as part of def main() - - Required for debugger entry""" - rospy.init_node("lidar_distance") - - -def main(argv=None): - """Main entry point of this node - - Required for debugger entry""" +if __name__ == "__main__": lidar_distance = LidarDistance() lidar_distance.listener() - - -if __name__ == "__main__": - init_ros() - main() From b159c55d9b3f6b63cf8790b08985a1a6be1b199e Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Thu, 7 Nov 2024 18:22:18 +0100 Subject: [PATCH 04/85] Debugger working with docker + logging improvements --- .vscode/launch.json | 8 +- build/agent_service.yaml | 1 + build/docker-compose.leaderboard.yaml | 2 + build/docker/agent/Dockerfile | 3 +- code/debug_logger_node.py | 77 +++++++++++++++ code/debug_wrapper.py | 114 ++++++++++++++--------- code/perception/launch/perception.launch | 2 +- code/requirements.txt | 1 + doc/development/debugging.md | 39 ++++++++ 9 files changed, 198 insertions(+), 49 deletions(-) create mode 100755 code/debug_logger_node.py create mode 100644 doc/development/debugging.md diff --git a/.vscode/launch.json b/.vscode/launch.json index e7ed6ee0..29e9ce53 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -5,19 +5,19 @@ "version": "0.2.0", "configurations": [ { - "name": "Python Debugger: Remote Attach", + "name": "53000 leaderboard attach", "type": "debugpy", "request": "attach", "connect": { "host": "localhost", - "port": 5678 + "port": 53000 }, "pathMappings": [ { "localRoot": "${workspaceFolder}/code", - "remoteRoot": "/internal_workspace/catkin_ws/src" + "remoteRoot": "${env:PAF_CODE_ROOT}" } ] } - ] + ], } \ No newline at end of file diff --git a/build/agent_service.yaml b/build/agent_service.yaml index 530eb208..5255aae4 100644 --- a/build/agent_service.yaml +++ b/build/agent_service.yaml @@ -30,6 +30,7 @@ services: - ROS_HOSTNAME=agent - XDG_RUNTIME_DIR=/tmp/runtime-carla - ROUTE=/opt/leaderboard/data/routes_devtest.xml + - DEBUG_WRAPPER_DEFAULT_HOST=0.0.0.0 # Simple route without special scenarios # - ROUTE=/workspace/code/routes/routes_simple.xml volumes: diff --git a/build/docker-compose.leaderboard.yaml b/build/docker-compose.leaderboard.yaml index 126f3d09..8d6633ee 100644 --- a/build/docker-compose.leaderboard.yaml +++ b/build/docker-compose.leaderboard.yaml @@ -8,6 +8,8 @@ services: extends: file: agent_service.yaml service: agent + ports: + - "53000-53100:53000-53100" command: |- bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && \ sudo chmod -R a+w ../ && sudo mkdir -p $${XDG_RUNTIME_DIR} && sudo chmod 0700 $${XDG_RUNTIME_DIR} && sudo chown -R ${USER_UID}:${USER_GID} $${XDG_RUNTIME_DIR} && \ diff --git a/build/docker/agent/Dockerfile b/build/docker/agent/Dockerfile index 408fae6c..1ac2cebc 100644 --- a/build/docker/agent/Dockerfile +++ b/build/docker/agent/Dockerfile @@ -171,7 +171,8 @@ RUN source /opt/ros/noetic/setup.bash && catkin_make ADD ./build/docker/agent/entrypoint.sh /entrypoint.sh # set the default working directory to the code -WORKDIR /workspace/code +ENV PAF_CODE_ROOT=/workspace/code +WORKDIR ${PAF_CODE_ROOT} RUN echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc RUN echo "source /catkin_ws/devel/setup.bash" >> ~/.bashrc diff --git a/code/debug_logger_node.py b/code/debug_logger_node.py new file mode 100755 index 00000000..202bcfc6 --- /dev/null +++ b/code/debug_logger_node.py @@ -0,0 +1,77 @@ +#!/usr/bin/env python3 +""" +This is a dedicated debug logger node + +Without a fully initialized node, log messages do not show up in the rqt_console + +This is why this node is used by the debug_wrapper for logging +before it has initialized it's node +""" + +import time +import sys +from multiprocessing.connection import Listener + +import rospy + + +def eprint(msg: str): + print(f"[debug_logger_node]: {msg}", file=sys.stderr) + + +def log(name: str, msg: str, level: str): + msg = f"[debug_logger for {name}]: {msg}" + + level = level.lower() + if level == "debug": + rospy.logdebug(msg) + elif level == "info": + rospy.loginfo(msg) + elif level == "warn": + rospy.logwarn(msg) + elif level == "error": + rospy.logerr(msg) + else: + rospy.logfatal(msg) + + +def main(): + try: + address = ("localhost", 52999) # family is deduced to be 'AF_INET' + listener = Listener( + address, authkey=b"debug_logger" + ) # Only one listerner can be active at once + eprint("Debug logger node started") + except OSError as error: + eprint(f"Failed to start listener: {error}. Exiting...") + exit(0) + + rospy.init_node(name="debug_logger") + time.sleep( + 5.0 + ) # We need to wait a bit until the node is fully initialized to send log messages + + # Based on + # https://stackoverflow.com/questions/6920858/interprocess-communication-in-python + while not rospy.is_shutdown(): + conn = listener.accept() + print(f"[debug_logger]: connection accepted from {listener.last_accepted}") + msg = conn.recv() + conn.close() + log_msg = "Wrong log message format" + log_name = "NAMERR" + log_level = "fatal" + if isinstance(msg, dict): + if "name" in msg: + log_name = msg["name"] + if "msg" in msg: + log_msg = msg["msg"] + if "level" in msg: + log_level = msg["level"] + log(log_name, log_msg, log_level) + + listener.close() + + +if __name__ == "__main__": + main() diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py index 88486091..993b216d 100755 --- a/code/debug_wrapper.py +++ b/code/debug_wrapper.py @@ -2,70 +2,89 @@ import importlib.util import os +import subprocess +import runpy import sys +import shutil import argparse +from multiprocessing.connection import Client import rospy -DEBUG_WRAPPER_MSG_PREFIX = "[debug_wrapper]:" -TYPE_PARAM = "~debug_type" -PORT_PARAM = "~debug_port" -WAIT_PARAM = "~debug_wait" +NODE_NAME = "NAMEERR" +LOGGER_STARTED = False -def printdebug(msg: str): - print(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") +def start_logger(): + global LOGGER_STARTED + # read directory of this python file with resolved symlinks + real_dir = os.path.dirname(os.path.realpath(__file__)) + logger_path = os.path.join(real_dir, "debug_logger_node.py") + eprint(f"Starting logger at {logger_path}") + try: + python_path: str = shutil.which("python3") + subprocess.Popen( + [python_path, logger_path], + start_new_session=True, + ) + LOGGER_STARTED = True + except BaseException as error: + eprint(f"Failed to start logger: {error}") + + +def eprint(msg: str): + print(f"[debug_wrapper]: {msg}", file=sys.stderr) -def printerror(msg: str): - """Print to stderr""" - print(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}", file=sys.stderr) +def log(msg: str, level: str): + if LOGGER_STARTED: + try: + address = ("localhost", 52999) + conn = Client(address, authkey=b"debug_logger") + conn.send({"name": NODE_NAME, "msg": msg, "level": level}) + conn.close() + except BaseException as error: + eprint(msg) + eprint(f"Failed to send to logger: {error}") + else: + eprint(msg) def logfatal(msg: str): - """Only works after ros node has been initialized""" - rospy.logfatal( - f"""{DEBUG_WRAPPER_MSG_PREFIX} FAILED TO START NODE - NODE WILL NOT SHOW UP: - {msg}""" - ) + log(f"FAILED TO START NODE - NODE WILL NOT SHOW UP: {msg}", "fatal") def logerr(msg: str): - """Only works after ros node has been initialized""" - rospy.logerr(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") + log(msg, "error") + + +def logwarn(msg: str): + log(msg, "warn") def loginfo(msg: str): - """Only works after ros node has been initialized""" - rospy.loginfo(f"{DEBUG_WRAPPER_MSG_PREFIX} {msg}") + log(msg, "info") -def import_module_at(path: str): +def run_module_at(path: str): basename = os.path.basename(path) module_dir = os.path.dirname(path) module_name = os.path.splitext(basename)[0] - # Based on https://docs.python.org/3/library/importlib.html#importing-a-source-file-directly - """ spec = importlib.util.spec_from_file_location( - name=module_name, location=path, submodule_search_locations=[module_dir] - ) - if spec is None: - raise Exception(f"Failed to load {path} as module {module_name}") - module = importlib.util.module_from_spec(spec) - sys.modules[module_name] = module - spec.loader.exec_module(module) """ sys.path.append(module_dir) - module = importlib.import_module(module_name) - return module + runpy.run_module(module_name, run_name="__main__") -def start_debugger(port: int, node_module_name: str, wait_for_client: bool = False): +def start_debugger( + node_module_name: str, host: str, port: int, wait_for_client: bool = False +): debugger_spec = importlib.util.find_spec("debugpy") if debugger_spec is not None: try: import debugpy - debugpy.listen(("localhost", port)) - loginfo(f"Started debugger on port {port} for {node_module_name}") + debugpy.configure(subProcess=False) + debugpy.listen((host, port)) + logwarn(f"Started debugger on {host}:{port} for {node_module_name}") if wait_for_client: debugpy.wait_for_client() except BaseException as error: @@ -81,31 +100,38 @@ class ArgumentParserError(Exception): class ThrowingArgumentParser(argparse.ArgumentParser): def error(self, message): + logfatal(f"Wrong node arguments. Check launch config. : {message}") raise ArgumentParserError(message) def main(argv): + global NODE_NAME + start_logger() + + default_host = "localhost" + if "DEBUG_WRAPPER_DEFAULT_HOST" in os.environ: + default_host = os.environ["DEBUG_WRAPPER_DEFAULT_HOST"] + node_args = rospy.myargv(argv=argv) parser = ThrowingArgumentParser( prog="debug wrapper", ) - parser.add_argument("--debug_node", required=True) + parser.add_argument("--debug_node", required=True, type=str) parser.add_argument("--debug_port", required=False, type=int) + parser.add_argument("--debug_host", default=default_host, type=str) parser.add_argument("--debug_wait", default=False, type=bool) args, unknown_args = parser.parse_known_args(node_args) - debug_node = args.debug_node + debug_node = args.debug_node + NODE_NAME = debug_node base_dir = os.path.abspath(os.path.dirname(__file__)) - printdebug(f"Node {args.debug_node} starting at {base_dir}") - - target_type_path = os.path.join(base_dir, debug_node) - module = import_module_at(target_type_path) - - module.init_ros() if args.debug_port is not None: start_debugger( - args.debug_port, args.debug_node, wait_for_client=args.debug_wait + args.debug_node, + args.debug_host, + args.debug_port, + wait_for_client=args.debug_wait, ) else: logerr( @@ -113,8 +139,10 @@ def main(argv): Add it in the launch configuration""" ) + target_type_path = os.path.join(base_dir, debug_node) + loginfo(f"Node {args.debug_node} starting at {base_dir}") try: - module.main(unknown_args) + run_module_at(target_type_path) except BaseException as error: logfatal(f"Failed to run node {debug_node}: {error}") raise error diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 39d97263..b7a78c48 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -75,7 +75,7 @@ - + diff --git a/code/requirements.txt b/code/requirements.txt index b9b6155d..55de87f0 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -16,3 +16,4 @@ numpy==1.23.5 ultralytics==8.1.11 scikit-learn>=0.18 pandas==2.0.3 +debugpy==1.8.7 \ No newline at end of file diff --git a/doc/development/debugging.md b/doc/development/debugging.md new file mode 100644 index 00000000..45a3a6f5 --- /dev/null +++ b/doc/development/debugging.md @@ -0,0 +1,39 @@ +# Debugging + +**Summary:** This page explains multiple debugging methods for ROS nodes. + +- [Debugging possibilities](#debugging-possibilities) + - [Message based debugging](#message-based-debugging) + - [VS Code debugger](#vs-code-debugger) +- [Rebuild docker containers](#rebuild-docker-containers) +- [Sources](#sources) + +## Debugging possibilities + +There are two main debugging possibilities + +### Message based debugging + +Messages can be logged into the ROS console vie the `rospy.logdebug`, `rospy.loginfo`, `rospy.logwarn`, `rospy.logerror` and `rospy.logfatal` functions. + +### VS Code debugger + + + +## Rebuild docker containers + +The docker images on your pc might not match the latest Dockerfile in the repository + +To update them, open a terminal and change into the *build* directory. Execute: + +```bash +export USER_UID=$(id -u) +export USER_GID=$(id -g) +export USERNAME=$(id -u -n) +docker compose -f ./docker-compose.leaderboard.yaml up -d --build +docker compose -f ./docker-compose.dev.yaml up -d --build +``` + +## Sources + + From 3d43f017bc12e045b46bc297b3813664883217cf Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Fri, 8 Nov 2024 15:53:06 +0100 Subject: [PATCH 05/85] Debug logger node added to launch config + general logging improvements --- code/agent/launch/agent.launch | 4 + code/debug_logger_node.py | 77 --------- code/debug_wrapper.py | 41 ++--- code/debugging/CMakeLists.txt | 204 ++++++++++++++++++++++++ code/debugging/launch/debugging.launch | 4 + code/debugging/package.xml | 62 +++++++ code/debugging/src/debug_logger_node.py | 126 +++++++++++++++ 7 files changed, 412 insertions(+), 106 deletions(-) delete mode 100755 code/debug_logger_node.py create mode 100644 code/debugging/CMakeLists.txt create mode 100644 code/debugging/launch/debugging.launch create mode 100644 code/debugging/package.xml create mode 100755 code/debugging/src/debug_logger_node.py diff --git a/code/agent/launch/agent.launch b/code/agent/launch/agent.launch index fb9ef983..7861a38f 100644 --- a/code/agent/launch/agent.launch +++ b/code/agent/launch/agent.launch @@ -21,5 +21,9 @@ + + + + diff --git a/code/debug_logger_node.py b/code/debug_logger_node.py deleted file mode 100755 index 202bcfc6..00000000 --- a/code/debug_logger_node.py +++ /dev/null @@ -1,77 +0,0 @@ -#!/usr/bin/env python3 -""" -This is a dedicated debug logger node - -Without a fully initialized node, log messages do not show up in the rqt_console - -This is why this node is used by the debug_wrapper for logging -before it has initialized it's node -""" - -import time -import sys -from multiprocessing.connection import Listener - -import rospy - - -def eprint(msg: str): - print(f"[debug_logger_node]: {msg}", file=sys.stderr) - - -def log(name: str, msg: str, level: str): - msg = f"[debug_logger for {name}]: {msg}" - - level = level.lower() - if level == "debug": - rospy.logdebug(msg) - elif level == "info": - rospy.loginfo(msg) - elif level == "warn": - rospy.logwarn(msg) - elif level == "error": - rospy.logerr(msg) - else: - rospy.logfatal(msg) - - -def main(): - try: - address = ("localhost", 52999) # family is deduced to be 'AF_INET' - listener = Listener( - address, authkey=b"debug_logger" - ) # Only one listerner can be active at once - eprint("Debug logger node started") - except OSError as error: - eprint(f"Failed to start listener: {error}. Exiting...") - exit(0) - - rospy.init_node(name="debug_logger") - time.sleep( - 5.0 - ) # We need to wait a bit until the node is fully initialized to send log messages - - # Based on - # https://stackoverflow.com/questions/6920858/interprocess-communication-in-python - while not rospy.is_shutdown(): - conn = listener.accept() - print(f"[debug_logger]: connection accepted from {listener.last_accepted}") - msg = conn.recv() - conn.close() - log_msg = "Wrong log message format" - log_name = "NAMERR" - log_level = "fatal" - if isinstance(msg, dict): - if "name" in msg: - log_name = msg["name"] - if "msg" in msg: - log_msg = msg["msg"] - if "level" in msg: - log_level = msg["level"] - log(log_name, log_msg, log_level) - - listener.close() - - -if __name__ == "__main__": - main() diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py index 993b216d..91b3d961 100755 --- a/code/debug_wrapper.py +++ b/code/debug_wrapper.py @@ -2,34 +2,15 @@ import importlib.util import os -import subprocess import runpy import sys -import shutil import argparse +import time from multiprocessing.connection import Client import rospy NODE_NAME = "NAMEERR" -LOGGER_STARTED = False - - -def start_logger(): - global LOGGER_STARTED - # read directory of this python file with resolved symlinks - real_dir = os.path.dirname(os.path.realpath(__file__)) - logger_path = os.path.join(real_dir, "debug_logger_node.py") - eprint(f"Starting logger at {logger_path}") - try: - python_path: str = shutil.which("python3") - subprocess.Popen( - [python_path, logger_path], - start_new_session=True, - ) - LOGGER_STARTED = True - except BaseException as error: - eprint(f"Failed to start logger: {error}") def eprint(msg: str): @@ -37,17 +18,22 @@ def eprint(msg: str): def log(msg: str, level: str): - if LOGGER_STARTED: + error = None + success = False + start_time = time.monotonic() + while not success and start_time + 5.0 > time.monotonic(): try: address = ("localhost", 52999) conn = Client(address, authkey=b"debug_logger") conn.send({"name": NODE_NAME, "msg": msg, "level": level}) conn.close() - except BaseException as error: - eprint(msg) - eprint(f"Failed to send to logger: {error}") - else: + success = True + except BaseException as e: + error = e + if not success: eprint(msg) + if error is not None: + eprint(f"Failed to send to logger: {error}") def logfatal(msg: str): @@ -82,7 +68,6 @@ def start_debugger( try: import debugpy - debugpy.configure(subProcess=False) debugpy.listen((host, port)) logwarn(f"Started debugger on {host}:{port} for {node_module_name}") if wait_for_client: @@ -105,9 +90,6 @@ def error(self, message): def main(argv): - global NODE_NAME - start_logger() - default_host = "localhost" if "DEBUG_WRAPPER_DEFAULT_HOST" in os.environ: default_host = os.environ["DEBUG_WRAPPER_DEFAULT_HOST"] @@ -123,6 +105,7 @@ def main(argv): args, unknown_args = parser.parse_known_args(node_args) debug_node = args.debug_node + global NODE_NAME NODE_NAME = debug_node base_dir = os.path.abspath(os.path.dirname(__file__)) diff --git a/code/debugging/CMakeLists.txt b/code/debugging/CMakeLists.txt new file mode 100644 index 00000000..8cc214d8 --- /dev/null +++ b/code/debugging/CMakeLists.txt @@ -0,0 +1,204 @@ +cmake_minimum_required(VERSION 3.0.2) +project(debugging) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + rospy +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# std_msgs # Or other packages containing msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES debugging +# CATKIN_DEPENDS rospy +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/debugging.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/debugging_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_debugging.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/code/debugging/launch/debugging.launch b/code/debugging/launch/debugging.launch new file mode 100644 index 00000000..4388cbbf --- /dev/null +++ b/code/debugging/launch/debugging.launch @@ -0,0 +1,4 @@ + + + + diff --git a/code/debugging/package.xml b/code/debugging/package.xml new file mode 100644 index 00000000..5598d5ed --- /dev/null +++ b/code/debugging/package.xml @@ -0,0 +1,62 @@ + + + debugging + 0.0.0 + The debugging package + + + + + peter + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + rospy + rospy + rospy + + + + + + + + diff --git a/code/debugging/src/debug_logger_node.py b/code/debugging/src/debug_logger_node.py new file mode 100755 index 00000000..68bc4b6c --- /dev/null +++ b/code/debugging/src/debug_logger_node.py @@ -0,0 +1,126 @@ +#!/usr/bin/env python3 +""" +This is a dedicated debug logger node + +Without a fully initialized node, log messages only show up in the logfile. +But not in the /rosout topic and thus not in the rqt_console + +This is why this node is used by the debug_wrapper for logging +before it has initialized its own node +""" + +import time +import sys +from multiprocessing.connection import Listener, Client +import threading +import signal + +import rospy + +ADDRESS = ("localhost", 52999) +AUTHKEY = b"debug_logger" +CLOSE_MSG = "close" +LISTENER_THREAD = None +NODE_RUNNING = True + +MESSAGES_MUTEX = threading.Lock() +MESSAGES = [] + + +def eprint(msg: str): + print(f"[debug_logger_node]: {msg}", file=sys.stderr) + + +def log(name: str, msg: str, level: str): + msg = f"[debug_logger for {name}]: {msg}" + + level = level.lower() + if level == "debug": + rospy.logdebug(msg) + elif level == "info": + rospy.loginfo(msg) + elif level == "warn": + rospy.logwarn(msg) + elif level == "error": + rospy.logerr(msg) + else: + rospy.logfatal(msg) + + +def run_listener(listener: Listener): + running = True + while running: + conn = listener.accept() + print(f"[debug_logger]: connection accepted from {listener.last_accepted}") + msg = None + if conn.poll(timeout=2.0): + msg = conn.recv() + if isinstance(msg, str): + if msg.lower() == CLOSE_MSG: + running = False + msg = None + conn.close() + if msg is not None: + with MESSAGES_MUTEX: + MESSAGES.append(msg) + listener.close() + + +def close_listener(): + try: + conn = Client(ADDRESS, authkey=AUTHKEY) + conn.send(CLOSE_MSG) + conn.close() + except BaseException: + pass + + +def exit_cleanup(signum=None, frame=None): + close_listener() + if LISTENER_THREAD is not None: + LISTENER_THREAD.join() + global NODE_RUNNING + NODE_RUNNING = False + + +def main(): + try: + # Based on + # https://stackoverflow.com/questions/6920858/interprocess-communication-in-python + # Only one listener can be active at once + listener = Listener(ADDRESS, authkey=AUTHKEY) + eprint("Debug logger node started") + except OSError as error: + eprint(f"Failed to run listener: {error}. Exiting...") + exit(0) + signal.signal(signal.SIGINT, exit_cleanup) + signal.signal(signal.SIGTERM, exit_cleanup) + global LISTENER_THREAD + LISTENER_THREAD = threading.Thread(target=run_listener, args=(listener,)) + LISTENER_THREAD.start() + + rospy.init_node(name="debug_logger") + # We need to wait a bit until the node is fully initialized to send log messages + time.sleep(5.0) + rospy.on_shutdown(exit_cleanup) + + while NODE_RUNNING: + with MESSAGES_MUTEX: + while len(MESSAGES) > 0: + msg = MESSAGES.pop() + log_msg = "Wrong log message format" + log_name = "NAMERR" + log_level = "fatal" + if isinstance(msg, dict): + if "name" in msg: + log_name = msg["name"] + if "msg" in msg: + log_msg = msg["msg"] + if "level" in msg: + log_level = msg["level"] + log(log_name, log_msg, log_level) + time.sleep(0.5) + + +if __name__ == "__main__": + main() From 37c308a2d59271f3c758c7471d23b8b2aa8dd864 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Fri, 8 Nov 2024 16:39:14 +0100 Subject: [PATCH 06/85] Update remoteRoot source mapping variable PAF_CATKIN_CODE_ROOT --- .vscode/launch.json | 2 +- build/docker/agent/Dockerfile | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/.vscode/launch.json b/.vscode/launch.json index 29e9ce53..68420ca7 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -15,7 +15,7 @@ "pathMappings": [ { "localRoot": "${workspaceFolder}/code", - "remoteRoot": "${env:PAF_CODE_ROOT}" + "remoteRoot": "${env:PAF_CATKIN_CODE_ROOT}" } ] } diff --git a/build/docker/agent/Dockerfile b/build/docker/agent/Dockerfile index 1ac2cebc..48818408 100644 --- a/build/docker/agent/Dockerfile +++ b/build/docker/agent/Dockerfile @@ -165,14 +165,16 @@ COPY --chown=$USERNAME:$USERNAME ./code /workspace/code/ # Link code into catkin workspace RUN ln -s /workspace/code /catkin_ws/src +# For debugger +ENV PAF_CATKIN_CODE_ROOT=/catkin_ws/src + # re-make the catkin workspace RUN source /opt/ros/noetic/setup.bash && catkin_make ADD ./build/docker/agent/entrypoint.sh /entrypoint.sh # set the default working directory to the code -ENV PAF_CODE_ROOT=/workspace/code -WORKDIR ${PAF_CODE_ROOT} +WORKDIR /workspace/code RUN echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc RUN echo "source /catkin_ws/devel/setup.bash" >> ~/.bashrc From b5cc5e4d1d7a7f8e4c5a88052fee8b683ccb8b49 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Fri, 8 Nov 2024 21:25:21 +0100 Subject: [PATCH 07/85] Revert perception.launch --- code/perception/launch/perception.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index b7a78c48..10f79a80 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -75,7 +75,7 @@ - + From 6fad77251a403f501121a41110188255623d4449 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Fri, 8 Nov 2024 21:55:36 +0100 Subject: [PATCH 08/85] Add detailed documentation --- code/debug_wrapper.py | 63 +++++++++++ code/debugging/launch/debugging.launch | 2 +- .../{debug_logger_node.py => debug_logger.py} | 39 ++++++- doc/development/debugging.md | 103 +++++++++++++++++- 4 files changed, 198 insertions(+), 9 deletions(-) rename code/debugging/src/{debug_logger_node.py => debug_logger.py} (73%) diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py index 91b3d961..c02d8d0a 100755 --- a/code/debug_wrapper.py +++ b/code/debug_wrapper.py @@ -1,4 +1,39 @@ #!/usr/bin/env python3 +"""Debug wrapper node + +Node that wraps a python ros node +and is able to open a debugpy remote debugger instance. + +Logs any exceptions from the node and other information +into the ros console via the debug_logger node. + +Always tries to at least start the node, +even if dependencies like debugpy are missing. + +Usage: + Already done for existing ros packages: symlink this file into the package. Example: + `cd code/perception/src && ln -s ../../debug_wrapper.py debug_wrapper.py` + + Adjust the launch configuration to use the debug_wrapper.py + instead of the node file and set the required args + + More info in [debugging.md](doc/development/debugging.md) + +Arguments: + --debug_node: Required: The filename of the node to debug + --debug_port: The port the debugger listens on. If not set, + --debug_host: The host the debugger binds to. + Defaults to the environment variable `DEBUG_WRAPPER_DEFAULT_HOST` if set, + otherwise `localhost` + --debug_wait: If True, the wrapper waits until a client (VS Code) is connected + and only then starts node execution + +Raises: + ArgumentParserError: Missing required parameters + error: If the started debug_node raises an exception, + it is logged and then raised again +""" + import importlib.util import os @@ -14,10 +49,24 @@ def eprint(msg: str): + """Log msg into stderr. + + Used instead of print, because only stderr seems to reliably land in agent.log + + Args: + msg (str): Log message + """ print(f"[debug_wrapper]: {msg}", file=sys.stderr) def log(msg: str, level: str): + """Log msg via the debug_logger node + + Args: + msg (str): Log message + level (str): Log level. One of (debug), info, warn, error, fatal. + debug level not recommended, because these are not published to /rosout + """ error = None success = False start_time = time.monotonic() @@ -53,6 +102,11 @@ def loginfo(msg: str): def run_module_at(path: str): + """Runs a python module based on its file path + + Args: + path (str): python file path to run + """ basename = os.path.basename(path) module_dir = os.path.dirname(path) module_name = os.path.splitext(basename)[0] @@ -63,6 +117,15 @@ def run_module_at(path: str): def start_debugger( node_module_name: str, host: str, port: int, wait_for_client: bool = False ): + """_summary_ + + Args: + node_module_name (str): Name of the underlying node. Only used for logging + host (str): host the debugger binds to + port (int): debugger port + wait_for_client (bool, optional): If the debugger should wait + for a client to attach. Defaults to False. + """ debugger_spec = importlib.util.find_spec("debugpy") if debugger_spec is not None: try: diff --git a/code/debugging/launch/debugging.launch b/code/debugging/launch/debugging.launch index 4388cbbf..330263e8 100644 --- a/code/debugging/launch/debugging.launch +++ b/code/debugging/launch/debugging.launch @@ -1,4 +1,4 @@ - + diff --git a/code/debugging/src/debug_logger_node.py b/code/debugging/src/debug_logger.py similarity index 73% rename from code/debugging/src/debug_logger_node.py rename to code/debugging/src/debug_logger.py index 68bc4b6c..6778531d 100755 --- a/code/debugging/src/debug_logger_node.py +++ b/code/debugging/src/debug_logger.py @@ -1,9 +1,16 @@ #!/usr/bin/env python3 -""" -This is a dedicated debug logger node +"""Dedicated debug logger node. + +It can receive messages via a multiprocessing ipc socket on localhost:52999. +Message format is a python dict with keys {name, msg, level}. +It will then send those messages into the ros console via rospy.log*() -Without a fully initialized node, log messages only show up in the logfile. -But not in the /rosout topic and thus not in the rqt_console +Main usecase: it enables not initialized python nodes to publish log messages +to the /rosout topic. + +Without a fully initialized node, +log messages from python files only show up in the ros logfile, +but not in the /rosout topic and thus not in the rqt_console This is why this node is used by the debug_wrapper for logging before it has initialized its own node @@ -28,10 +35,25 @@ def eprint(msg: str): - print(f"[debug_logger_node]: {msg}", file=sys.stderr) + """Log msg into stderr. + + Used instead of print, because only stderr seems to reliably land in agent.log + + Args: + msg (str): Log message + """ + print(f"[debug_logger]: {msg}", file=sys.stderr) def log(name: str, msg: str, level: str): + """Log to the ros console + + Args: + name (str): Node name this message should be associated with + msg (str): Log message + level (str): Log level. One of (debug), info, warn, error, fatal. + debug level not recommended, because these are not published to /rosout + """ msg = f"[debug_logger for {name}]: {msg}" level = level.lower() @@ -48,6 +70,13 @@ def log(name: str, msg: str, level: str): def run_listener(listener: Listener): + """Run the multiprocessing listener + + The listener exits when it receives CLOSE_MSG + + Args: + listener (Listener): Listener to run + """ running = True while running: conn = listener.accept() diff --git a/doc/development/debugging.md b/doc/development/debugging.md index 45a3a6f5..9d364145 100644 --- a/doc/development/debugging.md +++ b/doc/development/debugging.md @@ -4,27 +4,124 @@ - [Debugging possibilities](#debugging-possibilities) - [Message based debugging](#message-based-debugging) + - [Viewing the messages](#viewing-the-messages) + - [Problems of message based debugging](#problems-of-message-based-debugging) - [VS Code debugger](#vs-code-debugger) + - [Setup steps required once](#setup-steps-required-once) + - [Required once for the node you want to debug](#required-once-for-the-node-you-want-to-debug) + - [Debugging workflow after setup](#debugging-workflow-after-setup) + - [Known problems of debugging with VS Code](#known-problems-of-debugging-with-vs-code) - [Rebuild docker containers](#rebuild-docker-containers) - [Sources](#sources) ## Debugging possibilities -There are two main debugging possibilities +There are two main debugging possibilities: Message based and VS Code based ### Message based debugging Messages can be logged into the ROS console vie the `rospy.logdebug`, `rospy.loginfo`, `rospy.logwarn`, `rospy.logerror` and `rospy.logfatal` functions. +Most messages are then published to the /rosout topic. + +`rospy.logdebug` is not recommended, because these messages are not published to /rosout by default. + +Note that the node has to be initialized with `rospy.init_node()` before logging, otherwise the messages are not published to /rosout and just end up in stdout/stderr. + +#### Viewing the messages + +There are several ways to view the ROS log messages + +- The most convenient way to view logs is via the **rqt_console** GUI, which starts when the leaderboard is started. + It allows filtering for debug levels, nodes and message content. + + Caveat: It only includes messages published to the /rosout topic. + +- Execute `rosconsole echo` inside the *build-agent* container. This shows the /rosout messages from this point on. + +- The leaderboard logs usually end up in [code/log/ros](../../code/log/ros). + + This includes the [agent.log](../../code/log/ros/agent.log) file where most of all the nodes output is captured. + It seems to exclude stdout of the nodes and excludes the debug log level. stderr and all other levels are included. + Exceptions that occur at node initialization can also be found here. + +- More accurate "per-node" logs including the debug level and stdout end up in the individual node log files. + These can be found in the directory returned by running `roslaunch-logs` inside the *build-agent* container. (Usually `~/.ros/log`) + +- Manually starting a node with `rosrun ` inside the *build-agent* container helps to view stdout, stderr and exceptions. + +More information can be found in the [Wiki](https://wiki.ros.org/rospy/Overview/Logging) + +#### Problems of message based debugging + +- Time intensive and cumbersome: leaderboard has to be restarted to add a new message +- Frequent log messages "spam" the log +- Exceptions on node initialization do not show up in the /rosout topic +- If messages are sent right after `rospy.init_node()`, they might not be published to the /rosout topic ### VS Code debugger +Debug individual nodes with the VS Code debugger. This allows usage of breakpoints and code stepping. + +#### Setup steps required once + +1. Make sure the docker images are up-to-date: [Rebuild docker containers](#rebuild-docker-containers) +2. Start the `build/docker-compose.dev.yaml` containers and attach VS Code to the **build-agent-dev** container. Always use the VS Code remote for debugging +3. Make sure the recommended extensions are installed in the VS Code remote. + +#### Required once for the node you want to debug + +Adjust the launch configuration of the node to use the [debug_wrapper.py](../../code/debug_wrapper.py) node. + +Change the type to **debug_wrapper.py** and set `args="--debug_node= --debug_port="`. +*debug_port* can be a port in range **53000-53100**, because those are exposed from the [leaderboard docker configuration](../../build/docker-compose.leaderboard.yaml). + +Configuration example for the [lidar_distance.py](../../code/perception/src/lidar_distance.py) node: [launch configuration](../../code/perception/launch/perception.launch) + +- Original entry: + + ```launch + + + + + ``` + +- Entry modified for debugging: + + ```launch + + + + + ``` + +By default, the affected node will start up as usual. When you attach the debugger later, you are then only able to debug the callbacks the node receives. +But if you set `--debug_wait=True`, it will block the node from starting until VS Code attaches and allow you to debug the initialization of the node. + +If the leaderboard hangs on `Setting up the agent` after the configuration has been adjusted, there most likely is a mistake in the launch configuration. + +More usage information can be found in the [debug_wrapper](../../code/debug_wrapper.py) and the [debug_logger](../../code/debugging/src/debug_logger.py) + +#### Debugging workflow after setup + +1. Start/Restart the [leaderboard](../../build/docker-compose.leaderboard.yaml) as usual +2. Wait for the application to start up +3. Add breakpoints to your node. +4. Start the VS Code debugger (debugging tab). A default launch configuration named *53000 leaderboard attach* is available. It uses port **53000**. + +Any errors/exceptions the debug_wrapper encounters are published to /rosout via the [debug_logger](../../code/debugging/src/debug_logger.py). +With the **rqt_console** GUI you can filter by node *debug_logger* to see all messages related to the wrapper. + +#### Known problems of debugging with VS Code +- Adjusting the launch configurations is a bit cumbersome +- The side effects of just "stopping" a node with the debugger are unknown ## Rebuild docker containers The docker images on your pc might not match the latest Dockerfile in the repository -To update them, open a terminal and change into the *build* directory. Execute: +To update them, open a terminal, change into the *build* directory and execute: ```bash export USER_UID=$(id -u) @@ -36,4 +133,4 @@ docker compose -f ./docker-compose.dev.yaml up -d --build ## Sources - + From 1dd75132524fa979e1dc386971a8bdac4c9914bc Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Fri, 8 Nov 2024 22:00:57 +0100 Subject: [PATCH 09/85] Add debugger comment --- build/docker-compose.leaderboard.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/build/docker-compose.leaderboard.yaml b/build/docker-compose.leaderboard.yaml index 8d6633ee..4c43bd87 100644 --- a/build/docker-compose.leaderboard.yaml +++ b/build/docker-compose.leaderboard.yaml @@ -9,6 +9,7 @@ services: file: agent_service.yaml service: agent ports: + # Reserved ports for the debugger - "53000-53100:53000-53100" command: |- bash -c "sleep 10 && sudo chown -R ${USER_UID}:${USER_GID} ../ && \ From 5753cad1a1cc5810e0802d39eea5c90489324f06 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Fri, 8 Nov 2024 22:09:18 +0100 Subject: [PATCH 10/85] Add missing symlinks --- code/acting/src/debug_wrapper.py | 1 + code/mock/src/debug_wrapper.py | 1 + code/planning/src/debug_wrapper.py | 1 + 3 files changed, 3 insertions(+) create mode 120000 code/acting/src/debug_wrapper.py create mode 120000 code/mock/src/debug_wrapper.py create mode 120000 code/planning/src/debug_wrapper.py diff --git a/code/acting/src/debug_wrapper.py b/code/acting/src/debug_wrapper.py new file mode 120000 index 00000000..e4e2c378 --- /dev/null +++ b/code/acting/src/debug_wrapper.py @@ -0,0 +1 @@ +../../debug_wrapper.py \ No newline at end of file diff --git a/code/mock/src/debug_wrapper.py b/code/mock/src/debug_wrapper.py new file mode 120000 index 00000000..e4e2c378 --- /dev/null +++ b/code/mock/src/debug_wrapper.py @@ -0,0 +1 @@ +../../debug_wrapper.py \ No newline at end of file diff --git a/code/planning/src/debug_wrapper.py b/code/planning/src/debug_wrapper.py new file mode 120000 index 00000000..e4e2c378 --- /dev/null +++ b/code/planning/src/debug_wrapper.py @@ -0,0 +1 @@ +../../debug_wrapper.py \ No newline at end of file From 8694e5e6a82a80dbab0b587a12c974824b6f1a48 Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Fri, 8 Nov 2024 23:26:29 +0100 Subject: [PATCH 11/85] Added two tasks to vscode which can be executed in order to run catkin_make inside the container. One of them is more convenient as a list of containers is automatically provided. It however depends on a vscode extension not yet in recomendations. We might need to select one of the two options and remove the other. --- .vscode/extensions.json | 3 ++- .vscode/tasks.json | 36 ++++++++++++++++++++++++++++++++++++ 2 files changed, 38 insertions(+), 1 deletion(-) create mode 100644 .vscode/tasks.json diff --git a/.vscode/extensions.json b/.vscode/extensions.json index c27bbad5..596e223e 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -12,6 +12,7 @@ "richardkotze.git-mob", "ms-vscode-remote.remote-containers", "valentjn.vscode-ltex", - "ms-python.black-formatter" + "ms-python.black-formatter", + "augustocdias.tasks-shell-input" ] } \ No newline at end of file diff --git a/.vscode/tasks.json b/.vscode/tasks.json new file mode 100644 index 00000000..e59d7898 --- /dev/null +++ b/.vscode/tasks.json @@ -0,0 +1,36 @@ +{ + "version": "2.0.0", + "tasks": [ + { + "label": "Run 'catkin_make' in Docker container. Write container name.", + "type": "shell", + "command": "docker exec -it ${input:container_name} bash -c 'cd ../../catkin_ws && source /opt/ros/noetic/setup.bash && bash devel/setup.bash && catkin_make'", + "problemMatcher": [], + "detail": "Executes 'catkin_make' in built-agent-dev-1 container. The container must be running.", + "dependsOn": [], + }, + { + "label": "Run 'catkin_make' in docker container. Autochoose docker container.", + "type": "shell", + "command": "docker exec -it ${input:container_name_shell} bash -c 'cd ../../catkin_ws && source /opt/ros/noetic/setup.bash && bash devel/setup.bash && catkin_make'", + "problemMatcher": [], + "detail": "Executes 'catkin_make' selected container. Requires Tasks Shell Input Extension.", + } + ], + "inputs": [ + { + "id": "container_name", + "description": "Name of docker container", + "default": "build-agent-dev-1", + "type": "promptString" + }, + { + "id": "container_name_shell", + "type": "command", + "command": "shellCommand.execute", + "args": { + "command": "docker ps --format '{{.Names}}'", + } + } + ] +} \ No newline at end of file From 95912ca96c153cdc706758ce02024824d8cd6d98 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Sat, 9 Nov 2024 14:59:44 +0100 Subject: [PATCH 12/85] Add setup.py --- code/debugging/CMakeLists.txt | 2 +- code/debugging/setup.py | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) create mode 100644 code/debugging/setup.py diff --git a/code/debugging/CMakeLists.txt b/code/debugging/CMakeLists.txt index 8cc214d8..a857d84f 100644 --- a/code/debugging/CMakeLists.txt +++ b/code/debugging/CMakeLists.txt @@ -18,7 +18,7 @@ find_package(catkin REQUIRED COMPONENTS ## Uncomment this if the package has a setup.py. This macro ensures ## modules and global scripts declared therein get installed ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html -# catkin_python_setup() +catkin_python_setup() ################################################ ## Declare ROS messages, services and actions ## diff --git a/code/debugging/setup.py b/code/debugging/setup.py new file mode 100644 index 00000000..d320ac00 --- /dev/null +++ b/code/debugging/setup.py @@ -0,0 +1,6 @@ +#!/usr/bin/env python +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +setup_args = generate_distutils_setup(packages=["debugging"], package_dir={"": "src"}) +setup(**setup_args) From e7de5fca23441bd9cf74a747af7c4eadb4585eff Mon Sep 17 00:00:00 2001 From: Sebastian Seitz Date: Sun, 10 Nov 2024 12:19:52 +0100 Subject: [PATCH 13/85] add link to videos of the runs --- doc/research/paf24/general/current_state.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/doc/research/paf24/general/current_state.md b/doc/research/paf24/general/current_state.md index bffc2432..f5a9d194 100755 --- a/doc/research/paf24/general/current_state.md +++ b/doc/research/paf24/general/current_state.md @@ -128,6 +128,8 @@ Here are the raw notes in case misunderstandings have been made when grouping th ### Run 1 +[Link to Video of the Run](https://drive.google.com/file/d/1Hb4arEC5ocfUD2KZh1bNVwRG2hoML8E9/view?usp=drive_link) + - Scared to get out of parking spot - lane not held causing problems when avoiding open car door - stopping for no apparent reason @@ -153,6 +155,8 @@ Here are the raw notes in case misunderstandings have been made when grouping th ### Run 2 +[Link to Video of the Run](https://drive.google.com/file/d/1xot90LTNcSYOkLa1sXJJeMFBkXKmFO2x/view?usp=drive_link) + - merges without giving way to traffic - does not respect open car door - crashes into car in front when going after stop at red light @@ -168,6 +172,8 @@ Here are the raw notes in case misunderstandings have been made when grouping th ### Run 3 +[Link to Video of the Run](https://drive.google.com/file/d/1ERvN3nGddzuvtRqtIF2PKlFrcMzH2MrA/view?usp=drive_link) + - does not give way when exiting a parking spot - LIDAR detects floor - trajectory for overtaking is wrong / no overtake needed From 6ed2ae2c722ae017d9a24ec6f0c068cb53334b85 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 15:02:26 +0100 Subject: [PATCH 14/85] Improve dockerfile ENV var usage --- build/docker/agent/Dockerfile | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/build/docker/agent/Dockerfile b/build/docker/agent/Dockerfile index 48818408..fb6d9202 100644 --- a/build/docker/agent/Dockerfile +++ b/build/docker/agent/Dockerfile @@ -162,11 +162,10 @@ RUN source ~/.bashrc && pip install -r /workspace/requirements.txt # Add agent code COPY --chown=$USERNAME:$USERNAME ./code /workspace/code/ -# Link code into catkin workspace -RUN ln -s /workspace/code /catkin_ws/src - # For debugger ENV PAF_CATKIN_CODE_ROOT=/catkin_ws/src +# Link code into catkin workspace +RUN ln -s /workspace/code ${PAF_CATKIN_CODE_ROOT} # re-make the catkin workspace RUN source /opt/ros/noetic/setup.bash && catkin_make From 96240644773f57c45a927e0bbf107b2ef6e9618d Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 15:04:27 +0100 Subject: [PATCH 15/85] Remove unnecessary uses of BaseException and fix debug_wait flag --- code/debug_wrapper.py | 8 +++++--- code/debugging/src/debug_logger.py | 2 +- doc/development/debugging.md | 2 +- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py index c02d8d0a..924f7037 100755 --- a/code/debug_wrapper.py +++ b/code/debug_wrapper.py @@ -77,7 +77,7 @@ def log(msg: str, level: str): conn.send({"name": NODE_NAME, "msg": msg, "level": level}) conn.close() success = True - except BaseException as e: + except Exception as e: error = e if not success: eprint(msg) @@ -135,7 +135,7 @@ def start_debugger( logwarn(f"Started debugger on {host}:{port} for {node_module_name}") if wait_for_client: debugpy.wait_for_client() - except BaseException as error: + except Exception as error: # Yes, all exceptions should be catched and sent into rosconsole logerr(f"Failed to start debugger: {error}") else: @@ -164,7 +164,7 @@ def main(argv): parser.add_argument("--debug_node", required=True, type=str) parser.add_argument("--debug_port", required=False, type=int) parser.add_argument("--debug_host", default=default_host, type=str) - parser.add_argument("--debug_wait", default=False, type=bool) + parser.add_argument("--debug_wait", action="store_true") args, unknown_args = parser.parse_known_args(node_args) debug_node = args.debug_node @@ -190,6 +190,8 @@ def main(argv): try: run_module_at(target_type_path) except BaseException as error: + # Yes, all exceptions including SystemExit should be catched. + # We want to always know when a node exits logfatal(f"Failed to run node {debug_node}: {error}") raise error diff --git a/code/debugging/src/debug_logger.py b/code/debugging/src/debug_logger.py index 6778531d..317843ce 100755 --- a/code/debugging/src/debug_logger.py +++ b/code/debugging/src/debug_logger.py @@ -100,7 +100,7 @@ def close_listener(): conn = Client(ADDRESS, authkey=AUTHKEY) conn.send(CLOSE_MSG) conn.close() - except BaseException: + except Exception: pass diff --git a/doc/development/debugging.md b/doc/development/debugging.md index 9d364145..42003d96 100644 --- a/doc/development/debugging.md +++ b/doc/development/debugging.md @@ -96,7 +96,7 @@ Configuration example for the [lidar_distance.py](../../code/perception/src/lida ``` By default, the affected node will start up as usual. When you attach the debugger later, you are then only able to debug the callbacks the node receives. -But if you set `--debug_wait=True`, it will block the node from starting until VS Code attaches and allow you to debug the initialization of the node. +But if you set `--debug_wait`, it will block the node from starting until VS Code attaches and allow you to debug the initialization of the node. If the leaderboard hangs on `Setting up the agent` after the configuration has been adjusted, there most likely is a mistake in the launch configuration. From b4c3ed8843cfeaa829745bf38da25716b9ea961b Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 15:06:41 +0100 Subject: [PATCH 16/85] Remove pyrightconfig (unnecessary for this issue) --- pyrightconfig.json | 25 ------------------------- 1 file changed, 25 deletions(-) delete mode 100644 pyrightconfig.json diff --git a/pyrightconfig.json b/pyrightconfig.json deleted file mode 100644 index 5cafbb7c..00000000 --- a/pyrightconfig.json +++ /dev/null @@ -1,25 +0,0 @@ -{ - "include": ["code/src"], - - "exclude": [], - - "ignore": [], - - "defineConstant": { - "DEBUG": true - }, - - "typeCheckingMode": "standard", - "strictListInference": true, - "strictDictionaryInference": true, - "strictSetInference": true, - - "pythonVersion": "3.8", - "pythonPlatform": "Linux", - - "executionEnvironments": [ - { - "root": "code/src" - } - ] -} From 2302dc9d968cba94a4c22d367b4c161555cbea6c Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 15:16:57 +0100 Subject: [PATCH 17/85] Add rough architecture documentation based on CodeRabbit --- doc/development/debugging.md | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/doc/development/debugging.md b/doc/development/debugging.md index 42003d96..3e26453f 100644 --- a/doc/development/debugging.md +++ b/doc/development/debugging.md @@ -11,6 +11,7 @@ - [Required once for the node you want to debug](#required-once-for-the-node-you-want-to-debug) - [Debugging workflow after setup](#debugging-workflow-after-setup) - [Known problems of debugging with VS Code](#known-problems-of-debugging-with-vs-code) + - [Debug Components Architecture](#debug-components-architecture) - [Rebuild docker containers](#rebuild-docker-containers) - [Sources](#sources) @@ -100,8 +101,6 @@ But if you set `--debug_wait`, it will block the node from starting until VS Cod If the leaderboard hangs on `Setting up the agent` after the configuration has been adjusted, there most likely is a mistake in the launch configuration. -More usage information can be found in the [debug_wrapper](../../code/debug_wrapper.py) and the [debug_logger](../../code/debugging/src/debug_logger.py) - #### Debugging workflow after setup 1. Start/Restart the [leaderboard](../../build/docker-compose.leaderboard.yaml) as usual @@ -117,6 +116,15 @@ With the **rqt_console** GUI you can filter by node *debug_logger* to see all me - Adjusting the launch configurations is a bit cumbersome - The side effects of just "stopping" a node with the debugger are unknown +#### Debug Components Architecture + +More technical usage information can be found in the: + +- [debug_wrapper](../../code/debug_wrapper.py): Acts as a proxy that wraps the target node and enables remote debugging capabilities. +- [debug_logger](../../code/debugging/src/debug_logger.py): Handles the logging of debugging-related events and exceptions, ensuring they are properly published to the ROS ecosystem. + +The wrapper uses the logger to ensure that any debugging-related issues (connection problems, initialization errors, etc.) are visible through the /rosout topic. + ## Rebuild docker containers The docker images on your pc might not match the latest Dockerfile in the repository From 4db8bdaa4ff8fac8812e10194f3e6bab3cdd8d09 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 15:30:51 +0100 Subject: [PATCH 18/85] Fix message ordering in logger --- code/debugging/src/debug_logger.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/code/debugging/src/debug_logger.py b/code/debugging/src/debug_logger.py index 317843ce..4d45b6f5 100755 --- a/code/debugging/src/debug_logger.py +++ b/code/debugging/src/debug_logger.py @@ -136,7 +136,7 @@ def main(): while NODE_RUNNING: with MESSAGES_MUTEX: while len(MESSAGES) > 0: - msg = MESSAGES.pop() + msg = MESSAGES.pop(0) log_msg = "Wrong log message format" log_name = "NAMERR" log_level = "fatal" From 09342c27c09b301e6af828ebbc70063b320237fc Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 15:50:42 +0100 Subject: [PATCH 19/85] Add exception handling to the receiver in the debug_logger --- code/debugging/src/debug_logger.py | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/code/debugging/src/debug_logger.py b/code/debugging/src/debug_logger.py index 4d45b6f5..62f7eb4b 100755 --- a/code/debugging/src/debug_logger.py +++ b/code/debugging/src/debug_logger.py @@ -79,16 +79,21 @@ def run_listener(listener: Listener): """ running = True while running: - conn = listener.accept() - print(f"[debug_logger]: connection accepted from {listener.last_accepted}") - msg = None - if conn.poll(timeout=2.0): - msg = conn.recv() - if isinstance(msg, str): - if msg.lower() == CLOSE_MSG: - running = False - msg = None - conn.close() + try: + conn = listener.accept() + print(f"[debug_logger]: connection accepted from {listener.last_accepted}") + msg = None + if conn.poll(timeout=2.0): + msg = conn.recv() + if isinstance(msg, str): + if msg.lower() == CLOSE_MSG: + running = False + msg = None + conn.close() + except Exception as error: + eprint(f"Failed to receive message: {error}") + continue + if msg is not None: with MESSAGES_MUTEX: MESSAGES.append(msg) From bda286aae58d6adeeedaa376fbfaefe0e285ada5 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 16:28:31 +0100 Subject: [PATCH 20/85] Fix PAF_CATKIN_CODE_ROOT path --- build/docker/agent/Dockerfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/build/docker/agent/Dockerfile b/build/docker/agent/Dockerfile index fb6d9202..e2176159 100644 --- a/build/docker/agent/Dockerfile +++ b/build/docker/agent/Dockerfile @@ -163,9 +163,9 @@ RUN source ~/.bashrc && pip install -r /workspace/requirements.txt COPY --chown=$USERNAME:$USERNAME ./code /workspace/code/ # For debugger -ENV PAF_CATKIN_CODE_ROOT=/catkin_ws/src +ENV PAF_CATKIN_CODE_ROOT=/catkin_ws/src/code # Link code into catkin workspace -RUN ln -s /workspace/code ${PAF_CATKIN_CODE_ROOT} +RUN ln -s -T /workspace/code ${PAF_CATKIN_CODE_ROOT} # re-make the catkin workspace RUN source /opt/ros/noetic/setup.bash && catkin_make From 5716ef77d2853b2ca988a1feeb6d17153cf90a01 Mon Sep 17 00:00:00 2001 From: Peter Viechter Date: Tue, 12 Nov 2024 16:28:52 +0100 Subject: [PATCH 21/85] Add warning when debugging with debug_wait --- code/debug_wrapper.py | 1 + 1 file changed, 1 insertion(+) diff --git a/code/debug_wrapper.py b/code/debug_wrapper.py index 924f7037..cafd493f 100755 --- a/code/debug_wrapper.py +++ b/code/debug_wrapper.py @@ -134,6 +134,7 @@ def start_debugger( debugpy.listen((host, port)) logwarn(f"Started debugger on {host}:{port} for {node_module_name}") if wait_for_client: + logwarn("Waiting until debugging client is attached...") debugpy.wait_for_client() except Exception as error: # Yes, all exceptions should be catched and sent into rosconsole From 676073ee2bd6cccd89648bbc6d31b17918e9c3f5 Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Tue, 12 Nov 2024 23:43:57 +0100 Subject: [PATCH 22/85] Removed one version of the catkin_make task. As the addition of a vscode extension is no problem, the cumbersome way of selecting the task via an input field was removed. This now requires the tasksshellinput extension. --- .vscode/tasks.json | 18 ++---------------- 1 file changed, 2 insertions(+), 16 deletions(-) diff --git a/.vscode/tasks.json b/.vscode/tasks.json index e59d7898..9f845638 100644 --- a/.vscode/tasks.json +++ b/.vscode/tasks.json @@ -2,30 +2,16 @@ "version": "2.0.0", "tasks": [ { - "label": "Run 'catkin_make' in Docker container. Write container name.", + "label": "Run 'catkin_make' in docker container. Choose container from list of running containers.", "type": "shell", "command": "docker exec -it ${input:container_name} bash -c 'cd ../../catkin_ws && source /opt/ros/noetic/setup.bash && bash devel/setup.bash && catkin_make'", "problemMatcher": [], - "detail": "Executes 'catkin_make' in built-agent-dev-1 container. The container must be running.", - "dependsOn": [], - }, - { - "label": "Run 'catkin_make' in docker container. Autochoose docker container.", - "type": "shell", - "command": "docker exec -it ${input:container_name_shell} bash -c 'cd ../../catkin_ws && source /opt/ros/noetic/setup.bash && bash devel/setup.bash && catkin_make'", - "problemMatcher": [], - "detail": "Executes 'catkin_make' selected container. Requires Tasks Shell Input Extension.", + "detail": "Executes 'catkin_make' selected container. Requires Tasks Shell Input Extension, in order to generate the list of containers.", } ], "inputs": [ { "id": "container_name", - "description": "Name of docker container", - "default": "build-agent-dev-1", - "type": "promptString" - }, - { - "id": "container_name_shell", "type": "command", "command": "shellCommand.execute", "args": { From 634f678a5df379c314c326457bc8367ba0a23477 Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 13 Nov 2024 12:50:37 +0100 Subject: [PATCH 23/85] Add first draft of radar node --- code/perception/launch/perception.launch | 6 ++ code/perception/src/radar_node.py | 97 ++++++++++++++++++++++++ 2 files changed, 103 insertions(+) create mode 100755 code/perception/src/radar_node.py diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 8d6072e7..302a97d6 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -79,4 +79,10 @@ + + + + + + diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py new file mode 100755 index 00000000..b35060c1 --- /dev/null +++ b/code/perception/src/radar_node.py @@ -0,0 +1,97 @@ +#!/usr/bin/env python +import rospy +import ros_numpy +import numpy as np +import lidar_filter_utility +from sensor_msgs.msg import PointCloud2 + +# from mpl_toolkits.mplot3d import Axes3D +# from itertools import combinations +from sensor_msgs.msg import Image as ImageMsg +from cv_bridge import CvBridge + +# from matplotlib.colors import LinearSegmentedColormap + + +class RadarNode: + """See doc/perception/lidar_distance_utility.md on + how to configute this node + """ + + def callback(self, data): + """Callback function, filters a PontCloud2 message + by restrictions defined in the launchfile. + + Publishes a Depth image for the specified camera angle. + Each angle has do be delt with differently since the signs of the + coordinate system change with the view angle. + + :param data: a PointCloud2 + """ + coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + + # Center + reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( + coordinates, + max_x=np.inf, + min_x=0.0, + min_z=-1.6, + ) + reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] + reconstruct_coordinates_xyz_center = np.array( + lidar_filter_utility.remove_field_name( + reconstruct_coordinates_center, "intensity" + ).tolist() + ) + dist_array_center = self.reconstruct_img_from_lidar( + reconstruct_coordinates_xyz_center, focus="Center" + ) + dist_array_center_msg = self.bridge.cv2_to_imgmsg( + dist_array_center, encoding="passthrough" + ) + dist_array_center_msg.header = data.header + self.dist_array_center_publisher.publish(dist_array_center_msg) + + def listener(self): + """ + Initializes the node and it's publishers + """ + # run simultaneously. + rospy.init_node("lidar_distance") + self.bridge = CvBridge() + + self.pub_pointcloud = rospy.Publisher( + rospy.get_param( + "~point_cloud_topic", + "/carla/hero/" + rospy.get_namespace() + "_filtered", + ), + PointCloud2, + queue_size=10, + ) + + # publisher for dist_array + self.dist_array_center_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), + ImageMsg, + queue_size=10, + ) + + # publisher for dist_array + self.dist_array_center_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), + ImageMsg, + queue_size=10, + ) + + rospy.Subscriber( + rospy.get_param("~source_topic", "/carla/hero/RADAR"), + PointCloud2, + self.callback, + ) + + rospy.spin() + + +if __name__ == "__main__": + lidar_distance = RadarNode() + lidar_distance.listener() \ No newline at end of file From 76193d607ac927e038c74edfb6991f7d679423f8 Mon Sep 17 00:00:00 2001 From: ll7 Date: Wed, 13 Nov 2024 14:42:59 +0100 Subject: [PATCH 24/85] Add sprint summary template and update guidelines for submission Fixes #451 --- doc/dev_talks/paf24/README.md | 1 + .../paf24/sprint_review_meeting_guidelines.md | 2 +- .../paf24/sprint_summary_template.md | 35 +++++++++++++++++++ 3 files changed, 37 insertions(+), 1 deletion(-) create mode 100644 doc/dev_talks/paf24/sprint_summary_template.md diff --git a/doc/dev_talks/paf24/README.md b/doc/dev_talks/paf24/README.md index 4a2ada4b..70503b4d 100644 --- a/doc/dev_talks/paf24/README.md +++ b/doc/dev_talks/paf24/README.md @@ -11,6 +11,7 @@ - [Student Roles](./student_roles.md) - [Joker Rules](./joker_rules_paf24.md) - [Sprint Review Meeting Guidelines](./sprint_review_meeting_guidelines.md) + - [Sprint Summary Template](./sprint_summary_template.md) ## Notes for Sprints diff --git a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md index 3dc2228d..0c41eeef 100644 --- a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md +++ b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md @@ -17,7 +17,7 @@ ### 1.1. Pre-Meeting Agenda - **Summary Submission**: By **Monday at 11:30 AM** (before the meeting), submit a summary of your work on Digicampus. - - TODO A template will be provided. + - A template can be found here: [Summary of Work Template](./sprint_summary_template.md). - Upload your document to DigiCampus at [this link](https://digicampus.uni-augsburg.de/dispatch.php/course/files?cid=5b0c38206c78cc03880bc2e71997220f). - Inform us of your group composition and presentation order for our note-taking. - **12:00 - 13:30**: Sample Review diff --git a/doc/dev_talks/paf24/sprint_summary_template.md b/doc/dev_talks/paf24/sprint_summary_template.md new file mode 100644 index 00000000..27785587 --- /dev/null +++ b/doc/dev_talks/paf24/sprint_summary_template.md @@ -0,0 +1,35 @@ +# Sprint Summary by *FirstName LastName* + +- Sprint Review Date: YYYY-MM-DD +- My team members: +- Area of contribution: + +## 1. My work + +### 1.1. Issues and PRs I worked on and my contribution + +- Link + - My contribution + +### 1.2. PRs I reviewed + +- Link + +### 1.3. Work I contributed but is not directly linked to a PR or an issue + +- For example draw.io board updates. + +### 1.4. Effort estimate (optional) + +- Estimated hours I worked for the project during the last sprint: + +## 2. Things I would like to mention (optional) + +- Lessons learned +- Issues faced +- Feedback +- Personal reflections + +--- + +Submit your summary to our DigiCampus course page by Monday at 11:30 AM. From d537803e1b86b44418f326c6fac171b20782c1e0 Mon Sep 17 00:00:00 2001 From: Ralf Date: Thu, 14 Nov 2024 12:05:39 +0100 Subject: [PATCH 25/85] update radar node --- code/perception/launch/perception.launch | 4 +- code/perception/src/radar_node.py | 90 ++++++++++++++++-------- 2 files changed, 61 insertions(+), 33 deletions(-) diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 302a97d6..8320e3f5 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -81,8 +81,8 @@ - - + + diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index b35060c1..bd8f351f 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -10,6 +10,8 @@ from sensor_msgs.msg import Image as ImageMsg from cv_bridge import CvBridge +from std_msgs.msg import Float32 + # from matplotlib.colors import LinearSegmentedColormap @@ -28,29 +30,53 @@ def callback(self, data): :param data: a PointCloud2 """ - coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + # coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) # Center - reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( - coordinates, - max_x=np.inf, - min_x=0.0, - min_z=-1.6, - ) - reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] - reconstruct_coordinates_xyz_center = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_center, "intensity" - ).tolist() - ) - dist_array_center = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_center, focus="Center" - ) - dist_array_center_msg = self.bridge.cv2_to_imgmsg( - dist_array_center, encoding="passthrough" - ) - dist_array_center_msg.header = data.header - self.dist_array_center_publisher.publish(dist_array_center_msg) + + # reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( + # coordinates, + # max_x=np.inf, + # min_x=0.0, + # min_z=-1.6, + # ) + # reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] + # reconstruct_coordinates_xyz_center = np.array( + # lidar_filter_utility.remove_field_name( + # reconstruct_coordinates_center, "intensity" + # ).tolist() + # ) + # dist_array_center = self.reconstruct_img_from_lidar( + # reconstruct_coordinates_xyz_center, focus="Center" + # ) + # dist_array_center_msg = self.bridge.cv2_to_imgmsg( + # dist_array_center, encoding="passthrough" + # ) + # dist_array_center_msg.header = data.header + # self.dist_array_center_publisher.publish(dist_array_center_msg) + + coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + + # x_values = coordinates['x'] + # rospy.loginfo("Erste 5 x Werte: {x_values[:5]}") + + # depth_values = coordinates['depth'] + # rospy.loginfo("Erste 5 Depth Werte: {depth_values[:5]}") + + dtype_info = "\n".join([f"Feld '{name}': {coordinates.dtype[name]}" for name in coordinates.dtype.names]) + + # rospy.loginfo("DatentypenNeu: " + dtype_info) # funktioniert + + # rospy.loginfo("DatentypenAlt: " + coordinates.dtype) + + + + msg = np.min[coordinates['Range']] + + dtype_msginfo = ["{type(msg).__name__}"] + rospy.loginfo("DatentypenMsg: " + dtype_msginfo) + + self.dist_array_radar_publisher.publish(msg) def listener(self): """ @@ -70,16 +96,18 @@ def listener(self): ) # publisher for dist_array - self.dist_array_center_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), - ImageMsg, - queue_size=10, - ) - # publisher for dist_array - self.dist_array_center_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), - ImageMsg, + # self.dist_array_center_publisher = rospy.Publisher( + # rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), + # ImageMsg, + # queue_size=10, + # ) + + # publisher for radar dist_array + self.dist_array_radar_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Radar/array"), + # PointCloud2, + Float32, queue_size=10, ) @@ -94,4 +122,4 @@ def listener(self): if __name__ == "__main__": lidar_distance = RadarNode() - lidar_distance.listener() \ No newline at end of file + lidar_distance.listener() From ed8b7106ec00a22eecc333c9feecfc2c4aaa5e2d Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Thu, 14 Nov 2024 20:56:31 +0100 Subject: [PATCH 26/85] Split up Acting and Control Moved pure_pursuit, stanley, vehicle and velocity controller to new control pck Changed topic names in the new control package Added a passthrough node in acting, which passes necessary topic to control Adapted acting launch file to accomodate the changes --- code/acting/launch/acting.launch | 38 ++------ code/acting/src/acting/passthrough.py | 87 +++++++++++++++++++ code/control/CMakeLists.txt | 18 ++++ code/control/launch/control.launch | 28 ++++++ code/control/package.xml | 22 +++++ code/control/setup.py | 6 ++ code/control/src/__init__.py | 0 .../src}/pure_pursuit_controller.py | 8 +- .../src}/stanley_controller.py | 8 +- .../src}/vehicle_controller.py | 0 .../src}/velocity_controller.py | 2 +- 11 files changed, 179 insertions(+), 38 deletions(-) create mode 100755 code/acting/src/acting/passthrough.py create mode 100644 code/control/CMakeLists.txt create mode 100644 code/control/launch/control.launch create mode 100644 code/control/package.xml create mode 100644 code/control/setup.py create mode 100644 code/control/src/__init__.py rename code/{acting/src/acting => control/src}/pure_pursuit_controller.py (97%) rename code/{acting/src/acting => control/src}/stanley_controller.py (97%) rename code/{acting/src/acting => control/src}/vehicle_controller.py (100%) rename code/{acting/src/acting => control/src}/velocity_controller.py (98%) diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch index 5855c9fb..25e6ddce 100644 --- a/code/acting/launch/acting.launch +++ b/code/acting/launch/acting.launch @@ -1,41 +1,21 @@ - + - - - - - - - + + - - - - - - - - - - - - - - - - - - - + + + + \ No newline at end of file diff --git a/code/acting/src/acting/passthrough.py b/code/acting/src/acting/passthrough.py new file mode 100755 index 00000000..253e108c --- /dev/null +++ b/code/acting/src/acting/passthrough.py @@ -0,0 +1,87 @@ +#!/usr/bin/env python + +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from rospy import Publisher, Subscriber +from std_msgs.msg import Float32 +from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Path + + +from dataclasses import dataclass +from typing import Type, Dict + + +@dataclass +class passthrough: + pub_name: str + sub_name: str + topic_type: Type + + +class Passthrough(CompatibleNode): + """This nodes sole purpose is to pass through all messages that control needs. + The purpose of this is that Control-Package should not have any global dependencies, + but is only dependent on the acting package. + """ + + role_name = "hero" # Legacy will change soon + + # Topics for velocity controller. + target_velocity = passthrough( + pub_name="/paf/acting/target_velocity", + sub_name=f"/paf/{role_name}/target_velocity", + topic_type=Float32, + ) + # Topics for steering controllers + trajectory = passthrough( + pub_name="/paf/acting/trajectory", + sub_name=f"/paf/{role_name}/trajectory", + topic_type=Path, + ) + position = passthrough( + pub_name="/paf/acting/current_pos", + sub_name=f"/paf/{role_name}/current_pos", + topic_type=PoseStamped, + ) + heading = passthrough( + pub_name="/paf/acting/current_heading", + sub_name=f"/paf/{role_name}/current_heading", + topic_type=Float32, + ) + + passthrough_topics = [target_velocity, trajectory, position, heading] + + def __init__(self): + self.publishers: Dict[str, Publisher] = {} + self.subscribers: Dict[str, Subscriber] = {} + for topic in self.passthrough_topics: + self.publishers[topic.pub_name] = self.new_publisher( + topic.topic_type, topic.pub_name, qos_profile=1 + ) + + self.subscribers[topic.pub_name] = self.new_subscription( + topic.topic_type, + topic.sub_name, + callback=self.publishers[topic.pub_name].publish, + qos_profile=1, + ) + + +def main(args=None): + """Start the node. + This is the entry point, if called by a launch file. + """ + roscomp.init("passthrough", args=args) + + try: + node = Passthrough() + node.spin() + except KeyboardInterrupt: + pass + finally: + roscomp.shutdown() + + +if __name__ == "__main__": + main() diff --git a/code/control/CMakeLists.txt b/code/control/CMakeLists.txt new file mode 100644 index 00000000..a3c31c0e --- /dev/null +++ b/code/control/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.0.2) +project(control) + + +find_package(catkin REQUIRED) + +catkin_python_setup() + +find_package(catkin REQUIRED COMPONENTS + rospy + std_msgs +) +catkin_package() + + +include_directories( +) + diff --git a/code/control/launch/control.launch b/code/control/launch/control.launch new file mode 100644 index 00000000..88a55e26 --- /dev/null +++ b/code/control/launch/control.launch @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/code/control/package.xml b/code/control/package.xml new file mode 100644 index 00000000..9aa803d6 --- /dev/null +++ b/code/control/package.xml @@ -0,0 +1,22 @@ + + + control + 0.0.0 + The control package for PAF Carla + + Vinzenz Malke + + + + + + TODO + + + message_runtime + catkin + + + + + \ No newline at end of file diff --git a/code/control/setup.py b/code/control/setup.py new file mode 100644 index 00000000..a712859a --- /dev/null +++ b/code/control/setup.py @@ -0,0 +1,6 @@ +#!/usr/bin/env python +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +setup_args = generate_distutils_setup(packages=["control"], package_dir={"": "src"}) +setup(**setup_args) diff --git a/code/control/src/__init__.py b/code/control/src/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/code/acting/src/acting/pure_pursuit_controller.py b/code/control/src/pure_pursuit_controller.py similarity index 97% rename from code/acting/src/acting/pure_pursuit_controller.py rename to code/control/src/pure_pursuit_controller.py index 4259fe78..fbf6526b 100755 --- a/code/acting/src/acting/pure_pursuit_controller.py +++ b/code/control/src/pure_pursuit_controller.py @@ -11,7 +11,7 @@ from acting.msg import Debug import numpy as np -from helper_functions import vector_angle, points_to_vector +from acting.helper_functions import vector_angle, points_to_vector # Tuneable Values for PurePursuit-Algorithm K_LAD = 0.85 # optimal in dev-launch @@ -33,12 +33,12 @@ def __init__(self): self.role_name = self.get_param("role_name", "ego_vehicle") self.position_sub: Subscriber = self.new_subscription( - Path, f"/paf/{self.role_name}/trajectory", self.__set_path, qos_profile=1 + Path, "/paf/acting/trajectory", self.__set_path, qos_profile=1 ) self.path_sub: Subscriber = self.new_subscription( PoseStamped, - f"/paf/{self.role_name}/current_pos", + "/paf/acting/current_pos", self.__set_position, qos_profile=1, ) @@ -52,7 +52,7 @@ def __init__(self): self.heading_sub: Subscriber = self.new_subscription( Float32, - f"/paf/{self.role_name}/current_heading", + "/paf/acting/current_heading", self.__set_heading, qos_profile=1, ) diff --git a/code/acting/src/acting/stanley_controller.py b/code/control/src/stanley_controller.py similarity index 97% rename from code/acting/src/acting/stanley_controller.py rename to code/control/src/stanley_controller.py index 3463e90e..86b26221 100755 --- a/code/acting/src/acting/stanley_controller.py +++ b/code/control/src/stanley_controller.py @@ -12,7 +12,7 @@ from std_msgs.msg import Float32 from acting.msg import StanleyDebug -from helper_functions import vector_angle, points_to_vector +from acting.helper_functions import vector_angle, points_to_vector K_CROSSERR = 0.4 # 1.24 was optimal in dev-launch! @@ -28,12 +28,12 @@ def __init__(self): # Subscribers self.position_sub: Subscriber = self.new_subscription( - Path, f"/paf/{self.role_name}/trajectory", self.__set_path, qos_profile=1 + Path, "/paf/acting/trajectory", self.__set_path, qos_profile=1 ) self.path_sub: Subscriber = self.new_subscription( PoseStamped, - f"/paf/{self.role_name}/current_pos", + "/paf/acting/current_pos", self.__set_position, qos_profile=1, ) @@ -47,7 +47,7 @@ def __init__(self): self.heading_sub: Subscriber = self.new_subscription( Float32, - f"/paf/{self.role_name}/current_heading", + "/paf/acting/current_heading", self.__set_heading, qos_profile=1, ) diff --git a/code/acting/src/acting/vehicle_controller.py b/code/control/src/vehicle_controller.py similarity index 100% rename from code/acting/src/acting/vehicle_controller.py rename to code/control/src/vehicle_controller.py diff --git a/code/acting/src/acting/velocity_controller.py b/code/control/src/velocity_controller.py similarity index 98% rename from code/acting/src/acting/velocity_controller.py rename to code/control/src/velocity_controller.py index db1f53aa..a863748c 100755 --- a/code/acting/src/acting/velocity_controller.py +++ b/code/control/src/velocity_controller.py @@ -23,7 +23,7 @@ def __init__(self): self.target_velocity_sub: Subscriber = self.new_subscription( Float32, - f"/paf/{self.role_name}/target_velocity", + "/paf/acting/target_velocity", self.__get_target_velocity, qos_profile=1, ) From ae9f0e707acc8836e90baec7efeabce6ed230b60 Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Sat, 16 Nov 2024 21:36:06 +0100 Subject: [PATCH 27/85] Added control documentation Moved necessary documentation from acting to control. Added documentation for passthrough node. Adjusted linking in Readmes --- doc/acting/README.md | 11 ++++++----- doc/acting/passthrough.md | 17 +++++++++++++++++ doc/control/README.md | 14 ++++++++++++++ doc/control/architecture_documentation.md | 0 .../control_testing.md} | 0 doc/{acting => control}/steering_controllers.md | 0 doc/{acting => control}/vehicle_controller.md | 0 doc/{acting => control}/velocity_controller.md | 0 8 files changed, 37 insertions(+), 5 deletions(-) create mode 100644 doc/acting/passthrough.md create mode 100644 doc/control/README.md create mode 100644 doc/control/architecture_documentation.md rename doc/{acting/acting_testing.md => control/control_testing.md} (100%) rename doc/{acting => control}/steering_controllers.md (100%) rename doc/{acting => control}/vehicle_controller.md (100%) rename doc/{acting => control}/velocity_controller.md (100%) diff --git a/doc/acting/README.md b/doc/acting/README.md index f55e66eb..a8d9acf7 100644 --- a/doc/acting/README.md +++ b/doc/acting/README.md @@ -2,9 +2,10 @@ This folder contains the documentation of the acting component. +The acting component receives information from the [planning component](./../planning/README.md) as well +as the [perception component](./../perception/README.md). It processes this information in order to +navigate on a local basis. + 1. [Architecture](./architecture_documentation.md) -2. [Overview of the Velocity Controller](./velocity_controller.md) -3. [Overview of the Steering Controllers](./steering_controllers.md) -4. [Overview of the Vehicle Controller Component](./vehicle_controller.md) -5. [How to test/tune acting components independedly](./acting_testing.md) -6. [Main frame publisher](./mainframe_publisher.md) +2. [Main frame publisher](./main_frame_publisher.md) +3. [Passthrough](./passthrough.md) \ No newline at end of file diff --git a/doc/acting/passthrough.md b/doc/acting/passthrough.md new file mode 100644 index 00000000..d4e42d4d --- /dev/null +++ b/doc/acting/passthrough.md @@ -0,0 +1,17 @@ +# Passthrough + +>[!NOTE] +>The passthrough component is a temporary solution while beeing in the transitioning phase of +>splitting up the acting component into acting and control. + +**Summary:** This page is ought to provide an overview of the passthrough node and +reason why it exists + +## Overview: +The passthrough node subscribes to topics on a global scale and republishes them into the "paf/acting" namespace. The control package subscribes to these re-emitted topics. + +## Reasoning: +Before the control package was outsourced and became its own package it resided within the acting package. +Therefor many global dependencies existed in the control package. As the goal of the outsourcing was +to eliminate global dependencies in control theory the passthrough node was created as a first stepping +stone towards independence. \ No newline at end of file diff --git a/doc/control/README.md b/doc/control/README.md new file mode 100644 index 00000000..f3f069b6 --- /dev/null +++ b/doc/control/README.md @@ -0,0 +1,14 @@ +# Documentation of control component + +This folder contains the documentation of the control component. + +The control component applies control theory based on a local trajectory provided +by the [acting component](./../acting/README.md). It uses knowledge of the current state +of the vehicle in order to send [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) commands to the Simulator. + + +1. [Architecture](./architecture_documentation.md) +2. [Overview of the Velocity Controller](./velocity_controller.md) +3. [Overview of the Steering Controllers](./steering_controllers.md) +4. [Overview of the Vehicle Controller Component](./vehicle_controller.md) +5. [How to test/tune control components independently](./control_testing.md) \ No newline at end of file diff --git a/doc/control/architecture_documentation.md b/doc/control/architecture_documentation.md new file mode 100644 index 00000000..e69de29b diff --git a/doc/acting/acting_testing.md b/doc/control/control_testing.md similarity index 100% rename from doc/acting/acting_testing.md rename to doc/control/control_testing.md diff --git a/doc/acting/steering_controllers.md b/doc/control/steering_controllers.md similarity index 100% rename from doc/acting/steering_controllers.md rename to doc/control/steering_controllers.md diff --git a/doc/acting/vehicle_controller.md b/doc/control/vehicle_controller.md similarity index 100% rename from doc/acting/vehicle_controller.md rename to doc/control/vehicle_controller.md diff --git a/doc/acting/velocity_controller.md b/doc/control/velocity_controller.md similarity index 100% rename from doc/acting/velocity_controller.md rename to doc/control/velocity_controller.md From 4b90716f5cc1ca936e008088462d2787c22565e0 Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Sat, 16 Nov 2024 23:40:49 +0100 Subject: [PATCH 28/85] Updated acting and control documentation. No Code changes. Added new architecuraly diagrams. Added and updated linking through markdown documentation. Moved assets into correct folder and updated docs accordingly. --- doc/acting/README.md | 7 +- .../acting_testing.md} | 6 +- doc/acting/architecture_documentation.md | 97 ++++++------------ doc/assets/acting/acting_architecture.png | Bin 0 -> 112754 bytes ...ing.png => architecture_acting_legacy.png} | Bin .../Steering_PurePursuit.png | Bin .../Steering_PurePursuit_Tuning.png | Bin .../{acting => control}/Steering_Stanley.png | Bin .../Steering_Stanley_ComparedToPurePur.png | Bin .../VelContr_PID_BrakingWithThrottlePID.png | Bin .../VelContr_PID_StepResponse.png | Bin .../VelContr_PID_differentVelocities.png | Bin doc/assets/control/control_architecture.png | Bin 0 -> 129940 bytes .../emergency_brake_stats_graph.png | Bin doc/control/README.md | 10 +- doc/control/architecture_documentation.md | 81 +++++++++++++++ doc/control/steering_controllers.md | 19 ++-- doc/control/vehicle_controller.md | 15 ++- doc/control/velocity_controller.md | 13 ++- 19 files changed, 140 insertions(+), 108 deletions(-) rename doc/{control/control_testing.md => acting/acting_testing.md} (92%) create mode 100644 doc/assets/acting/acting_architecture.png rename doc/assets/acting/{Architecture_Acting.png => architecture_acting_legacy.png} (100%) rename doc/assets/{acting => control}/Steering_PurePursuit.png (100%) rename doc/assets/{acting => control}/Steering_PurePursuit_Tuning.png (100%) rename doc/assets/{acting => control}/Steering_Stanley.png (100%) rename doc/assets/{acting => control}/Steering_Stanley_ComparedToPurePur.png (100%) rename doc/assets/{acting => control}/VelContr_PID_BrakingWithThrottlePID.png (100%) rename doc/assets/{acting => control}/VelContr_PID_StepResponse.png (100%) rename doc/assets/{acting => control}/VelContr_PID_differentVelocities.png (100%) create mode 100644 doc/assets/control/control_architecture.png rename doc/assets/{acting => control}/emergency_brake_stats_graph.png (100%) diff --git a/doc/acting/README.md b/doc/acting/README.md index a8d9acf7..f2046e78 100644 --- a/doc/acting/README.md +++ b/doc/acting/README.md @@ -2,10 +2,7 @@ This folder contains the documentation of the acting component. -The acting component receives information from the [planning component](./../planning/README.md) as well -as the [perception component](./../perception/README.md). It processes this information in order to -navigate on a local basis. - 1. [Architecture](./architecture_documentation.md) 2. [Main frame publisher](./main_frame_publisher.md) -3. [Passthrough](./passthrough.md) \ No newline at end of file +3. [Passthrough](./passthrough.md) +4. [How to test/tune the acting component](./acting_testing.md) \ No newline at end of file diff --git a/doc/control/control_testing.md b/doc/acting/acting_testing.md similarity index 92% rename from doc/control/control_testing.md rename to doc/acting/acting_testing.md index 49bd88e7..108e3c3a 100644 --- a/doc/control/control_testing.md +++ b/doc/acting/acting_testing.md @@ -8,15 +8,15 @@ ## Acting_Debug_Node -The [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) allows you to tune/test/verify all acting components independently of Planning-Inputs and also lets you easily output the data needed to plot/verify the tuning/testing you have done. +The [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) allows you to tune/test/verify all acting and control components independently of Planning-Inputs and also lets you easily output the data needed to plot/verify the tuning/testing you have done. There is a dedicated [acting_debug.launch](../../code/acting/launch/acting_debug.launch) file which starts the acting component **as well as the necesarry perception components** automatically. It is recommended to first test the [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) with an empty road scenario. The following guide provides instructions on how to launch this setup. ### Setup for Testing with the Debug-Node -To use the [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) you first have to edit a few files in your current branch: \\ -**! Make sure to revert these changes when pushing your branch!** +To use the [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) you first have to edit a few files in your current branch: +>[!WARNING]! Make sure to revert these changes when pushing your branch! - In [dev.launch](../../code/agent/launch/dev.launch) the [agent.launch](../../code/agent/launch/agent.launch) file is included. Change this to include [acting_debug.launch](../../code/acting/launch/acting_debug.launch) from the **acting** package. As mentioned above this includes everything we need. diff --git a/doc/acting/architecture_documentation.md b/doc/acting/architecture_documentation.md index 5c1aeb9d..f4699186 100644 --- a/doc/acting/architecture_documentation.md +++ b/doc/acting/architecture_documentation.md @@ -1,68 +1,46 @@ -# Architecture +# Acting: Overview and Architecture -**Summary**: This documentation shows the current Acting Architecture. +**Summary**: The acting component receives information from the [planning component](./../planning/README.md) as well +as the [perception component](./../perception/README.md). It processes this information in order to +navigate on a local basis. This information is then processed in the [control_component](./../control/README.md). -- [Architecture](#architecture) - - [Acting Architecture](#acting-architecture) - - [Summary of Acting Components](#summary-of-acting-components) - - [pure\_pursuit\_controller.py](#pure_pursuit_controllerpy) - - [stanley\_controller.py](#stanley_controllerpy) - - [velocity\_controller.py](#velocity_controllerpy) - - [vehicle\_controller.py](#vehicle_controllerpy) - - [helper\_functions.py](#helper_functionspy) - - [MainFramePublisher.py](#mainframepublisherpy) +- [Acting Architecture](#acting-architecture) +- [Components of acting](#components-of-acting) + - [passthrough.py](#passthroughpy) + - [main\_frame\_publisher.py](#main_frame_publisherpy) + - [helper\_functions.py](#helper_functionspy) ## Acting Architecture -![MISSING: Acting-ARCHITECTURE](../assets/acting/Architecture_Acting.png) +![MISSING: Acting-ARCHITECTURE](./../assets/acting/acting_architecture.png) -## Summary of Acting Components +> [!NOTE] +> [Click here to go to control architecture](./../control/architecture_documentation.md) -### pure_pursuit_controller.py +## Components of acting -- Inputs: - - **trajectory**: Path - - **current_pos**: PoseStamped - - **Speed**: CarlaSpeedometer - - **current_heading**: Float32 -- Outputs: - - **pure_pursuit_steer**: Float32 - - **pure_p_debug**: Debug +### passthrough.py -### stanley_controller.py +> [!TIP] +> For documentation on passthrough component see: [passthrough](./passthrough.md) -- Inputs: - - **trajectory**: Path - - **current_pos**: PoseStamped - - **Speed**: CarlaSpeedometer - - **current_heading**: Float32 -- Outputs: - - **stanley_steer**: Float32 - - **stanley_debug**: StanleyDebug - -### velocity_controller.py +### main_frame_publisher.py +> [!TIP] +> Follow this link for [Documentation](./main_frame_publisher.md) on this Node. - Inputs: - - **target_velocity**: Float32 - - **Speed**: CarlaSpeedometer + - **current_pos**: PoseStampled + - **current_heading**: Float32 - Outputs: - - **throttle**: Float32 - - **brake**: Float32 - -### vehicle_controller.py + - **transform**: broadcasts heroframe-transform via TransformBroadcaster +- This node handles the translation from the static main frame to the moving hero frame. The hero frame always moves and rotates as the ego vehicle does. The hero frame is used by sensors like the lidar. Rviz also uses the hero frame. The main frame is used for planning +- rotation = - **current_heading** +- position x = cos(rotation) \* **current_pos**.x + sin(rotation) \* **current_pos**.y +- position y = sin(rotation) \* **current_pos**.x + cos(rotation) \* **current_pos**.y +- position z = - **current_pos**.z +- rot_quat = rot as quaternion +- **transform** = position x/y/z, rot_quat, Timestamp(now), “global”, “hero” -- Inputs: - - **emergency**: Bool - - **curr_behavior**: String - - **Speed**: CarlaSpeedometer - - **throttle**: Float32 - - **brake**: Float32 - - **pure_pursuit_steer**: Float32 - - **stanley_steer**: Float32 -- Outputs: - - **vehicle_control_cmd**: [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) - - **status**: Bool - - **emergency**: Bool ### helper_functions.py @@ -95,19 +73,4 @@ Interpolate linearly between start and end, with a minimal distance of interval_ - **_clean_route_duplicates(route: List[Tuple[float, float]], min_dist: float) -> List[Tuple[float, float]]**:\ Remove duplicates in the given List of tuples, if the distance between them is less than min_dist. - **interpolate_route(orig_route: List[Tuple[float, float]], interval_m=0.5)**:\ -Interpolate the given route with points inbetween,holding the specified distance interval threshold. - -### MainFramePublisher.py - -- Inputs: - - **current_pos**: PoseStampled - - **current_heading**: Float32 -- Outputs: - - **transform**: broadcasts heroframe-transform via TransformBroadcaster -- This node handles the translation from the static main frame to the moving hero frame. The hero frame always moves and rotates as the ego vehicle does. The hero frame is used by sensors like the lidar. Rviz also uses the hero frame. The main frame is used for planning -- rotation = - **current_heading** -- position x = cos(rotation) \* **current_pos**.x + sin(rotation) \* **current_pos**.y -- position y = sin(rotation) \* **current_pos**.x + cos(rotation) \* **current_pos**.y -- position z = - **current_pos**.z -- rot_quat = rot as quaternion -- **transform** = position x/y/z, rot_quat, Timestamp(now), “global”, “hero” +Interpolate the given route with points inbetween,holding the specified distance interval threshold. \ No newline at end of file diff --git a/doc/assets/acting/acting_architecture.png b/doc/assets/acting/acting_architecture.png new file mode 100644 index 0000000000000000000000000000000000000000..fd2a780dae5fd20c4e54cf8ca8c91929740d7fce GIT binary patch literal 112754 zcmcG#by$^K*FC)Hk`|CIC6(@0xpXvd z*LPosL+tIo@3q#PV~sh-Six_Vq%qM+&>;{ArmT#_I|u~X4FZ98MnwjHxfy;ifk3by zJk&It-hFbVvU9LCF}E_Na&osbrZRRj2QRwK7AKm=JZFrNdUOoo_h%IBhI@~*L;Ck* zi*b{PSJOm!G<0U^=Yw$?sk}0@J(bRW^Xkgpr$olLv%<%q zGtgF9=6cQT#>40CqJ76w>I8~!Eqcq^e|?u`c%O1#VzVhHv6q)+Q?}8~rc;ON-cb8q zH+<>$mW$pOb>GeGoOudwLe}rp(M2g#nhLpOGtiHci3SmZJd1|o35VrrT4XA{DN$s) z4hHhHn!83yYgjp~c~{&-^+V)PccxVOWIOYx$oMwbbLv;F^pDBveA2=atL;U+R%y%I z&I4RRjt}vLGC?WIi+z~KkyG^dL#*E<3u4+GI_5Q(y(R@anNBNfMh6^M8-Cx;y}?WJ zMy8SwYGfnUqQV%HmrO7WEf2=&R`RFg%u`;aL3k&}MMvzIrTr#U_@=TxueX`!hekFf zaBmn_G5 z3yVw`!H(hj<;4=mt&R7lmB31Yca>lIgv$i+hjGrjA=WR7i_*l`&O3N*EKjPcGndx?f(K3K!hoifA8t7OfQ-?>+7Peq%aX zDH4pB?wG%ybGulFRk+n0=|051@3|}7zM_z1dLV~mh0~$kfAhDd8o9L{zw72o#$tC7 zVbEOssO-Ql#Wh#!9+A^ic>({3q^$^-W?oHGM3JM%W|3aDa^5A}`$AfEe3A2$MrRr# zTPo>SK11EgDH%K-el$&|wl~6z!?gt&E+ppPq_slcK5eSh)?Lmo7#!iMwUB6`VNziH zE|&_;{#?*$Ub9Q4JVN~G=YsKo2l}T8;SclTyE5<07FDcy8omec6PoU6=e^ZJd)6zy zPaGWhCPXTlmrh=sq320=O?mwom8CqMDs#h}c)9J(ZNijBBR}R~Lbn;3xP@?XClAF0 zJ=-vYY;ymzneAwS(A^BazJU|uU%AE>p1IQIvkG+ww=RqhMWoPQi{m(a3h73Z-8iGdS-u1-dQjFxEmbpnAXJQ{;Aa&}dBX zl}iHGV|FoyY*wuC`yV8VFe8i{M8z`$xN9*^?+&O~mn{A%LSlReRvkV;pORJ=DX|+n zoi2wyCR^l67Ti1%XOC&YGHw1AT9?i~SMIxP_u>)AbU;vs9>atP$1WaIg;xc9HGf{U z)A~JEb~RQChfa)}`X>JK+Kg zY;gH(HBh)f3NvdJYKAeqwkIBVsKEvp@GqJ?jX#GP2n1!Qp2yX@Rahz@ah}HA>r@+| zof??)-iIS2Qbg!&TfRUP=baWmn{5$8KFO}BQ6Tzxp($s(_NMLS@wfRa337{rMEnkQ z$S5K2#gj9(137a`vY`BV>^q@;s^zDRMs0&K zH@(qm8W|I%_FX!~n(GmMwH}rWYg9rbZ>8bNE!X&XG2br1ICu zb0?n%ZC-!h7D_JY{+tt1lA!^WI>(ms$-hJJMg7~R@WGxpxu7?3SEz{{P5k~)ALFI* zwZ3-N>ob`QG%wXEow)-Y>l6Q+DNGM}@9?W>Ag#y)FOG9qw7{t#!C=U5QMB+eF-I6^RvGJ^M7;!g)3e}fM7 zJy_x*JbB?8QvCOW72b5h1(Wm{&U^H{C1>2M3aKZKodTZufYpN47?H%byh5g>LeiPVfW(`zTnCNYg! zTKhKEjXU=>DqI>oG;KP)_EZcM{Fy<2%(j~o(&?ESHtnvl{meg!6&d~Hmu*jLAuE^!&Nr^lluT5uB@n}#Rjbvc z805)H7ao=-Q_Uh*XK|z)-U;gCTTN5Zzg6tpo(^Ven?9~_h@sY3yZjT4^{V={`HVH& zAYEfw#v)}M4+7#iB2L`fRn}6rO7xcD_g5v^$2<#5&y~I4SJX0;A-p)9EL(Q#=xzlB z8Bu#I0oN>=hZ?WWmQ|eUBs`dhBWkuer?Jk5L#nz7>%>{in6*%_UI*0OYaJq>K8b0f z#NPbEs35SMz~3Q70GHLAQXXgY%D?A^AyqA@s#$qKiLG~GMqp>Kog5x1YPiYad!EQ= zp9GY5nU`iF5CbZ7Enh+zH=2z3bEf;6w*z$~Y;YX@#(8*oLBvuNRVc}lnAhJD(lzZh zW+vFjo1_TdV2@+Ftg-MFw-q4U&h;2Bqaa`fLX zX)X`a+XQ6@vJy#uewDrrG$O7M)d-5ErML;6Y)%lZ`O;Z38-5R^6)^ zDByoWWL>YYQ>bF!&ol4S<{gE;x-ZB1Bh|ZufoB}=M2m|oL?RQ(iLga4)9?elM#s?K zB6Vb`GZl~Zv{_cicRI^lHOp|{=52^JkJ$6WMcl0|d%CzgWVxFeX5ehvs+ffC_P#CY zqCCZ8O`FDdNo9HGX>FH0Vokw8etmY8GklW363OOn2qpv#OyGSQNK4R z`f}&Y{>-@V&l&w#gYk+jrAsBgNwSFq>7C7XootHT!nq248fst^Us{N&KMu{HPE=x1 zy&)dV)lI0=+))UVzSwhdFELclC=%W7dRl*FU+-64dTf)&n%f{usm8kQce?ER?5lbO zM$p1XxvhFQUyg83x(HFLuu%Rt$U$Ge+sHub(}H81rv|^k^QzT%&^4EPtGk&j8LIkW z;SsA@EIn9vX6;EMVp)HtpVIr8m`}6fzrK`WH{JM$3^rUNT&L@^(cm{5)m7E5|ZZX%i_^CQ$K@JJ%GE#g%1l{X5VYQAX zf>a-z$tIxM5HCby&x4yO;?n>^7ph_xa@t?Z0aecD9fdTwB^giPNp++vsj5RgKdbgt zXAMTnz;{#z*;aWr8oZC%ImeF+{BT#e)2u7O1veQ!yShWAR0qmC)X#APm6kVHy zl#|xK2a@)h#%lN`spj=HZX`b2l_Br2V}3c=JS_GM5gg%e(Oye7p=!}X4HJtPi28Cm zMY`)hDj=nlLeP9SfM&?&aC-cirX%JVO`-_48w5U#B{e^Y8QXN?3Ga*Xn%fF(`Gt~> z*XI|Xp;nx?EOUjJovnnHD}GrI-*9H?H|4#UgD)7LLOD_&C65(fW~xwLZ6CG_MRPOX zZ)@W{gfC_5DQj;wDyaqAQpHTpsn0-t*yPqp$(OasW>Xs%aa(M#MUSA(^QE{g^-Inp zL%4TyGL#6v^Iqp78SzEc-V3rYkt{_rzpa0AcsDS1sOU5d$K7}&KdidlmBe(C-9K`Y zVT;o?OOPnf#z$YR7bq+GaP|xS;diO0kJVG;!2K!LBRa@Zn9iRA8`cFEsD+Dk;*F@$ zZ|ISdRFCY9iYFs~oh^Ki!N8SJCd!VG76tD9ZEn`I>bl8<3VoFS+l;?Y zUUMHRb!Pe`DmCbdjRmvuD;0dg-;Bt5(@9~wa+@xw(P z=Y8HRo>JaT?Jy?Wqb;)|{zLcqQh2fLQipHD@-J%X9$(kqH3V;8+gXd@l|j+lp@E-Q zxr5D{L(pSa`WE**GwZL92#0d-Uh1yo{)9l_zM6}Rzm*ji|8FM%)c+~o(ZVtvVq{%< zsz0*`kP3tNjPjKTB_zqJ(IxY7EWUjpS75pKr^A#D3C&*CvO6{`-(6lUD*RGNh3ezS zC&qjsXi&6s`px{PO$+xzdo&>Q0$N2&h?lCO_Ee zW$mlT^q|Kl7c9RkwbE}LoeGIV;Y6a{eh}v>HoX>VHYZJi28+LBE$rOtG^G0&brroA z(rugK$buonX+(#A)=6!^KGi9QU)fZEtBf1?UNO&$dZWD0J+$(}%gP(!Ym6_%-o}Z0 zT!FY9G(V_bfA!};XZS7k^+W1Y47AzEnq%yGpI{yIdUXAD4KXwlqbckMl-9=TidcNz zcWmfYt$c&ss5sL|76jebA}%SjXv@CHCFcRHYDgv`vZY*A$GF3lm^wPVT*laS^Ki)N zPiEpi_A0CPn0$tE-sEx(yJ9$%xHnHg?QbB@3kt6=?d(v)HW@sdyBYUKF}+S}Vp&CD#{UWZC=2>r`B#PE!U zhUTD0Ratl<_qx6P3(C$!VLVo+BpcwK=~ zV+!wc6)Z}Tzk!rKsA6y5;u!u3TZvT`Q4s?Vo+Ce3Wsa|1Yx6TVH(+@9EixuaXTC~y z%Y{cg%SSnD>sP!BPGgd<9)Dx7;!si!S=TP)et8a?3#_x&(^H3s2WTs&%{(6mCnteM zw2O?eTh2#D78aBHn+u57aXX5eP}-T6&DrKa(Z|L~=v^;;`gj*SE-voQ>4zeX_7DPQ zGjnrlZf=73{;u7LLd_<(lUiL@b92T(Y|0N&uz78ed7!5`i1av?Y2!f%)-)grpcYNy}fC7}=nw(s2<<@ISlYa-hx_=krF ztC@;#^Yc1MNl73;^!wr%JG;A8)zmr#kD5BlK6Nm#u;f-$#C-jV*z$OPROz(yj){p0 z;�e@4lTG==N~EwX@L33vR&0&CTw(sQ_EK(~bUuqN3+)Y*ByzDgG9#VWytD*pE9o@PL;e74N+k`A zXZ-y9raHFo-xJ8kvlvenX_5)Lgw0f%B9!^udr){Czka8xn#gBQW7~8RfaMPc?}Yy1 z#S6D)-O;hJa*dbtF}~T+;O%EUw2{kOThcy0BK<#J(LR6v^<=GERZnjyh2PQ4%Idt> z^!D-q%o#o|?rRkl+__p?)8Ajwoc1O$V|zPOT^DzfYxDDiggq~Zn>}53_x9YkQeDl= z%=GWBPNolBez1J(`;36%WCzQAhC;BRk`^~Ja-!DtfM#18(+;&N%#%7^U99vjION#`=!Fu}R9X)IF zIi6H@wCj?0{HKn9ll{t}RhLFIG_-b`T6_wMh}Kq7y4c{lx;oC1Ig9EFvk{s%;^MtS zLt7x@G7AcVYZpB*N~iikxGBlWp*Ol581%-x5P%`i=*q;z1RM?tiASGPXxHj(pzq#f zF+|7r{^IM`ulnU08Vyd2?(XhjSdgf+w80$NSO!MMm4n))+=d2{{`d&z23HA#%l8qsqOj2Ay_@Ij3lI_m9e? z?e?eHVF3b16>3bsMz zjEt--oPK8zF4Hjx6PY|5GO{NrS2Y_`6O)spq7Jx zLiCRLZEa$DSk64c9_M@q@EyIZ%U{2J`^1x6P*5<^4)PP%Jo|2F!{G$r%v){ky?(f% zA4A@$U`afohZ`WEJB>I#@$6Mp$arQ@&*m)fX)e1%7hJEqSbf_6gp+>8@2EmTK{2eH z>FMuBXghE@TaQ&fy_~bX{UJKl6;K%*7S_39XSY2}4RP6@&P1RFin z+KHRj^(a7~Uhoy%y++N)_bhL0=XTP>+vK^lrK+HsL%Srdr+u=;{{ps>AAl)DCmmWVtO9;*B)s~}OK6OWsuWxMF zKi)&vEEVpzET z2_uHUa7*a^eC(xelLm@7hyj6b0QW(P7X13PT0Ny}2*9=JX19=whlj&%S*+*-vv|N0 zxaI6f5reT@#Ujm018h9o8bUd)W(1Q% zv*i7tuBR6{wqrC^^3m(=q#M#=FkGLqPoVbh-S63IOOO{RN?vH%60;HLLZd7x`^}ur zyW^_4dX59!YHDg_E(cn=9y>2g29mlcAC6H7Uuv|iMT!mzL+26NnxTvGVD6PguGf*O zJv%UYk3ptaI`4fDxjPoOsox+Ze*!~nu3Ux0H!dzbAoO5sN)8vV|o;SB$7AmLx zs)U7wg+{dnflFhmwrw*(zeczc2ii?d; z*L%-*#-vfCVEGe%+A14M_X%WYtqnO?j06QbbaeCaU5+#gUJ?!Yp4npb6dXS3-o&{&HH^U_Rb$iE4u9sGWDfU}R*Rcj$j*HCq+@ z>lf4A{XKyw7)iapvhamka&>BKEP~jF4?nQJuF``k?$eVviB(bpm@ZE$?7{Wz+qW=E z(X{Dl4LNyvcMv6W-uBYqLH~0#@BoVNQPaxmC4k=S>S}_#Fg) zo3QAzsAj_X?;im=QJV$vfXDdn6^$i@MDgEW!1w>}zyFz!=53kT$(Wc38(RpOTkG6$ zSv?i7uTS9dVWxIcuQM*x< zKD%al()~&8v{SAQGNsQI^~J>ndZ%PxZ?6iDL{2{mSX=AgsZrD&(PWevUbn1i; z@rf9Pl;$ajY-%y$r-H{8m6Wx@}2ZKz`oaF6p_c)5Q+Egbv_vharfLVFvq)_;$M zFHyUC3O@2wbi;SFTGVs)T+}3Ts$=Bl9g~GTpO&7-YF-IqU}dyeE6%=8JEF!HwDU^C z%2_n*Flrtyq{11>!mfaJeE==Gmj_PuseB&?s_Mw98px{ZNEi!W<(3;`M@)K&f7w`LY^>&VMp(HZ0?28vFfw7w3>rwirNpox!_bEpfR&JoX#iUvSIC9E{sXMrDQDGu$z~P>*_l6+nx$(hTl9&)V{Xv1 zNFjFP6O%zFx`H+QtyctYVX1Ka{gnCN!5bZVyL97FT$fuABmVxDv1D;5^VfY^QAbC3;yDt zeB1tz-I#A79v@hSU$@m&# z@1ATrZlzeb}kTBz&bC$W9hn=UMR9xj#7u+Po;$LH4L{J}_cx9!4OyuN!O zGJhkWi=eRYi$UD0xM*%Pso2Uy?3%l8t|Gp{%>;r@lOceV{&SLa!p?Tv&y0JKd7hSZ zT2)06a)zlePOaJrKv-_FI;IGS2r54vAd@LZVCeD)WsyQ3&qV?vNfzl2^lV-~tRPAT z#*(Efxhuk1LRk!)AH1ZXAO)^e1ipaMMSx*Ly|45?xZ4u$c)85TSCh;;^%!6s=-9i> z9bN8iOEpfh*LY>e=*8j7==*T52dT4}zfg;#+z8}6G*W0S|Lf~3GRBbySGL_Dsl(~P zw1Xy|n8Nab|!_%IN|7vGU z^k;p2qO{LBLp67G9AW(FFgE2Mi|W(iA>4Fc?k@dNbY%-{8_liM-xj+ z!cHjrR)IcKn@QfKrQe_2c4b`g2Uy@)?td&W%g?a@vpK!;SmVZ}Y*PunT+EixKa)~g zI!X5Cak6aES4Pd!4d2*PR61Js-56|9q~ZuH9Yu==QBALB=9tYWe6Wa_%5= zS7U;4Ppi`5754edB)PCbDv#i`~ei7qELCQ}UW#GS5`^3{x2gt*1 z@YdB4ecG8KD+^O@Nez}?PTV3Ste2uAVV^y(I6JfDGYEk{VMFJNq-;hI3=s_(ciDQ| z+2QD&mhLsW2v7=?`3xX~^=E(fBrHAUBDL$6-n`jw_^fNU+oc|*#?PP7)OY^^I&Dt> zPedW}60a&|)sV7je^)}`M#}SeEbrjBgs}mrbL2qoW1+D1Tvd3zZA*8vXnp*AlXF0jQ~143M^wz;z<18DTeeTK!s*;LEAvlc;b@z|$_tPuTrXSvV@{69|>5JJzdLdD!X> zMXQ~X{;6{=r}2;8;Txep5SATM1x)S}P7J~OmVa*PZN^^9*FU0Qvxx{Ncc5T%uI!>E z{H1$1PgZx^vOPLJS5EuXD=m+Tfh|~kzr(Avb==+|^f+F6wMY5bH+tRw3@k!(jAyDd zC7n`o&&e-~$s(POuZ5L!>-qtRPNq(M&R+I*-0spf+xxIN7yrk;qoed^EgbY?)+oai z6O{_P7wAaYuV;I6uw*u><8|{|Y96Yl=yg&RFXOCud}^YHro0EwN%IhncPb|G{u1F5 zx2G>Y&?+h_-mOOKy>+jO5pB6ZxjEkxH#m~;dAteb5=^>Y@NJeca&mpRx};=JRLrY> z9Lu9LoQyOnH#k9Gyz0;+juj4we|!LC`bp6(n~wt_T`X>GKe*#Qk6^}UpY|N+Uz3$f zU%RH0{6RZFU3oJ8u`zF$Xf#-sOc}A^P8Cz?Hj&$){CK7FN7?7@StVui0D@>^t75J3 zpRb90Nn~CXpJbD}ja_>^tO!ZRkQXLxA{Q!$L@?T5oX0f_>@^9kl+2f2ZHE<#3WvV< z=IkAVDe3z@*c<8}d0Rbp3-V^INF5yj!)MU2Qq(v^>CLnlXvzgE4xZuX;^tA6Y40eqK@H&8{*a<6g#yx>s^{&Z&z_83EV3sgD92N^P)|JK)LTp4DVow5)N;cHnn>U>Hx1J* z^&d_ox6OZx^U#&~%RB!3O?FUFinjX!HP-usy|`OK3b(94`P4N&=Licx^{eW%-ug_` zJO8AfB}uX@uofx#!t$@#8^ubrOlA_iQwrPR{n0S1#r6ym6cN1HjlD1sUc2NrxZ(3S z|H$F|N9`u(=kfM}=t|OFsmW?paO&nV50AQ|JydP>GGHEOCNkiTWq@0uw{ZtdLBYp;SdO8DZ#uDPi<*gBu7*pw$b;M3fTK_ zi(CXaZmM60{+hMAb--GOu(`G6%U872?1#fzwBXt@VJTqI7qg`0vD6P-jCK`Glz)7E z51L%YU0DQocc1B>C9%gXdV8chCoTxOaMF1yTt9_1GYvC-wgcwew*e_>~OBeMek^M%7x00)|ZGC+zzRm64;X z?|i(@TG@Xcnf><3f>$xpQP%CyFIagde5C&XIM3Sqfz5n*1ynQ&%j=I-=FZ`Gw< z(25K_@{sD43*y55g7c41P(ZvP#ZbpF!_1O)!;4h7qqLzo$tbNu(62=PC-2xWA&cfq zy9+5+8z*!PA$Q>a_)@zrY;=_)CdTum&sOgRkI0V+!4GGbceU35?Bq5^y+8*n56Xk@ZPw{y zeLS^3ZSDQfMEqU(9IZga$FPiNOWw7GCySsoh*scJBu-i zdT+AB!y~XIzXGtvuKjX+iWdi$*nU=kPBB?V#taogD}|kxS(4e&m0A8X;*}&bak>YB zaN~=;Cqy8q5&kFDO#H^TGu5~$UbsGbam3`};0>Pyq$X6lVcnx#2wHpWth|G5!ucfv zN^)A13Up(dQ_%uc6VPchF6X*u<2>Ys;_Y~&27&BZc`YBAK)wItpJPh-OHXNZndYB9 z^C$0`lD*25r~Fg1U>BB%&*RYbiMXrd0<^S4pN);*uupS~nGV_`)Z+UgCYEcf%4nCds z@vLyW5zm>D?3`q?Ik&MNfXHgV`zNn_aaOOZ5J4v9unwsqC^htMM?dWop)bFMcu3_i zI#@5;y%#}}c3r*XBOaxVWsWKNZBfC*2Bw-k=$}*Vf9+)=cf=lWPGLCxz9x7;l7Btk zmPVurTllvsYK^n%Q`T$&X@af^Pyqj>@0<*eZl+^nvq5|?@kIjNqZ|a)f6VY4n_kaf z1OsU{Di_3`6DTtuQsfU?kU;w&IC5LuN`{8VGK$6njZbS2GzqeD94Nz!xzBeeBLSzB zO3#NQVFC-46Z_94Ge}@H$*e2W?fiCOFq<*g!@SfN|C3bneFNxByft{^fk%)eqal`) z5loQtbUz~>!a&^~!_ z%j8nFu`H*Rg4KZ1HTsG#4b}4{HHpRg(`v={YCLi8-s|<1-*CJ%5%mbjW8*Pq^3FzH zF}+lc0*~A9Kc!so^}CWH+i|KJDNOi`U*-P(hMs(C)#_(s3ttS_NWugVK&bt*4}xLx zP(p%^wk;(i#tSO+3&k@x;kZdcl@H!QAq{vT5eJ)Y9k^QaSa$<1R+FIp;R0XudAi8u z?(gU67LR>fw9ZrV@YF-6+R=Th&XHNa?CNO3so-wK;_xayQoAaik$sCci&OfSY@nrL z=HYsztY8LjpBW5N)HxS)EM(?3)WZq51WC&^{mV2Fj%#PjHI)WR;lU05ucP7gY_rB{ z-i&ROmMfSdQ#Mb*wLW#6FG6)pO}02Y>1NYnH`%hlT;PqlGkN%cGZ#N8q%5H*L6I;F z86Vb{YyUc8^v8(JkRyqWFr=Mm;t*R$Nn)*x1+@ z^v#*5tb2eOgpV%{8m*d|n&?3w8KZfC2q@w0E$r;<%$KT!l!K{R`~iqAsOac4?CdIV zJ8enH$>!G9T?Z~}E{*o}I(0fMLKKll*He0e*H?R@5W3i%D$2?kuUW(Fk)RnXkqz#` ziICRT7BN`hkO$U(w2A9|^Hn$m)pMMG%hIgiahEiGpiWpR#fDx<8AC~(SxK4MCNlYh zItEKAJ{Z^Bnn3h1@c@`01!PW>SOU;R>oV&y;xJ^t0fFBETB$sm$Gj*w+os(H728(0 zJ2WDXcaFN=7w-vQX-TAuc*`g#Jg1`zSYFmg%ESEr{d>7_KOq){P|w5tZ6c2~Nu}u! z9WAYRJFbe)3x}ESadBnlV{|}_Rd#dZ%goF~L_%8G+R9rF5HpYauNR;y^XA5*udgq^ zpkU?dWGyErhs~f9b#-lxAcbdqbo7m?Dn8IM`N*(VX2)kIklNzk-%4mS_#uOT z%!__bM3s752PrFdNSQG1B_Re+a=4$LU*!XkKY>JrhKf48eEz$0vF_Go(>rgr+QXf;c2{`w~cuYWlO8Kr&?aeef!2eefu$-z4!lOJ2gE zpeShzVra#yUnj#t>5peMeSEkNBNzO!zi;*C&6}qQF8MVzKkn|lHV0GXfy@_6r}*2X zl94Swp?@Q*p#eNS2@sNjm;hAwKhUP1Kas$arl&74B1Hp*%Zi7Tot@qEWx})YgEa~Z zipZ^^uKb1ufxiBJ<;2O+QUC6>cA#2EMd1Kx5e*ab#q;N#P@$JEpH$8i#lo8XEd0hm zP;3J#ZrxghAke*$B_$$fO;uKV?35)*qxA5O4=zFV>k<9e!E zT76CKXWLVyl#wDg`K5t=Rm#-V)J8@|Y+hG(K;Us(3+GMXcccT_G5Vk+Sf@;&WdoIB z=?MH!OG~S4?jY|edrWMs_czSOg~iMzW~pr4#)XIl8_^@APz1xI0I4pH&l>|ON~AmERqfvuuJ6h&jCpZ=2)0e*V`y*JbWi6fFmj@ z3KJbYpofYkCUh{-5lD&XVL?G&mLLI}?l0#Q(u5Mh!ZA^i2lW~m0Qnf`geQ~Qw)WlR zt~f+Qd2K1*<__>yE^W`em}pntVGf1ezs{3^hV3Nno>1&byXc51$%pTAd!=a`lJ92E-O1bI3j}X z)vNIBZL_XDJi(a`Mt=V5s-a|B=?J^^9$YMPfzGXTUnNCF%$1cDAd!z{OJjSSZ@<>i zNbqL>D3Aw)S&4?K^!t6&zX|N(U8zdTV9K&GGW=kFy1OX#eJ>^{{$%%lGC+zxp5r$j`t>FGnj$^ikM0~A?V+2=1_>|iK@r-9FJqow&cO{C}59`iz; zfr;rIn?P`0x=&JPr$o!uDuz@9Spmq#9wcT)#!n!Dgl@L8(WU64foO2#`{*erC)Xgs z-m!L4284JZsxg2ks;>T?lk@!M@}R#n7=Hpk=SxszB)y18no7159KDAwxrkT7@855L zHQ~#I#S2Ep;KgRou{>qUFsW>RI>2d>3Sdt($z0m>8(&%Ib9#EZ|A_3>_4P?7zVdM& zb1CeBX^4!0&IywF1GIHpLV*t7usZ_wm(-dzpzs1^n3k0_5|{x%7)if-hsV3+5!~5CdKeASX&17|^W!32)qXwpnUPB^PwDTL5!BdP@LQI$T1+KR}d+ z<8xR?MM6S?iG7ix4+-n*Mx&#nGV=1Ob{`qr> z_H83@Pw-0~aBg&Vc7kdE=x$bXHR0e%;b3ltI7U^}Cr^ZqoL_!yh%45vEm_G>YEW@+2ar+h2 zTVSlPJKr8T(<%WA`5y~TNN6Z9Zm};ky3#Wh8_7`icTo9S#Bct%gR= zYFFrx=Nzxqw3wkGE!a_jAMA(s?WKJefjXPTI0FD2%@(g~q^?x}pAe<6XEiA2mbm_{g>hYJbYd<2`%k_F7yH1sOReI=X#- zrZSPs91p+~Y&ak(mmTWQUxT0=?afDt404j)*w_GJ$bgforl1f8^llo5cHksJLq~r{ zB~Xx&K?Pi80_!zfo0~Do$?{7r-u1VKjew=rJ>Mf2^$`LdmR#T{`J2oe+0-PIm6g?E z&kwvwhLOU^ZNI-^z=3w&Z<|_G;Bjd2z8&1Ve~N?C2J#lA?cZhqps1!z)ucCd<1FvV zs;aAZw|z#Cm6Q8zP_Fa#rT>>NaAg`VxAwge={=}Y3xq3Y_O*HV_!0o*fKfaH`ZaL7 z0ON(o{kba4+6K0{L6X|oipol2c7sky$|V4hAXD>!UyPSG9)NE&Fp&U%-orxbvVI)4vVaePt!^G{oLgkM zdj=_Yzg4ZQiddyZ(&3dODTKWuEiEnKu5OneefosDBPk#Mzz(x00-(_Q z!2{?8@ap6=HIXgHv5Il?@*;Sx#hU;E2*iUsV6^DgX9MwL4y=b%RLi7uq7LgljFI6| z*|y&FwbTp@+hLOFv1bsF|1i!6SR`;=73nr78TbDfY4!Deg8Zel8`EwPDaVmt-ILzE zS$ApJz0zbL%XBCW{2M^-j-gP~mEYe?!{-2Sz_F3A9^~JEJ>qW)e=NYelf%X%2Uy$# zh-;pK5Hx;;~wccjaTEqZs%TeCDh-2m zbrk^n9RF0M+lc{S+puu8sD{4^VFuU(d++tx76Nc~m8*t`(-S{I4wIq<42VqFBd({X zC)DD|h_$WR6ACj2fmaGY6a!-P1&m8YN9XTH*M*DX)l2K20I=iYI;APSB^(_&W9gMA zla;`B_JxB95fB5|bOck@5n!S)coGRoNp?Uw0jazK z=1O7?qaOaL=$IHl=J0`0O&{3iz6J!GexbaB#P*(t9{|r-G9WU*nf3Z;u{n{$7~L)l z5*-yKCMk&&h(&Gy95`D#L%_MS189onREcp{2mzRUyZehN1o}hHrz9kDz>x^hrLL~7 zvV@+NwnP26VfymsVow@aAM5Mu69!CdTCPpBw6$SoQ-GOXN1jWxOia7lT?g+_(a=`F zNb<6>{JTPl_QHWRXY_Re3~S{6R{(el^O0sQPuoOH#K(~FN1=L#!P6`ifMqXt+){!S z7<$UzeZQxtD+BK%bjkP8wL)=cXGh0<<9nWBIsi3LOPmTn-Uz{rPv&Q)Mn+N5(e~{J zb5=Yy4LiAGx!T1aY#I-0Q~_fVxG0*#AtZE}y`z_ul5$w`hNhlWk7P@80uHcr23(h% zK6h8P^M{VrM1YL|(DWWUa1n$qdL9u2=$)^qr~skSu;0C8!~rAD$9ban!Jw!CHqQ$w z0-!bMt1aV3EA52j1Y5n-X+IUFEX%Y*%8sG?H4JFfXx9bmo}#QX97@FD=J5$U-fz#s zVcMlcaQ{kBC<33RoQ(}jVq#(*fyajuo!QxNV>A+(SlusIU zb}PhsXHe+Ypy1KI+SVqB0F8QwpD^5}A&&yzMj4T=105tsB`)J^Gk>k1GDE%c-$cUX z6jSb7e9FmW!;1|*Em8))2I+4U*N3NL8B_t7q<;<<8u>xp2kJM`pThvI{b#HmlvpaT zi8+Ad648oh&e+lr_(sFX_<<43U5Ek?A0G_^!!o{`Nkrr!PM0tBqlE<%*fYU?2^e1~ zZy~rNN)~*ilWgFx%W{_`8c>LG>Sqk9V2V|aeMZ5CX)=9H*!&;#B%v7^NCo(X=D$X7 zo5;O4FZU;a#rq@&fRV?NZ4m1Lkoz z7!nrW4}(DvE4a}t;z$%b4)3y%WAM1&e%^-vuz&3rm;V{qRPfmJ*{`GVxTEa7OE#2~ z^;G=?>WBSobY@JG0AV?OHT}}XiqJD}_nW$%74HH(ZGlD6awn0f!dDc@G3F-L^mrTa zMElpT%@{yp7$sM?TFr1UF*EZ!ZR6Nw(aQr!=Wp^SE}Qxe$Z$ZiShYoK^NU{3e^4MjM*v1E^axmB zPV8Fb<}~0`j`+hN0KMQmn8JTzJ#V>ZV@P>#Z>GW+gDw{BOS{;cH}F#*UCCV<7kDH4 zH)upfTl*LGLDrt=0O}O))%^44&*${?2=pPA(b3WK9(%>09yWY@R=`a~SS%kJRl$jHjN1w5Q4fL4RI!`eHb#0m}$MnpkT{rEAw z*C;D9^K-djH)#KFFSUw-;y$~nsj2^|+lOMUE`Sj~V->(gg76M({{laO1Y=~-N=kqV zF!f|-p;@%K5vop=qX;Yidt>R-9n(Nr1gN*$?LjRt)&d<^_VZdNjs>V`)@$Z$Xaxk4 zUdaC_GwQ`N8BFN~aKQNL)yBi^5g-W1pj!|PYK}VlHBh-4%-7k2;>m8#x)u%)VAyer zFyQbN5uwN)=|R92@@v3$%N!RDv7y>H{ z6&1Tc>t}XW>#qstz`%g1H8UW2fFra2dpDNK9+^tsoh~eQV1BJWNv@L18fABlSgs&ZTns)$*gjFl#4Aew!%s#(Z}l{g(R-v^Ye41=GG-A z>@?7%0i7oAA%uT1DA0ZbhaNBpUuF~)g&iNmHt4~bNpSQ47#&xJd>=R)U5`uv;6Pv; zpS9)6A3Q%evoKq*)(l7ttkFQAuG0?Y^*jKmvpa1tU;tP2;Lu)9iy55BqmI=`B9YoQ zzsvr!($uB1&rUI-S8X~!rR;1EZ3LSa|dc4KHQ`Ul3{@(D4?tO4TH#_cFui0 zTAD3U;cvR=W7USXwzm6Tacvza6#&l!S|8w9UVAzYtVnfE+uHf`d4XKD}nI3NuG zG_HdP`zaksaWe-a=IyZ71nf#pRU6Z&AnT6CU_J*Q=JRltjzG`CQVLcG z(1P^zhx5FxW=xyfThgO~(+cm0hOQplc?i7@xFz+0EDd9 zA9nzWnxGElowq{(tr|f2EA-ppVcQ5OzyXAVolGZYZR5m^jU;^D>uexl;3ITt5^RRB zjv;t#caTUsbG58s+XevPRKS;$n|lh*2(US<%K#d94J_E;zzK2&IOqWI6J$0ZjsSR| zac@B96Oc?$DQmX+2!nps`G6~EC5{3T3#h2u@@EuKpM$E#Ps#Z)yRT0U+-nAO-oSkT zYgYAr3Zuzru(pG$1NRRDtT0tjvPg8&Q+d1$e<5#Q%d_HKtD}~QqI6zF%x&=$cAg2q z2Yc-_oEgXJyVXv zXMA>4fZBrE4nD90c2MbRB+>^_3^WV?Ia!kyy}<<)M-I40NC-N}4Pss!GH}WXKouEi zPSPo-DS#6rfMg2qxs?1rw!Q-#%eVhq6b-9MGSX5iDw18Ol!Op6i?T;{wvti8uOwxU zWM%J78A(?5CRy2g^M0;=|L1+5_dVX{czTW=G(|!0a>N6*m;WM;{nYpGh zR*uk<6H^l_Yl*c_h-rWMG#+7{^kfTJuaFV-q+SuFbIUIBuP=IZ0w&jj zl_D!SNvv<}%?_N(Rf#cLFB#`;Utgvs<4^pC_m&Em9n9-fMDTz-qm?k?+a2V8~ESSC<;%gV?U zqczPQP0S;v$eJKN!`9@dfHzaLs~HHh6Dm$je0;x&)9PQu96J#2dCE?Bl%6-~3q`G~ zZmbG4r z=(C|gK|f${YSXLnEib=rHQru^r<&x3wDeHBL6Xq;I-y4iJ|+%-*b5-Y|Ghv$ms;%rW9`zb?>Acm7rJa0;8mS+;mVjl8Vt9d2??tAqV#8j2n)C#5%! zg~!@cJrOF@Q}?0Rtb1tKB`#Vrk!GBQt;dy4oj2uG%Plw@0m}BDS{&dDMB}*^gB_rV zyLazmb0A@J3sx?)=fgl4Ass4AlD|9{NKZ+Q2lId@Q5^um*YX>--vnfVmW7m-mX>(r zFJ8PjH`?NZ5nAny79Atw4~$Bc)zyzM;{$(tgU^n}-8|ZZWE2U^|b6OwOfP3trw)O?hQV)~P zn%UiZ_I$b6qDpoJbcR9m=f3JoJy_h#e2)sz-Vjs=&q}FFa&_Ru}_@TQ&Fip%r{Af3I|6-9KqNv)I)1D z)LvsUgYww`cVo{#ieO45S2tmiR+S&vD4wpRoMdQUrO@z-3!tO!_anTw1Aj~NMz!h2y0UF z6-hi#c`1&$xu@gOMi{)vT}4HJDPH^rAE#5>c#lNX&vw@j@DBn8hf{Y3xLti?<3p;g z+sMg({rSVLv7Ig)gdtjUg8#sMDQRwg2MP=g-up`?AzLk<(~5djz1{lcdG-~CDr?P? zH_J+_KkqBw_HdN(0o7Ex(51IVWN$cih4G+M5xt2)ziUB(5CJk04pEEy13g+m^_vTa zgoK1J_T7Q;gqM&dfsbE1l$=Hdnn}fsc&28E3q8_v2;pHhkPYl%}ZMl=l5=7iS ze?Eh~)eCsKfI#5V(h~Ko&66i#vazjjIAR|KoD4gi*#>~b(DPIR0s>fVv5AT01PfGn zT}M_{c4}ck8~mGYhBCmz6TYz>%Uj`d)}ym{+I(IH#^W-2oDG9E6Dudu)t6d*RBT(~t-dmbE)~?yP}HB-Tq~bMp*_6myVCmNr8*AD+9r z6Nt(Qsi1G*K+ZF8PI_*8D{&lHVRHBWyZ7!@qW$2t82%??HP_jhWHd6tK(Iawmf<@} zN;gDAwtyRM9zVdq@Et^PE))F$(e13IQMXA2MOCj*7itZ7KigF*uOVqu-p{*oJ6S5t z@_;AcwqWnKv08E>_e0-)b_E{KAnR9Y- z68>f489`SGdK~PP75^kyKvZxOY&7Bt3Mv)fMvR5UL`9cciZ;sD7khd*zG1>3$e-41 z)1&+M??34$0TeiASF292|Wuk<4LaNUAuPmV^$c5jSe9tEWLtL#bmhLzsAR_ftG#4$HVG+F#W3x z`#hyHK8Y_|$dibwkrq{RDtM7aT*zOCgisg%jJmbFShRT?1Plg<%P=q#!$Kcc5*wJ( z41<>btf) z`?sY$b!v<9YIi8)0ffhxgTov9unU%48z1h!s)eACkhH*tH=a|}oRPT#v{#vS<9&TF zu6cLYB* zI{Gi3IZQpP$ISqvXw%3AX2+#ItE7(aLg&w?bj|rr3bv#mApcOiU~-FDFf~Ht>7*&g@?%lt79;f2Pb(_HuWpn3$Lt53%GA-uH{IZgl>w zzrWm_JM|O5gAZa&<`)!zG=hF-H|{jGb=?kD+)s<^cz8T+dB+ygJ2VTl+LZQj%@hdl zZ`C6>Oz__l78cwjSv`&dPOBX~OBmgX;nT1DN^|)KZsih|b8Df40C+_Bx&zR_n8SYR z`{6^|$lPS%Ds_f(H6HQ=J)`dY4?y;k(Yz85KH=0i(E5fZy$zggsN>2hJWt1jgqRK; zIz%{Np%Ad_u0h4ot_`V%JpC&way1%3KGR>%=hulT9rQFU6B98=5JTSb(B;ij0x?*e zthVy#S-}5Az_g54NAEL09g=omOG~WCah>1dkiGtuUuYf)K#ZHAUO!{lf?rit^)pSd zl)F^4SbUSZRmlrfHf$fbe#7&&aq;m9GzIF?m`bp5SX)~ggnf2`TL0W$qVi0h*usqZ zvsgCR>N9o7Q-*J0RBl;0P1`FYeizy&Fz&<%MWT{vNN8ZtY?6##DPv}4mcM(KFzllR z_}t*bB+xuESJUaZI^NpaO7JYGu?b|19qsKiy)HBn^6bkiqe%p1i%LzdoOIX`gN^i| z-pX&^ikq98ZMRK8ukZv)jf6=y09Oyc(UN?U4wbU9${Y*Adwf1@ikOG-i7R`ABG2A8 z*H?7JQx+E&XZ7?|P!Qv&0kk}_u~#GOdogV}@bdF(nwaz$w^!0c$+odI1GCUNN6+s7 zPDe&VqsKU)UbobcC$e6*eOs=*g9BP{64VVvMMZgbJ;&X6wX3yxF$VN!Z#O9g7@P}a zNKWU@6b?L;@}8mn_Sa5b2dc2-6tUP;ibtd79R{x7nag4u8f#ixbH9ZgDJ@$VXs&oB zKmx;ShIfg19KtX{Yz7ZD>R()6UCfeV!L~vmVFV5l7x$9L&Y)9&5?(bDtd`Jz;Ng~b zwc8`3qXt5+InJIve(qe|iaJ_r@am)7Ne4W)IRoCXQnU@RZPHO3*~$9R@%a2{*5}zC zqiyW_LqbBH*xFk0`QXFdKZnnW>L-@x4A=in_pqB_ge0Q&_(`}z%Qc@fZaOoXxM31+ zl9`^a!~&7qtIg20cEYG1cqhIom^>2q4qXWL%Pn?xc8p9+rjH;0GkpdXWsL*Zy}Z2K z$|tkuSX!ImdcmKu%}gG;C|SLAA;J00%pN5HfjldkoTc79v4QhtlJ|bxeotAUo5)!% z??ma_M}O9>S!dKj%;0OJR|2)`_lXuavb<(DvM6#xM~8&Qu=M&cnfCBxy#$MU%CD5# z8II$htGufF>5&t)+q2E1tx?zLo35UI0lWG@uX}q63p>SSd1}YjwUy6iYeu=Er@BbC zv(~6%e( z(W^^K;Ldd&)a2!#CnY7#XS5k+ZiM>zZA)L6bTXrjF&YcziaPy#xNF6)^6{&|T+PwV zv$92d{C7J9?+#XA&~)YP;bx%1L#C+MV(j!OCFS)e%-SOUndJ#w+jQHRjr2kp=SJ91 zHa53f&e&yUX12DqRg&)$-9DWMA3LE?gT5;<(VLK~>FdWNB$VAhr{uy5?g0=*q|8Z~ zSozlWb}Vn7>yaamcZ;di4gT)E-BCsbWRi*WG8=_UyQ6^D^`j7dAmO(kh)}V_#}(ZTs{|LbBXUa=)G4 z$(7x5S_eP5$x2ckKY4MYHK!uNl<9f75v`SRN^35)X!zS;jqUXr0B~@Ty1TmpM^F9o zbsiMe$MBh0{WR=FOIaLIH#j?L+pri{9}6q*xs zL(M}_ouDkA3#`VCzvprk_X9mE^mw1G9T!{$^rQ;RW5%gFGo9t{+} zBAWC~t*t9?msiI6`d9_7apv5&lQvfi&v+U>(sIQ+MW2(QMWi+7y4EP;3xjWh++>>+ z840J~2js%~Ry`6l|<7>=)9Wr@<; zY#o;e=m7qcyhjWW2S-8|{RFfQ7#3z3I=4WL@eq)>WH5gd|Lp{Y(0MZmWp7wmSolvu z#*hpJ531?IXgqqXS3{dyTW=r(3A9u5VJVfv(PzK)O-y)4N3#)Co7|$kTw`KXp55=_ z{RSpHSIy)t(D#45EJyf>eRKjhMu zV`5O_X7JzO&93M_z)PW0ad=2MlZ13?)B!MfZHt5nVNS#^yvSG3fa%L5qW zUbZ}FWVsq^^`+ZxA9Z1*>C{25_ET3EuCv5E&z?$6K)JW01=Dr*p6ol<<3bVe_=4Hfh5uT13fK0z@MI zv^}r^1VbQ$?~S<`Y|sIZMN6+)d};^ zopY!(L?Zx=^44OI_ctXae`8A6w{M>e2wvrcOlm8W3m={UEh4nBbtB57d_=c|;cbYK z7ZE5J&m$YcYKXw7FcFtlV9@#*0kLw?Z$d((pw<)-5gE_*ID7iE76v^0(q#Q6cGSkl zmX?ne#@e1dc|v>WP*vV!VHH43R_kdr3$zin0PG?^etZsT6mSPnOemwhBO@=evM%8h zfofJFqu=TJEA{kIY;a@aImhfcUKseE8}dP(-VWqB zkGLFp_Wj=8-WcAHpma%PLIz-9-6@vM2$w!&@e{HzQC0K^y$;BY^^Umr>J(|eSkrw#7mCSfq3kyC{Kaop$e=Y{RJE57n$0)MDMw17Am4ZSJd(RQ!BY`z%^2i{x(3fbRIk#)|(?*X%>1^}%gM`A zncN^c-sikM;1oZX1VL-!%_QKKmnVS7?unfp7q-38YwQt28QUBYRQE9WQ_Cn3JB9ou z%h6^aB!r^(Vk;i@V`3y04Sd_4Fi4GsEqs&J_qKnLAa}Cnsbc@`lQy7zmuO`8)Dl&I`k^M{<%vqWu3#R__&Ly=Obe*Lz6f33XJHb z0*YfBq?fOZ1_pnsFNR@bawWt{ z^k&;L6Y+oVhGp#~6YG3b@s@bXu4eJ+%4g@z89H^@L|x=U7aIG zYuwx4kLGJ~87RpOia+Loj{~QC5xX=Lx%Vn2^%e_$))hl!d;`iN@DF`pz(+4^w}7ZF zOJK(&$aYW#%_Pz)JtI3^iCQz7&t{#b0P!XWRuV#Z3t1T%F@0elB?w}SHzb{%ov3cU z!Ky^18@i3(3_T3M31X7|cQ^*xyBp6yM7{3Ee{5e%MQcI8)!YK2n!&jv+ceTL(ACWi zbcJcN;Cy$s{#fuyiMy@A|{EaiN^ZAsqW_9~2o64$=P>vyQ_fXC8p`^aPPXh6CjaDJUD{5YeJx%nZ-m)s0 zFW$_zL^e|uU;HDLF2eP&c7K<`+{IqvtGB)atHnh ziqR)I^LyW2IgJhvm*BZYn^RmF?_=YP4A*T^H~Lx}%>;IQ3hHz+UZt_fwJ)m_BC$+4 zQ+3LOecwyD!7K~O)sNOvEs;sT8Yz{Aj}*P*Xr9cXD;mi1-KvCw~X1`q9)~^Y5z@G-O!|Ybdu{L~>G+X&D%JmfYu!uhr#dKySutzjO}Fkr7=O z-~83KhK9Y+gmAbBXs3MuLEuJt@R>xD?Mq!Pt%i{&f@&b5n~QzQG)oM5xJmIaTlRzaBNmX)mP9g4=W0+>kWxkYICsR+gXSYi2+gz??U0oV| zf8oqhs>)k~A)27_BJefKtfG27V2WgwZo?<&jGdaaG@ zcG;pgD}KY4Y;#oEd9D5TqmTUT$&lV^^||O?NC*mh$ovrMjuPl+fbp1Hte$8@H>5xU ziOpeYc_@^SkrHq>vtV}Dnncta03u;6qXz}7&Y*|KBXr(+qSJWjI681pVq^()r1l6j zLl@wJR+N#EQP+55oVpa#1OzgV{&sSuld?!PL>M6$=o6q5!5@J;ECD1gz_jbSsvx!; zp!*OpUVzw|u*B5VXe0U%wEHEf(D9=p0E)c5{TF2@qlFS;IhAj1e7`eHQ{dCmyUD6M z+`*gYVgK$(on$SMk@pmckuBxt=!13+{KE-sk^r%hWHG(C{fwHlqq=9;2!& zeRQ>QNsh&(eAd(L6t@mqcO4PbIx#ivq*qaiZwgo~3$vLdKhuBpyckF`3G6t65( zFgv~IQ{*f@rOC}@?BMKn{iwC@47W<=!(P%?s;ofqy-@!kF^v^>i|E@8H4y3c9)px}$sY}H!z8X=;6bkfG^yEzK? z?qGnWX?;@EsrUAbqBo=?35?UC7Mjvhd;?8X4+r02HuIn|A2QkHmU6%S%0U>OX=nv{I}_#9x$zE6S10KVM3 z4hg6an}O}U1BVn5jmZ{j{{?+zZQSWsn6ipDbm|C2N{gbk|(SgH-w5FTD$Q86(d2&(hL z5SI#ktSZxxUnnExJ>^^D<)al@T|OKSIYh*IO6yrW+b8YR`_5~3FVHf01vm-YvsFmT zn~gtnKgV;?@^rmU&(izU8TMyu4qIYk6NbXsHp;?c9_x=%N`A1WnRg=(*(_Ss)#Wzp zV%ZdpDlA_CNUT&+cUsfqAZ@wzslesm@lAru-!y+wi1+{bCHZG2E6>lz=Uw8%Z^bw4 z^E+);8wSp(r1hnbaH4HBjZfVZU%dKk zk48n)roMM{m)OXsj^y{0W*>K%zL^);b?21dv8y(-KbUT=O$UhZ3bad!SlXf|yYR?i{(Fv=)*pbY zN{XP`2?M}BG6D7zMBxlX6ebwN-voe&V>am{dS85n@6 zN1LfZ{BPGUfU*LW>T$wJc<|uCxyhbT=mM~&Brzm@Ty3fHxE{%h9u%a1Dg8nq>(H2y9!c&bxZ;`P9J6ee7{@%d29Z*(Yqc zZ&z1$Zf4OfJBl%E6n2xGS@~)hvf5+UR%mcpEV}E<>$M}D7B#JUhAAm`e%4mRt1Q2F zTIW``o8kQ2lN!9^QfFEHGfjo0o}Z6az9ur3w%2MLJ(kRJkI$y{q!F(|yKPjL_@>$m zIHp1i|qAz;R z>kBbT3KTZbPY2wx6>4Z`fW08j@GFJT0SPs{0V;>)C$syhu{1tD-dfl0*YOXl z82yEZ+Y!7v){*4{d=!dy^u8dD)n@1pWbB$6PU{{h^%kGHZNDSomZ3qv7~4w;06_d6~>V zv^@uc6oh$;YXgLx+YI@PRpN`FI3+@fQcBxm|%)+xO zWUKXaS_jvEp8{)$*&z&jQkeu^a?irTLTU+s)9v+9si~0tw2EkJpCF700T)L<=X&q= zH*w$x6$AqbtXqV5W58eI1Qf*3e*qWasGQFvf5LttG?IVRi1fOXTW~^)9>wDPv>8S3 z{e?TCr0Yx5(c_+LA49uyPvXUZl}j=w-5)-lhor>bkeb9GOC zRZO^IU8iA$tcHtkb4k16>WETJ3f$}?MN7>(pYMg1OZOC3d@E&rP8BL5Cufkw&TPzY zHF;UGAbg8Bh1~)RznSrfU3Pt)?y;hn=ZBp%7RD}jCe-Q`RM4JlbpQ3L=%?oAVuvY> zff$0&wEgh+dX%a=q#4rS0_dq0Qy)T<`fFF|zwn`4lbjBsnc<91vcjDO}QK z!kZnv8;E6a#%XydK7W2BHSK%dZ_}f7{QOhHT$|b>)~8g>N6D5dZnLr_P5of&^QIm) z(7)L>H_J!&ZR98CsnZnqn`kbZ4jq*?KUVZ!TW++t1XVFIr>*q1wb1t-Y??`m374bi zbZ#?I6h{;Zmi2@gDHVZEHNAsvIxR)1KK=qd z4s&}f=gEy%XZOB+=a=^DtG|aAzxl&)@8z_Sq5iT>!S(XLpWf+leKqAl`bw2hj>y>9 z57S5Y@;OGl8P8jotqZ$yoOHBK%t|{=Ep%{$S$>WEI`+LAa_s51c*1!6CKtdJr8d zz!~Lq54g3`O#81B#=Du>Si;t+}`a2Zp3yo$O4wW1DzSzFw zcX{51J5wHwjOl$cD~1kZ&Y{w9CoP4xUqUn0!g+~Ko2xxro{XhbaCjQ2gw*F2GApXL z&aZC_36gxG+*SD5J1XI{_3MJup|4xYcON+PxNXwO|4>_@!!7F~_uN&XwvLXhF@K8K z%5~DozNBCK%+!Wv4fAMXHPi~{<6*Q(Z)t{3X}>eH(+fXtT3<7;wi20mEtHz?_Op4d zZ8b>PsqLCA$&ocnAr+R6G|${MQo+RhJqb?5Hk_C1v%W3t7xgx0!*aPs z`ttf!bSVT1XO1s4Z-}WQgiD~#3QzhN-EAsy+RI}zd%S6>?x*Gn$C+xi z(BDO?j1Nj2%CxNqz4!@uC~?E$b48PHBO<) z*fp0Z_70E-)f8DO3ub? z%)KLwB1ULt|LrFCldF$z=3SBQf5G%Gdg;Slw6HKtJ{O%B=KLvufqh}@-4!2ViI#5r zCpfq|*K&0G_U*les}mT`q;_7L+W}$%`%{W>7r(mGx+Sdk;03aEXOdEz$XV6g=Y%r# zFJ|h`PpY`_c>EEYypyu&C!FKmFE~STQYqN>o?*jayWm)XxGK-;q0MGf2GbCVG@D_SYAIJ4%%)ofp==kk(jBRoC z+7tEtI?o&0q6U1|nR(Y#OvY30mVpN+yDZw51uxo==mbsLr@mJ%k~R$fsux$8LTSzhPrds*CCuNiQ~;cDs;IZe4bYM+2(en5$jB%otpetQW&)BoSIXWcWGei;NW` zMN--%r%FQ8PgO^+eVaOB7{ zU|rLM=K9h1x57@BeBxqxvTEr*>-^Xn7iS=Ia$mC^hm`X7#iR<$V&0j|q|&l`c2ZRv zqjE{+4L>R=U+#>K`S{9}X2T_vYvI=?^TExH{C~EYCvNGz;dp)*%L+x_0`r%uuYS>+ zL&n;-3*w~xRpiu!nZ=k(&d<3Ce<-5qAg@%nx1oI2>ewpp^56=hDsd1@AVR{qnZI zoDko5`m32!FoQ~@e*MOKZV$yC+k1`~9Hvsn-UYdvYSgwX)TjKvZOgvO!P{>?X=u1E z9DE^n(ed(kM;ltBUW-3F6}E(>n_fA@%jA;{qV{x{S#6qZQSRGOMVC#p_7%S>X`cn< z4Xgc8q_m8}nd0xFlXyFGrT(YPH8N}HP;i>4Qc#aM1{>CLq_3~VoEC1jU5k_FU0VJn ze9rC5E47&c4x%8`lVzIp)S&d=ym6y9E25kIs2d=EXiI)TMnrlLmX8xB7TVV0 zC@Zq=>z@&OG}IKmi^ri$htk`7Yw)oGIZ9nqMHmmy5O}0eScQ?7Kdimx0(9;c5b6~EPPVNrg_w%co(sl=H6qym_m4n^mJ!`fB$_R z*(cRt2>@c74389a3pb>sCVZFW|3pkg#64*`erH%CNm+XHb=uUc55;4yPT~2oG*=>1 zUR*wFvnRB~w~mUw%F=0V7nRrbjp-RX!&^O7&n{nL0ik5v#K!0ovG?Hzcu2h*v(qOR-LK{_Dus-F_ZH0Q#ZV?o8D_rTc%x5 z7O)o;%o#9gxiFr29{q^uoX2+u&hXUP(r$qlQ#NHwY)Pr))+C196aN-ZlbSU- z(opF9=hy)}Vx}o~98%BV^+ZA!_vglxneBU7)$9?U)Z1L4BXJ)X#q9q4aLzrB=J(u- zYbyT*1uxl97C!4e$aOp!dmz^CSKxSrh@3yz8}hYpPXvCw30H{6AW4m{0N|zft!#{* ziB7kCQLHn!`gY9WrS{hpVU>SOD=$S-GwM6oZ&bHiO*-ZA_}!DMc#XG-smy6@fcjlR zw=)74nj7P9s4Y;Vh1J&|#mFI}CfD*vnKOU>l#|0B%M;$rFO{Q2qf$#+I>?;Y-M!Cg z4~AxIZHx)GIowF=qd)#(vsh=?v(=XE+wPOZ`Xl|jNQu4^lFmx7s)*qkPU}+IF>QC8 zjcqTy@%Y-Re4#vvR7o1@Y53!cuDQHl2f1rrJ0z0SHj3Miyx2*)ihz{_fA>Q>x5@u8 zfZnZ7`c}v>q1nTItXt$;nuB=~d^DB?PRQ+2JW<;pfA_K(Y8^U`5S#U*>JFQ?HkPN< z&g74@3oBkP5BR!IXKh0<2**ozm4I4b;sF^gp4jh;dBX;Y2_^`DQyUe2?0GO z|HT)Ar#d!FeH`esN}Qs4{qtf3LTu~zC;CJSxK?Q3@bFS}oIVKU!$vk}+u!hc=ETWxTQormk_{rSkQ^bqJxzu?HCYoJWB274g> zf-)D<)XlyRIw3iSAHk3b)0hzFXiL}plfe%D)+xM!(0hqN;K<14kx=*#0?% zk&k1^7W%f?MmgzeSoAJvl~YQdkn@=sDiY62lUHkGTJm0hoBFwhw{X+d^H0_9fZz3J zG}4}St+$e41fEvU?pD~Gr$Hs)u4|A2RS^E5z^zuh%rx|I*s{yv=Z8@2I2w=B~F)YjlM# zI3o|GZhiZ+B8pb$*YGetk=MS`<8e@=;YMv^UD^8g`lt#*+H^hg&dy(Z9&t0IAS~wD z-&*hu86|{?4{nO_nu_@Nc)PRGa25?)60E-^O_rus7TgQH?-sj)$kG?=xBlx4$zl2Q_3J@O2U2gQN%H4)`8X zA&Ddog3*D$R4s1=+z%X8N}HRo9w64Kq^ZeIui;bQ#$`8u#>N~DLodCk<@eIsZSHMEOckOYw{G2f&Y<}W=x>3KPDu8URa5)h0l}pT0v_Gmg$G}@LX1lC zt+Mg~mcBg>Od=u)Rws*C@M=6J-9He5l8we_dTx$jIB-fzc)cz`)FQ4Ub5Jg+WfoFb zImn@%w~!HR79f5ID2Z?qhlCHLy2Gc;|C;qFwR!} zuJouPD0>GQBe=h(F0?=591`Rj4v`6h;$}^36KHfLE1}C{|&atVjOhB=a`=% z{uj+9FvjQ*+n347=OAnYKl39*DDc@cQar{dIXNrp>t6$Y8RZdD4EFPdQkFmu3kwUu zx4?BT29FwopNL!;}_IrO?vRX)&mXh)a91 z(~nG8>++|i{#k3+WqI( z`I1NCtr|Agq60~k%v$W-zF)CpZCP2k-8Ff&F|tXVEF!NTiS zyDdt>@!oUZU09CIFP~@6;SR|&JiZ!wbpCX##*4z*%E}!D>YUq5U;G>;)ZI5l{?bo` z(+n!*-HeQ##bm%z{Qyf0W|o<3rL251-58yW*5c) z$)Hx-Zs^M(Fl0SYuWz+ICwGK}a{pEX~pfG^ntXn!pY3lm*cP?o@8 zNm#`Y;)b`?p0Ei~FClTkyz<1x=JmUG@r+A_*yL5 zZDkcZ2owtqUOg}>m~6j84zUbV-q$Yc9;5X&IGPi-#KRY4HQ8MavK>dWT}S%^$Kz-| zo@Y1=KwLoAHvr0_0^A=^RMXz#Eg&&G)6%%G)P~YctnNw?@_Z7A*Ri~0Q4Il+;|@JQ zy@Z=56$l9iX=K?AAjqSvvhoGcLiE<%tij-i!O~wv{vDL)x09GWqlFACDc?WSD&7}I z<8-4fWav(Nz9+~10~{L-zg0fdHSS9aM^E_U6M1LEMDcOk^D*4A=R|{CfM}R4O+5ex z1FiKN(wyhNhlYGHAi;4Mb?$2Dv47XrX=LQUI0}UU;G5U@DI#L+-o3W)-4cH>FHR75 zxDpVJcUv`7YjXiCK^?*YUoXov`!E4OPe%$42F9bSsCeMVS^4=H*x1!^^k+^QSDt5(i;3g}Z=M*+q$PO@kVTFN3(3B;=Iz#aJ`Ms$yq< z3F#2HOO#3C+sL3Hr)Km3P8n)Hvjf}$%)TVFdvSV|UISsL(QsTojwXQVyAT)GURTi) zn5kR)dR+Iix3009UQuZiE@+R+gy8!N-^H_nj?CabT6f@Q06h2(|6>Sloe zNDuyMw%`%qqj*vyFNJzQ*iYfCf&W`dQ}YP4MByNvAtbp2bueIP`0t>RL|Td4^~eYC zelY!%kdhjNN}V8Fw~&#~eV=YksM@1;gsyi_j&tr&jXRdTJ@OBWJk5(Ld6%U``}eW; z=nuV4S=gR&{1jG_NCH)v&|s~u*pPF(`c82un^xvVJ}ad}h`C->?Icbg#Hbf__-ZKI zzsm=wr#!>k!!yM0YWm{h)nNN;NyIi;qXtK;R=LHPLQZmWoo&l46_;E{@ksD+G?TA_ z?k&XWc^sT^xCSZY)Kc0yIu#HueZ!VfUQX`!C+m|Dh;!f%c@y9F?R1@=uT;~`@Y+3x zT{ct25fVT5xsHhm;T->ezz*YNx?3=zz+2Ef|5KM6TOx#tVz}lY_i+i7{7rH87#3(F zs}Knk;v{3^Dz!IZTz8*Oij5VCtXHboHx^f@e~uoC&U~Z@jDLs2CVjMUqVbV+Mge4M zux~XR;lC=DmKhmA?d3vd78YX{HjS|5@qg?%aLnA&@>-PadSc$6Joae9jbxAvi2|@@&sz zp|G4j-uXv?v3&1DeZ%Q>HuaXg*GTL(cZ8+CCfyU^-U($Z!JZTLj;xZYQdhKWHY+31 z_fj-n_qk>3{?C9%%;(@+fk75_-3-Zok^z-&gY;#P@v5gNF;o1qj!R7Zl$@L_mUSPh z&08umVF~qXU}o`f6Si(_Cr7WpI(+e>A1rKyQw)7F5n|bXRyZ;1!0*dVqTbq z0`{L)NCrzAmeG+k(H%QFJnSJF-V0NrNVrU0XXh)(*-J{o#a4`-diqWtV@EYjP{6(Y zit|u&-dZ%N}^A;@mv_2JbSLaw162j!!@URqQ5C;*^q-f)I`@pIB?mWzxPZbJ@Fh8>R@k+D_>x4!52MRK;~I3AHa2=~;WYo!fUcZuv)H@_ga*c{_bhGgq8{%pNoL z@t^0}Bq2^4Hn7iZhuaLwFkjLf4+n&Z5Q5wEbna7>ruBc7o>wOW5JH81i5bo*B9%(^ zFkK3iN4T=ZNE?efM~wN*|G=+g92CeyWF7PJDor|DSzGH2{`f$&u3m>O{etNW<@XM| zAE6`jJFSSLHxCepj6(K|>K9$mK&I?MixCYweFJ=>M)H@DRt!3q!@TpI=CV`+piEIx- zL%U-}^`r1oFWE%?tQ4YXki6@cML*Xc5mc1)F{r6?srTiqgZ%y?*L+pK(&H_IU^F{ zDgQqy6z^1w^;%2{X@C7}YAA9MRi#|LD?Mle%%5nTASl!@2w zA|6RxPR{ni!N5b_Du?I;^qmYWaCNn!J-;Z>c^MS%<7QTjXukGL^pss8tpkzDgjSq5 zJ{VEI{zdEKCKpcBUi+fUJ%dt6n1eG7+l~2X#endT<6x$c*JbsTxj=n0ul)M%f(p$PBA3W= zc?01Nrk0ikCz}bC5FQ|_m5|_ICK%<1{p_)2M7E4V%9ay0qMm$3FQhHR8ELPBwYd9h)2+w3RI1 z%YEtH1N}1<4+TYTX|1-L=-=^HpUEnBLsvDzbSm^!V8zi^+tTptE6e*tgYu9TjHN+@ zXv42XzWmz&_QwADf%YEm%wL4h0}UHec$6u=?MItd`T>QTh#|q$ zOB|Ja{CJdFn0Qi4WW&hEFb>h3uFv3$oqeN3=j600oWsE%Jn@ry$|6_m)LmUc_lRl6 zcH>-RDafg@R$Fd+|L5hoCc1h}UN@1VU2QP9jydD3PRoK!#RsX!qu+;EErf?R0N$2x61lM*x3^vv~|5G#0=@e*{M~CXpJ-Zw5b)GyWK*=U~%7l}!Cruy$R{eXn|baE;nA4C=u_Ta{*Cak0*8X6iHQKo=o31_&1 z`lY1{Dk>_vsEcbOjz$R|6DAPi2NM)Lp;1TUgmkf6Pca4#`(hX1gVO;1db%bPL$$8W zH0zg#uLOT_i>QcC;w(JIT(8pM0pHF0EKHdsw))=w}n zP>a({=zT`Ib8Fl2&o3TSl0Ut&K%1(Qij>vm_1z!dJToLubx^PM)j4s=dID$F+6@H- z)d~&0AERo9usW@+(`eRndp!$E>nq$zjRuFfRWrBPAp7D<@kB<}(z{2WZe=aK0?34w zLyB|<7WeaPRWweD8D8OenZW@863C;(UPuBrJ8@h)lC%)laDs~~O?)N^)u1}?5<12g z5>aqMy~K*Cnz&t{S+FW7 zpA+e3OG|SFn^c&wiNXv%V(DU+3GNH}@a(~gj%YGL;xiG$)!+Yd%!Z2>$tGxz0TKcf zB$C=-5+aFjl2B9Yx+tx9@7_l>rT=IF?j6Ls?}aQA<(4=r8e2`gVv;s;ll=3U;+t$M zN8{w#iEw+Xj`NgAazv|Sv12NT-|}U1vjPUwB;7zb@Bh5ZVTB!-2!=bzXLbyEH+#{s zV_u!XAPZF{O_;*1?R~Oyjf{8Atp3k?eNLv2GM@>x)O}o{Ou^`NWNWS=bQMv_Y zBO-Jd=)-~q5%mgdnonjX5Ap+uKqX*|N(l;Z7ZEfK5KT-PuuHcU*j<9HeloQSFP&<) zXbenCU0t0B^7C)hiUNX-%N+FUmnNb_bPWs$(-GoofHSlLE5cNWMia?(FBIaBL#BmL zSUEX47tmZJXrh2*0u6_nmFS8vr=qCBSic8OiYq!kZ}IZ*v`8RGnoIjfaaUI`Rt*sg ziYkFrAmRvnymfRqILM)$Z$#KUp9K2}V)YI>n-ng)VX|?Yi)3kQ!5TgTUgdqLH?2Hf; zCSVmn+JVH1MaiDmZ;WBial#?(w#SN(ay9S#uN6~D;*XFw;v{HvoV7b9NC1e1H;f?C zs!&@mRXG7sZS5`sI`A?=Zu>Ga@+iP3Ezsk(;#ZIci&-Qf)(*VD6x_SN#>Rd?ph5E3 z!U73L1b(n;1-uAZwcAMuoCL;{3Kpjz0Ea~CM_VUf&j>Lp0+U9&at@FOGWIw|;5yU9 zBXmY7*_kkG{%Je~T&CqwFcwA{mc&HvC+Xh_ zp9Q(iMT3iky$!vp&;@ZnSDfm*D zb$OZh=?fS3Ac6oRp0Kbm=72DnlYoU&LyK;yO==EZK)e?A5d1a>ff4!zS;lRES9o36 z`WL?0w-dp_!*$_8X42njjs8>6{$4u{eOS`+0pKo#rzG;=#ly^%(l@DQU?f2B5dp6u zmk^<$eFFnc$7RTR|NOD7vD&|L8~ho^1OyJz(a~`;-1a|Qu~=QA#S=I(JbWd-sog(# zIjHjCpFKCsOic+$0%w8X(MOp_*r5!}aLB^IcrFqpOMq(P;uLsRKdqt0ep!TPhInX!JsS)`s{ef&7tVfh2=RHC1^H#LNU*{FMVzeC=V z{1q|%XB~NXnps=pD1hh0X(||z;|nhXIfWddz`y(;`d}g}k`TIM4#d46o(^`umre1C z)@|j>&yJwC3lg+>gCBtPm=AmhdP%z5gzJ1y`W9V%eNuihAz+efKc85g8{kk zryPCIc&NFR)gb19G^b2t`603cgX-gY?wsuGy4F_R%>o=G(B9t8@sx;Mz=0HcEPE28 zqRN;X2_68@I#M$^I@I790o=QO%_m+!tun{L(lRPDvw6b~=<>w^HUcq5)GDl;|G#B$ z6SD%+P>Qry(UCFW&k@{ROp@3Si3)*r1=A>jEg>rd_YF4@6(U(Vfv!^*Z3oo*f9TpMZvh-EDF8DbX0LG#79gop^) zicb&?xE7Egfm1+Qfr{;Kq1rVdQS%6V7v3Gvb_lgvkra2afCWvg6m~41E}x&UUHo_D zK92R-hrJMU53mNarbRjg4;f{3m4j(nM$9)NABfyb?`z%=*C;@%d?2V zLy;1>fB!I{=ZdTktJmeQ{rCF8AqhGqACC?A7-N(Sjta+%I2Z__i;g98YDO>d;?&E^ zdxZLMImmmF0>nUDp)zkYG`(_6wWD9HXy_P8L*lNYPph|kTKPT=eLLkcph*`In%lUV zpI78guDr~;5(20$wPJw?V0AVQR7y|IHJ@obHyLBxrhe<1&Pw{qu4vApkJKbu$ramL z;@6GeDAz7M$(h2_YhlNC@~X9(qT+1(SnOyaI+7N3J1;;eczeRViA1^(>KVE=GLwS& z12k~79H)4Ab@TDe@0-L41rtS^8|H)Vx$hP;=X(E|JO8t>m{tY_1-%!vxqy%f1Y!!2 z{b@aV^eFVM0x-1$G&-kK!?+Y_>Cy9-Z*TVN=n*ON!2@}Ck z|Mgy$M1UU=nbg32iF1z7=}3I?5Kh1$ObClO1P}_Z@8jYkmh`{KdJ}LgyS8muqudqB zU8Io85M{2+Bn>1=Lgq4+Lgsl&MWqxW86zPfA@h_<2$_;OWXe3x{QJ`Le&6>#|F*r` z^WIy@bzbMW&b5wXKlb5l^ncwfYs7l|i#@{uCqDe89~yY~`D54k2(kKEoM~vb^Nxm@ zh+O(#7n)s;ca;p(F_D4ihrgd+4Y!ljrm+HCG8y&5O%J>neIZ6C8^;*R|Gndz0non; z_gmD}B;^DcZRx+&3EjVckHUNh;w=2#jv%)&pR05(y=_?Wf2I$NznUGEGpy5_>D`oCG|;kY4V!w+<_y6qqdS0}9$%Rq?I2KX?qto`7EB4?1*R-;O3MoS+aSo#SX>1B!tuHA z+v1G-|K8b-fGbf2SO&pKzpRJ(^C6Do)$Q*WrGqFE|BYR%9!O%sls}Eesb*p z_bXt63f!Ing6R(OE3o0=3j7e4RJx~n2rUxvIYVg-CIm|Jh0hjp|N9zbeZ9dDg{d`e z8h-j`whcG7Ti_@Egeh|DI*{}n%NCb~bAlEomT=LZZ`mV8|KH19qU@T`RUt;8C812ZE^5g_9WvH6GM12}dD>tOdxk z1y3?%y(hz!|5?;Blb2CO;j4jTKtYT_p+bczGHEfeh^aPj-hb$j4|>R5m5D)^wxEe8 zo`6@byj%+13JZL+sxUG=6g(+`7VQ7og=nMN;ikZjfjf>v{dA2X4^Iqo$!QHwx^q~- z_)t_aK>1mNZMOn3g8!VE)G_=An&$0@ngDn|)O$)R^uM;K$+KJm{~%qUNbemlH`2ZU zW)NRYgfJlz51Jel`xJ%08rtGtYCt26R_HybZx}6&O-+4+!mmeVs2{?DYH~xhiQXNbuO|=;`m+2MqIiDYVZaN-<|E-xb(f!dj*JPGbW0t<=SEO=hr0Pr6gSV{v zoNdl0+)_z6pRgk=x&5$}rOM0tGkX-sVqND6ZBk|?Mk_V=&Zs4ZhKBrDCBC9u!-k0( ztg3l--~3|$IH=W89HYzwY5)_mkP4%frNM$Q2e)Y&>&n#80x6U9`Oq2Ii=}I{cAKMe z8h@7Zwm?5buq9yzr0;nKp(l$7e_d@P-w9wR5|n8ZX3chO%>x0(pG}4$^Gg-NN)_@-6_I;tZ8bmsWqvnR|x7melqzT(-N57RTz$cGTZ@t_46_(!Q$3M#cqDmm* zU_c0{(528lkww?h;eka*w!B!%BOsXlbqWW}jD70VBgT_tzgMIYomhVh+Z$Pu$Bwy; zD1o4Wr!(zdzOvCEpI6!{f2wkD!Pz5n^9JwAMOXI7-|+TQP59i{IOpV+rg0dE!Zb(9 z-DewQ@C+(JK!7n^XMewg+`x*t(hEFMr(kQ_$R6jBHK=T|*SjvyECmZp59*wdXtX+G zJu&seUo4|hlrzC3Dy>ZR@}-NtRoCgxCGKpoew-;H*7+x@sG@P3apHatS7wG2N3MnK z`EJ5=A->MqT5HMrLx$$H>!#6J>5q0=?LK$d^qFe<6EzjD`1nWndX6%_Xu4&gOxKsN z|9i<@X%_n1&Z6zy0X2MN>+}v!&<#*KQvI{$UXJ1_4to*b8iwx&uz!LB!G{C5rL~n! z-;v~%;uRwX$ETv7g1|D_%s=Yn2SyN57l^yozyM~1u}Mjl%Q=lVPsOXi1|xgDEVgm(;)ve2ei*Qlf$F^7E^{T%Fe&`_c^{Dr3kgQO)pIN4m6^?xsY=JMW8 zGs+3|(=V&;WDXAWY7E7FNSP{lw59&sv+&`Y)|)0RSPM11GQ0$-_&t1BhI~|`i>~HC zop=(eD^E{GO3EWSUrXwfTB_ocK(V_GVfNu&Qx-CKtxsfv}Vp$H*@+$ zaqUf$6MAPozx%q_pYqi77V3972u7!Kg-fvIUVs(pB(uMT0=ovlt>6Tbgs`tQ&<_66CkhfR0xTPqIJf^Fto3blJ> za?;&|gtVydDtmY(Y{r*lsAQZ^%})t_@CIzKgez0WHVEIS`*hlV8-2$)>$q60U{VMC z6~+;%R0sHo{u}cohreZMrkm`5{cFaS>WMJmYJ~2LGyrfFVe}_1F8o zK?Ryv1bS~V56Ax!NH1l`*zFH3E@o#H{ZdV?(NY{NooK7 zpEq;U*Vr04OhzZ_u5KCY>`CFz?9Y~zm@jxlvo0(rL2x*!QucJ;nz%PdE@)gX{}aX$ zmsG_n`SIZ$PN|K%bJf?~Ofgnw+JULGtDP+t@1G*rQZ?L0UCqM(R1Bqaf zXhwjPQ(!B`>2C=5O@PXQrq(1KQw`L6)rJnRV*LF1Gl;=sQw_T7aLu=i^bpYftGk;m zn8VNm=foz~q(g-l)vF6LPAg3eJ(bUGP5-ppS&ni0y{6-yLpc`BlpkxOTT4qWdilma zzEaKlTtnmF!DRj7{C%oslJYWXEL0cr@AS7Gh$ffr3Ue~dGu3o2RPc+3x!kguUuJ!c zE%<9yRWCS2Pqz$kK!8-zzC3*lf4WhYuh=Nn0^u@`S)>$UwPI>&3ap=C@Zt{dC)fAy zCtnO+cj%rdMV)kj`&>X+0H9(EYiqb{@?HDB7aSHa^8Bv1o+(?4M?o8vocWfbs-x?Y zv(>w2W!b9tPR|LtmFcBv7&}FKCPtexIahY9TkQ5N_&uEy$bbFMHywYTupjpsJj3yS zFYXyB?u_UOOSY_b66H5ir#-Q8?rQ)yzS$(*s*6UZZBwEVb>QH~v%N~*C6N;w9Z7lv zT%-+_AG(sa#poLY{-oV}_Y|rRj3fy93|n+Sy}+hOCQ;wi{EZiZh=aH_`s+9V(J9ZK zfjPn~=i%v5E10i8a&846aU56{NL?kFyXDmcwA2rxs5Wx%gT2#qcu=gK5 z3eZzJ_V>WQ)5pzourQT3_IAat&%(lSaz50*dibO?n#JY~qKg~<44C{(*BA7UooX8n z)-kKJ|LpaYmgP%Il>Cp8!$zh}RP2woT(J(-Nz%hE80EXF5c!l&-znnl*R=LeNJ9J# zc*TA04V6{`g^Z3};mNl@#wfGF{ciRtvy|~;!b8EEO#ol4z{bYx(;0(vvpJ`XN z&a{ez(Cg?{eiPaJRdn)jYOGJsQ{5$x7@C!PoOv&vg&1`u(?orE{b0^+(WluwtT4J@ zdB0Q52Y&u;BiHwR%**qG=9ecL-L46SWZASaEzbATLuM%3U+)tpyfrLgck{7i4xyI9 z_O@ACwPQ3p+mCK=k9Awxn`FlPEj0C4?sfB91jU~VNxyrqhmksBM_+tWU+7O9>Dr3UQe7}x#Ky*< z6n;QlJXeY3tfuB}P?5lOUQ6PtUMq%S!z@2?t{C)O5*tpapk&^MM-EEcx@@xw`I zLBL&2$Kft9V#h)QDeW|x4VcxnSl6Bd6=Mx~*9brh6cE-oWM1mQ&j5?RQciK5h;=l+Nokk={%757mA?VV{hZ<+US=OUW%0zmngnH#ziqaCw|7tLtdgpy!a;G9pk z*%mjq{$0%Z#%n^R_hfbY?|eIRKz*bXJA`DLrO#JdJG0&9pDrA3eTSCYyKQx||C8`W zVTVdESGJ)h(~ru+M^W|-8yZs8-%`}k>)K!26Y^#&g`q`#Ozg|z2aQ)Z7T)YvP%^!^ zvOE{*`fQbS3 zapG1ArXR7;!PJ=8$D{KFOk)7wN~F4yxs5Ug8!$5h^s*jQhMS1P21hdm%FKniCVU5s zK^i7oh*=4!aLUSld0q`zxLFu|5=9S&0^^3aw!tnM3yqU0d;b4$0ah2C2%FRNeG|!6 zTc5b|yu&Y!`1O3CZaO4&lOwBq`|GgNx=&9!_B(V;b))h8 zaC6bG^W)lQ@-a*O=aqQP(<1U)6*9rJJaMmRs_MrWHk9p2F_nk==Hxj89FSDDhCfA-_no9T^>VGWwr zi)^tSv;8+UniN!yU1|zC=&q-t{#h;xRI7_v(f7uI~`yyVw(>j z5KST`l<><$Gm3u(SpwP#*tRMd2WJ>=CjOf{cdiYi%NVd0MVW-VR8$lsGdbUI z?p3%b687czMmo-8C*g;HWS2nRJDacFy!mXk^S{$4n7!WKmWjuBs&cK_uHAPdeCaDp zTLmecPhO^?@Qf0Th@#rc@@d7X$B^Qvsk&8l6%C6+tBC)4cAxwrpaf~&KYr}|;)WP7H5{e%UY&VE30XqbGXdkCh59<{XGgk z>sd~UGWmyDHp~0WvW9GbB+or-ZNGVZ=vQHwlvCW6*&Nq7={mVe??_ke&S!B`bH~2U^5O1}ai9)z{`*a`{l# zVvdKr2^JXN-qC3n>!Hd4I7O&%n2N)tGa3S6j68s%^}f}FEgh6D8gt`g?whle_Un$8BOXL8-TzXwx);%)(k`zWIli`1Y(huWWsrrrpW2^rCTN z#QU2!`<&&IU;mjDiBLOO#q{EM%>0OeIg6Cc$E}A}CI?2iuB59sHRrswV(m?k4p%}z z=)yv1aqu-EMSI7&NSaOTy`yUs1A;nPXg_s$_EYq&^NdSK>@l8^D!N#eUv{kd==l7@ zm6B#RHxCxx`CTtNJhKn`ZY^rd%oa{zJskAw^rBw)oJJa+rWG}=6p?4 zo5H);BIcjlqK-9To<;Np$k!wOv}!RGsPW-I4fseJ@wcFyuwlpnteB@8((4ZBD9K0? zhGkD7aKeUZ)3{K3O$cZWF)E}05QhvUJT26^AjGre*bbqaT#8!5oKXM3%Zn1`w?tKg z8G8y0mB|i{<0I$U72}>G8X#1n@W8W0k!fLRc@^p&{36$>1l^bCIj@@2swBH6ydc#VA zkt$qShHXqY8)w-HTz{Lfp9}k}nOxwG`T>h#tpD`Lc#V~k#e#M@gQ)WXYU;;m$2)u4 zmb$X$9kcmvEb6J6irz_%72Lni<@Z1Ic+niaS5>l(ER+Eoqg@&DlRUQn+?J;SRv9wl zNor%BWzWP%PZWxTJ21V+ASh1d&Dj@0eMl-QYHSR~AftNu*T=?w)JS`zTtm^yfHMYZ z0Xw|7z>h+;NvJjq;`V&#p@{Akl<^cyash$TNKBrG^cI|9k0QNaQ1QiLK#MtFRzGP# zCFLEmKLoGb{MPk)cXX0G@Smn454YSEkuQD1IH_5<{H{KxNP~VEl$k#yA(tw zeRx3%s=#Kmg25rF+1ZQVG-ofiIWBF`SuU^r7Mk;2GH~JUmR*v57XGhOrv{S0DzsZw zPhB*7aZaw9N;T0rBK}xKM}tzq_eKiK+CAa(6A91$r5|r$alN06kj(jOOs@0N!y5CP z6J`Y=TW?5pXZW_BJ!>WCwp2oCZ?6-U($cCG`kb%ntDEwKuy*qywM_DQt^50WiQRQP z**U^^sEDaL0WnBwgwrQBoEfbKM+h87Pzr4lvmN|}cj!w=iI=8X)&_UfF~Do&RvBea zaTt{v>_ZR(25J;Q?Rajup>NXze+N@SazjB97+erbtpe;1>Mc)GtqPi02#o;75wHPN zNWx7(oCpO@sQZ{^A^ZraxGREOYk&Os0P)xAwms|nP@O_b3m;!245XO-aGrT z&a=b)O|@tLnj@^_B`JlOIcO{m=7CSDzirIJ|h! zZGJ#%LH30m)1gln47)h!_B)v}!m<211w{MtYb=;9ximZEN>VjU+c%7eP!*;Pd`#|l ztvzOBv+OBk_|EzMrfMbaKQ3*p?I$F(U7hon7N}!S{xcc(a=XECae<_6n`3maHkLKkYtL2lqoClTObd| z6J~>Bem%T@XlCX<51%}^`PHFJ#)ePzxkq6*GVmx;TdodcTMeAAZVD+le5L+_{!KYvqmN&o@OXq{ zr~c0Zy1rx{86)8N+HY%`%Bz?491+L9@BdVf4BlgqwG{zs0QV5`>ABD^-NY6g%~a{z zas(z+f>n+Q2yk%6UTnc*{Mb zTWL23wUm5hn+cmS51h6=rMt5KwoLKDx3Rv^BkLEk{B>&zN6(mN)sTN>*7>rQkDvAV zx9C`rOAX)X#U9&HP5!GYw2!p3_uJ(9e?9oY`}9Nh&9^;_FXWHPN1oOaga`*FHH4Rj z6g@1`!J161RiAriKIn^)Dt{Oh0V2S{q=EuNJ0p+){X~K|p&>#80Pcj$ty`n+1%Izv zcBp^&&w7IGf>>AefV?l+q<_k*uJbSI$SFGdEf2p82?Gx0r9k%U?~* z=I2guZ(Cz#xqmZ)f?Va8oR6tA)6~DETDL4Vsp)%OIknTFWfw26y zLh8*L1x~eFeqQ5hl)hMc>TTljxKQWrjXTsTg2UHQ{HA8WdT~8RglvUqc@t z&u;Ar<8e@CA(sOaq}z*H&<19&XEl=3)2DK0u7X^YpRc@g(ik1g^h@9Di5J;FkK*+| zFmac*b*114Q_bS{h$GK6s!a^GU&aY2!BN+q-p(B2>lOGWd#B0n3Qmd`Wsj`Z2Vaht zwJpDmkJ-v`I(9fd;Yj+{xZI1^J#P&jzFyt;?!~#4t<#Z_#ZBz=_EH#Xl^}$vwyPgw z0OXGR-2EKXKLCE96_&|umv{}Gd5NbF*4g~=HQ@j@%QfIt41s%P7X95mGjvcvE-wEd zCh5FdeTG*0Be&V%_PJtnW|?^9HNSqpGBl`pwAjAc{1?mjC0&yh=P41%xl!G^h97*K zT=!Vo$E?hP?ID|2}5w2gk&69IQS8|1p3R^P3E2Zvy%@s1!-&|TaVM=bIEpBpQ3GT zdn7MBTKhdN0PyK^R~O+UTN9o0R{l(d2h3lpYDhL?*3Z>j`lIrC*)PK`E6-(K^t9dn z%-y`%;hr(6y^mGhI>OH-);G2%(z}&jzlPnWTEgeUeC5dYyE6B`xX?BgTEy*s-+eYG zVq$dk*Rg`RbG}1TsG~@v;AXL8DFjJCVo!Ls;7B8l&ayDf9|bS-!_PH_!9W4-bAJ29`o8V$;T@HSCoeo74iPi=^lH_Xw{AYZ056W|-Rc@kyD2!OC180#*sE1v>0qQTx zItNZ}?k*6~|BSIVq1Kx6lr$G&9J1oq9@N>gd9&C^-t(}-hDFkxo0ASanLXhYM8*24 zK9Ywsp}6kmsou9)Tw)Bzu8XcLMy6iLA!W|OLnr&`8Q+N-sg>Hqg}L8SE1e0vs^evv z-1nKpedtPj-&v3Cu}*^Z`q77-A8%W6Jz5HmZ&a`_l<08WC8Y|mzfaMIT~IUs@bQET zFIA+q?i}09ezL2lX09$hA$8qfMi-1Rpoy0TahSzravQov zv~#5WCr$)lR##%+L2MW>4}z4E#(S}W;=(!qPxtdH$A9n83gMtU zQB2A2w0spk)Y@A@ydf;@;`g3bOST+c+Gt5_S9$Jgy2hNFQp;)O(C}Bn61*$jGt;Jn z&3T@|baZE!8NU@vtx!$b9HH3r_2=2~pQWF+?s^Q`D($Y~69tPBJG$8hfBKb;XXtiG zjpP+Mndkd7wv?fM4%&Th{ZoeSigk8X(dp@_9JQWyRlV`LJo?|f`TRO3b60+Fi_duJ z3LIs1ub=o!rue>_G69hPydbOa8Td0V&7lTx>#QRV6I>3wg11d#$%=zg`M{@ z73R0&Dvv#4QS4c6RXdza)2+rQaFmwiSbrxkN;B) f~=O_=!BJB+$X<#;$5Z%v`J zqtFW7^LJn~QfFyGFCVbZBuFp!o}|0xZ{lEe!>A!i8}%$9?*L#Va?7gg=fgqjN3j_A zP1F|@D;9cuH+OVxmBh>*gu;Egn(_`ofAAZhL)sB17ZS9<~F$4ooF zW}GhLQA`IV%ICHRQBI!cuXev3(Y8GcN6X*0)TrVjk{Vpra!x7t(Hmr8r1#xd!x zXy^Q{x5GWd5dGM555FVO4%!t5FArgSoFV9na2kitgd-(Y!NnJQ4k$I-LxU=*WW6m?D3uMRO zewH6zc_?&y@sFiBA)$2J1?msxI#o~jm`;4OR>+dv8B$+nzA|F|yN3v@JsmRIA7T3p zbg=vN%BE+uXp4BBb6j%5ektA%_sH}470Im5=l=~k`u57#(WeL4*`T7%oG_+&Z(1w* zLgA4@-gRnow^_E&cQ>?%@ZQCnH`bY25S>+Ot@z@#LP3CAa?|bDAez@-HVSDRezbLJ zx}Yk&0E&_ODRi+>=Q%}d<5aD>GE1NBq;G1_od2F|VKuY&z_-GvoDt*VrYcUJLwi@w zP(K`Y#c^EvDqhgS(w5z2L{Yh5(T6f(Hg8E#>hj`*S=GqB*Q!THDvW>pytZ$x)_;0H z_thQ{OivRK)=<1pKm>%;I;p*n=U}AL4M}PG${q;(%iDo?fKtcG$+-!jJ{WWajimq? znz$K2ZvyTNNTol1jPN?u0-Z&WtLMh8G8p@-a1A|Lj8%&0(OsD*68a@q`w!p_5Irph z!Ngd>J-Y-hFHl(BcWxw4hQ5xXc)yFVHVQ#aYQe)I)Vj&T3ney#pRP~ycUIXR=;iY` z&Z-@_;qD#f%NM>p+m#_;-l4rXUX*h!F2S&;?zz)MZ{ZZNY&UAP?3hCJsa?p%5%^cia9` zlLK9OKlg}(9tAq{#{2Uj234~lpC zCDa&+mf+ExIdi73VJ<8oiN9rt#FEI>E{U~_>Z z&a>*k>k>FVsB5-|v9R+x|0^cpqG_KlHJg$YixU99f2HmiA$xmJL~>-xOAieB)Mq}I zh>sP9si;2d7#i@Ek9nOQ6Kvrho9a-^NNq3}lb82MZDszn&iup(#dH1}%x=!(tdE&0 zii}b(*v$XC;;^#yi%-OOyL_vi(s*6HYS%z)N%e)|`(3BWFm!0hG{|MkigS0BP%z^` z?!#B-nv?k*nhxLD9R(Se!RPT~*pqKIr#(Jt#Q|jOOfY{)gU;+aY)f2aXU{BIUds60 zjmvlTcet%ta#GO2V6RDx)=$#Ko3BE)WKsXKb!#^iSI6PC1Ti@3$yT=S{O94gNffHU zKLHuRr+{|XE-GnE;Xua=kUxp(8+gC{0&Y(c*8&@`>1kUOl_#B?!~jH*fepxg@O=a* zM{=z|QmZ!^vYTK5zZ6f*1hzVlb&`AWp}XD{F%fqdP`%Nzre$PYgzFGal~0fW>^qTx zgxWrMI?fz;M-n)$ve+C6_~ZB$S3wpxw(|BI9)yHw!B1l=j4{o zsTs*)+&^FXrO?Sdv0zancvsOKJXT@UGq@qH&Ln)US#xo|BS%F0a^gk;>_k0*i zYrNblq;S&G#a8CN)n{-iRyR7wD0kM1PD*Feie0H-0|bHzBhKGOm^I6ES0)cEukpy8 zuH+ET>6>j_^1Y~|@$J<>)Y$Y`cajr}(aNxSk}%DLqRM-zgy-KWjxjHlp2^ixu{=pw zO?glLv*Sz2T3QNV(t7g*FIehKrvdk;E0BE^9>8}SK4fus)+;ai=&7kD>_;tX+uXxR3M*=|9%g+RO-!-!PlDt31E z*Gj#b;CbMQf^BStfU_}33ZqmLoLsUa9D0IpWETh)&xb+xgxC0r5F_far@Ta&;Bp&h zadg+h@^h=Gd&#!+SBLuaRGc|qt_k(-vKx&Nmt-mVB>81ePn=--`6!5{+c=nAl- zsXCXohH}`9Pp!kbYQq5o?`F8B&U1YO>p3#05NBvwm}BHKgAb4-_1#CAz@qH zjh%CUM=c#8&wPj1d&zGSd`ti5o}0%wE9uzCf?3{xj)0S zi(XIC4OVbn{km6zf1_Jz2lErVD8J&8vg_sYZaT3U1jCSc(Z)` zYqkd+(x8M8jKJg(`GTVyjyceE9@=%pohTk)$poApocF)vZ2>(;d+nsZf@OsMZIF&v zAy#yl$KOG=;ITLo0PRx5HdT=)sZ%vI=9n+x_`;kz@cprz=Y4#-K3DSXb7;Oj=<;`S z-p10N&`x_%yIsNc!VU)xt})wMK3CaIRMnE#>S{(Y*p!(xT^CBys;s*}e`gw$FOtB^B5z@p{uU{m_$7-cz-I3a4A zE__VR2zqT*szBQAvogX`3tvoVu4P@Xd`9NXehL551GTPhvPSpsM5R4ju+p|N6zKgXQkB*F z%^_T5#vxok#d6W$aLGSP)!z-+ctoG%u+JFlJ)^oFOYUsz!?fgAE^K#bgXH5?wu5)? z>@2Pr>yP*2Da`y~BYWM{)Q00Wy3?_#fS1Q}qW;5fTP254pqy}=89s*>o{--T*to8T z7L4GP5C9(_B5!L4sd)B>)Kl!Dbs=IL(`Ehm=OC%$L)!I>-SX8T5Uc*Wv-!gA41@!0 zbv=GpM?vzpL{YF3Hv@;uREUlN0F3%)AVmK)|6za`z}jszKZIcP(8kNca85= z({#F>zfagdq3Q6DoDDJ9@=Nei!x4*d6$uV*Mq!6H%u0`5{M5-;DB!twhe1mG_rC3T z&`~9R(*bG8vJD@MDi|qA?69mH>~ayzlQ zFne|zw}f1{%CVx~S|^3sh}vr%bQxk1v{9#X-bz`~U0pomeLd&FtM_eX)ls6BXa9T^ zcibLQaX&)Nx1jVPg?~7OzXt`2#6N~J`HnT+))y|BzkE}va4GEWpKSIw1Bb5F$w$e! zoaq}Xd25kJHC6l4kGUR|$DJqSW_{Y>e^I@-^bdQd{vy>_jwMwMTmuR33`SL?McKk4 z8HyefTQP|gog42)?8|0|9tczbxC=5ZFwl^RL{kX&hi_m=D#3;Z-3;PZ`4Qr0JMg}F zh@>b0Wk3PW0M!Zl7~<#xCOnB$!0f!~POF(QhPqN&Z!v3RO4>~7Kv3C;PXpwVg2t7y zv9)7psSxfB?M9)2K*zwq!^WFNFpVJW5x8MOxAd-gXbS_MJ1i%l#)hcJa^@&`VK7SR zg#qZ3uvq~_pnh&>AX!c8OgYY!mzV!X2!cz4y9rbcpjIQMqJ22I)WC1=@_Ia4kf$!d zO=38?!e~Dyr#G${WJw0_>rl5^*3AF&rtDjxmWo2*yDJR)9JN1m&(F@%!oL*=7IL{6 zC@{5#EDf-5r9}f$_fVJJ_c(ET3T8Pl8bq)&3-@J8;93dLHvsBc?!6>kY9(Yv(jO3d2yo3B1GZ}ww!a#AuU~OYSPZvSJmW2p z78YY(2Se4g09Mf#pe*6$p2i^tw4wwk6mkpU*kBLNHPrtf^{(yqOUcZ9j%wBq+ukU8 zbAIR9QQLtgsNDc!ijRGwgLY*U&~7Kpiwj(rex@4xiWOObSc@T{gPdV&+VzWG1LHF@ z#u(p_zJ2mf{X@9U5jT812+BfO!;)-ZqNS6N$ZMU4tufT4k~nBG+8l`&C5gX_TI?A+YtVZX33V*z*MmfT2GJ&VVWWk>D|x{G%hIj8zH!5ifZZXyzHp|m5$Ot8SW zRx&p;lN?EzO+z#7b1GUa%Sr>o%~pw{_^QMmXQHRw|A9oE53?zAqirQ8|6Ahvd z@6f#$<)x(^2-`l9s5*hWEC7@cld~^)8RxKM9bkG^wW}Pbihy1r1+jd9|4=dF(u*MO zTPuy`2hY0;i9>!&8k?%Sw9`Gf7IP)WCZ-Lp4Z3mB#@3#+Fr@n&@F-NgURKp?*N%Fl z7n(y1*39<(LiYXX4AvTxqFZ%DX|{+S-k3*;{}2~ai=9n8Dt4|S@%iDz=OLQcOw2yl z+`QprcKv01Bw%}{oUlZf+xx#)+FtPH}7BHe;ugm zBWg-H#C>>Um=}&6-(USNqm<%~8P@OoR*|^pV6MRZ@DQ_XGL47YpKx4&go6_i2*@Gy z$OwE_zh4u={xE1O28W-7`ag=Jpwqon;ky6eflQ(*V3nrfCDOSC3sS=N0G>pM^6rIJ zk@#J}z3XafBLEG&(x_Z`7CF_sRqk&b9=QjogYCSxe|%UZPBBzHGe?WRdge*6Y2t7hK~N{<)=H15jBOGm3lDRWiF1;Dwa&VsGcyhrUTzKcellOiMP2aj|)H zL@50|ch2JbLkTBqf8-2U9v;z1Q6K7)sQ(>U7iO2=6Zk=g=@R|(WTp-38qL$kLt5`| z7Pid2xBu=Dyc-Nt%t3~`(W-)5_o?3+4`drqW-pnSw`fYNG%!9UTgBBBTF_KFDaD*I z7j}ElRun`CMOdOALSWJ71&$Gx1KL#>4OzAAR@J?Exhg#gGc!m->>-?POv6WnY!zut|Q-_C@NEOj!5%AQZ4+Op*UAKz$8NmSrY5Lhs_MwgXw)*GtbumGWy z#+&U8{3b}ZUl{2x30{d9nCsU$LG4w%grb1n*|lfIHis#;7Tk+|zFplAn}YMPCHr5AIevdyQbi+-f${2+|gpwkN z(#6aJ57cfX(~9YY5=*Zl#}!d|+oMO0WYNXOLIWG;;?yZ#(kVzM4u2SUhK8q8hg6(G z^AE!wWPD@{X!pQwrtv0r)13XWzU@Y-jS~O%U5D)`@mX11taK!fIXpoRNz2ii(rYa< zVBIMPzq%ueqoFxPaeKcu`0v$KD(nrNIC8WZ4^!QgdJi>yqAlgokcT^S)`jE^r3b1~ z9*y0c)9TS$t-3All1ZJ(4wIO*G>`syq~UQYQ6^eBs+x1GF7AAMlTNKe9N!@ zR!1L{?_+QaBo-L(raBGkFP@#HWd|cSgk0F~3E2qmBTmIq*a@|$*-){*a;e`j=inqy zD;hbY(iNZeUd%fv_62)F7?zfSuksqjpaH)iLLY?JcLnB87r2_YM-ytgiVE1p_Nq0% zL3uZ6(C=YcnJw|vh&UD9f&4g|h`~3Bi8c{^!|er9;4p!bknN?N^Xz^24Q)u7qjAuY z(nh*Dpa-n`+&H>hOl*m$F`+)4t+I&sq$9aB;ww-TK-G#Fjdh%w`JproUZwP!|()-r$u_w z$qgC1hw+8>U|xzwj>mBcJJEjE0lV&xyKPK-MEiRV-N_Wk-w@Zs8$aH5*cB`=kvuvs zF8Q^!R8ab)z`%|81`y{GROc-n0lG4quIt*^rfdtEX@dp62!+ochKBu}YMO4_DcV`K zm4tp|yzMfjQuiV3+ePjj>*wJg(^1~0eK$yp9Xw3T940#5>EGyP^8@CXXH&SNe9UvBId?+Z8@7>>!%mT{Ly1rZ9X)KyQ ztP;85Lx$qxJcuRNu5p6i7=v034!k2ApKrn7_mEERa~QTjI^CFKm)vqIpAxPtgSMps zl`<^<`j|WCuJ7D(DR>vd$6~&SLjYG)qiHsOmXh?KTM*>A-UuctDP>U&+RhY+H1OAz zmk-=7SBX~vEh`0DZbC)J%nW8VcJ0PnGyC*Ybdrr>nMPWRzkM3%d@yJm?%ujb_{rp? zHRkviIR6D5Jx^Pp-+2#p$>owkv<6x{^eD_p>^&^K-l}rrxr1!>=dB_73i#>Z+IeyG za`5u{lAr|?T*|gOtaoPD%uOL&st_J#nLuKRY6CWXVUEu?tU)$Cu@xhQycBFh32f+w zV-Q7x+$|K!q5kRh$6YV4W3*}h?slAA!gGE$I`3QFUE)`bJ-P&DHY52FmFPz9uPm>> zfp_5HwO_9Xy_lpQK#33EA0GSMVa}rJr=Z~7h0)w7 ze0}i5K`B+t(a(Vj`y|Ul^URKo;^N}!_!>s3yYh6ZfVz^Fk^(dgc;9@HXlcfmX_=`K ziNI)MdCb?1xJ;)xX~(Nr_J-Mw!@L3Y#YO<)V5c@X_|M>GbQ8}EQ1XD(^;Cv6o5hKs z2{HYbr@@fHOWHd^uR7`^MegXw%@S9g5~edu%?sZpAmX`0=zY1}ya?)60%?>B1`-?;| zI0Q$Qv?RQp9=+oJFke6-_T4@IOGeIH!kO4@v-KCrs1MUct2U=m>!Z+#!iLHnn$ZvG z#tliI%gY}ET_~G5;mz$FI=HQ%LQs&8erMFw%m`n~{*nj7L$S{JVJ;C*TvWZoU2^@H z#nHkgLP-{}ve@g_(%-4*W{Ut*8o)eHI+_TQ#mUp;o7oqB;k0m=B3fct%te{E=WD+i z1Q!G69r08MRpbDIG@MX&m$p-R!vSixy%urn$s8kNFBLPZtnUY?Gr-qoD-ARIMPD$x z0ZjZuTA5F1Bxj}9?gK<~8lT3Hpqh9U+~(okmUcT}vRdlTAqaZR++HB9z$JufnFFB886-cLm!0pa@U}mzuJLu^fV(uBz$#^HQ!4VFcKt7NX z2oGy7ep9wk%pK`X)fe;74KEJc6`X)KBwscagi9l?Gh#Cp(tkgXwo?H>2VhVFQ@uyZ z7ub3SILW_1^!Gv_I(h2nx6h-`2&OXX=_Uc>3*&xms(y*=i)%vLqx0&xfA#mvh)@`qmBRE?aZyJavt*f_n*&~ zC&EPBaO7flEbg}KxFt-;LNKmpgW(*i5A2=Y#pH9@&fG@m*ZzROKvZV?J^Ee)+dp{t zZ~&yJtJihc8Hv!C^k=WwWoZp9FOSXzYw@UgO+?&~3@X1{Y7mv3&6wJ_C5`PlG&e}C zcuE7KBiW$8j}Qm#k6|y*J{>?*Z2$4Qk)^jrE3G?b1JlNL2%g4U*pdwMd3=2LI&wuZ zf3GOG!l>W2{gH!{6CAh?KzhA;L7~L69u@UP)ZfbS24A1B5>v=@jdL0rFV;goEgQs& z#j|=(Rxf`)J_SQBFOX%SQ5ycV3O?_U+sgibeuUNWj<@$FG~TDtI{ycTRrV)n@83`K zX5Nou@HPPPD9!Won*ah|=uV3Lx^T$nOP8)Zu^ZpCM*5P`#=G2VdORYmMP$0n1uhr? zObm>T&yt_8cJPBwll56ws)8?O2cySxbT6iLipourueA1Jf$(5Og^J-|tU>KY@@KL% zLXg;jYkwJj@Nha0KY$od8SCqRe}_r(t;LN?jP5_?qg94AIPa5h8x@;DV=by+vDDl| zxpk|GG4m6$ekS?QjRO~2cmCqVVpL#k)i6G^szIo1+U#OdZf0i1n>XJ&Q*;h~h;M~F#B>H_H+B>OgTU#nl~F z6an(YXeCD3W>yQl2Gs<(L*1M?pTKtHJJZ)#&QF&*cRe|9JoA)z?m|t|lU~JX&S#8T z)9h3}WNFpAZP9#@qUov;mc-BSF1X@n$RX3AbpdOGlwFyrSY_30;TlHN&+w@|Sz*4K zV=-*tEAuikJ^j+!gFHF4a{J^)C!ZXB)2axIV)%r?Q~(a4s1qYoQno$(+^N_}JaJMR z(Rjkn3ria={wN#kOwz^Vtc+@UzWoM&Wo@BRYFNOmh~Tc@w}kNpfzZH!PvOQ5ZZsE# zd2O|FEO|P<$a;VeOmy|n;j9C9L^V#y+h>+N9jk!Q&eo_$qEr$jI4I**v;ZrJ)vf3q_>Ht z*!g{0qD$oeQ{fzl#4Y;#`O_yp*Tvb1O5$n<(DdX<)BW1mvI$}a2p>JmyY(p{g24*( zEvH4tFSdbx3ECryN0e7VSjniHNfFQr*_%Ac>marbVbih!*T zv_!xxpdy2&o$4`d6s&sX9UMe(5Dp)x?3bV9kOs|)10U9sXP z2s~8;%n9%smtz8*5p+-D~?3VU@MGV-m3LtwsLWi}l#3l29GP;)pmfApEP}8g@$xXlY5kjVvI- zVvgkTL*&EWy^+N)n=ln^DNPMSX8DB+9+(ZmP7|;$FeAWBfVpMK2KD#Yz~^8s9TwR` zZ6^>58zoRSQS#%*_F)hOBnu$q0gr4MMGjXuNdI-FdT}>&VGRvWA~ne ziwn|awxXO(|NVR&g1 z4LyqWHF#a&{zjtK;FJfV#&ACl{Fwo z@mL=f0;^EiZ-$`hg_I5cxg5A0j5loTc^Rs0uwjt#AT+DNqBdOMRS<_L`0on13mgW;nS%A7;D3Z4FJ&i z?ML;@3YKhl*(UB5b76_V=T_I$bPmU-BSDLNFpNUcNlOSE{l9m+@R|^8HaJifV5k25 z#+3C=-3Ic@zn_FtoF&45V37+KFOnM3;<_*-FsVWFs@?=b7);vN^~1%hUDKl2V1}lMY(YW6+m4>gFg(}aKfP|A{Kg>H0@DRsv2fm*SPgRpA>Ztfflex zBaV8vs~`RT{X5gV30@MbA0e87w+Y($VqnN55sO&&?%OA`c7J6#1_Q)!2N*L-xu4id zh^06|zhMLiUc6aWtNdKwe~P~-GTLo-T{ukbb>epQIpICj`AgH97|O9R$ZU$={EFv^ zp7m8Cp&I*4?+ln4W?IZHlh8mYAIRG8nuc|W|FnnV4ZbJj@5#?$4cO+G2CT<%9@>Ew z4JsNO7TtcNp*3Q_o_66vwL=iU%e*y6J}yNz8#Zplk%$4*@M&r3!b|NvEP?yc76JU3 zxjo|4_tFc(dK%GCSYKq2mL3Ejo1%@AP=FOh`$}?QPAKE8IHAvnWeM^K)v03$j5&o9 zIdsqVziYT|Ls%X9XJSCp2y!9Tr1;WgEl_081NIhe3qm(f%!$IG492j0-6lTb%0=95cCNupUi#mr>|U`n}9*{zo0Ys;D@q) zoovzeH~=r|)|&UGbBoKZ)&iDFOMNpY=^Ch38?$W^7Sge!1M0;dJPcpbp(AkMfP-64 z_CS)A@k#`U(744L(xx6Gs79@?K7rn4VLC6)padvYnYr77Cc(ZCo_e?5q#H73HjGkW zm1cw(dJKgrta`p(!Ph1BF_;9Be*(k{Tbu!m9MNM?m>y%-0`U#N4?zk@Ki}IjO@w~f z46%|Mk-~uFJWr>2SU5B-xnTfBbb2`D(5uEkxYIfguW*Oi4zD#hg7jB?^Jhtn8vyU2 z@Z|jb@Mg1|M__%Cpok0ZH*i-y3y_+UE+dHz;RqTwwvt?7MI{*NFo8r9|Aleh7#D+ zwQZdapkwF@WZ&{IGATYFxpsVZp?AT}I?5QjZ=ymRUMZOW!;PCYv|NBA#yH&J9{i^7 zU5r)ahj}-M=mFG00kBwyi2(6*ae(TA=S@i|oF>X~ALkHJi}~AGOy_8z`X*Q;@jJ&$ zF_Viuij1rA2Gvnt zGZ5ql5la4%|GDwEYviDedk^(4dN6Vi5C`TL>3su+t5BiX--i3*PF@`aR5n2^)TBwx zX7fK@{_4s$PWK0*o69r0SK?%q0MWENPi)1M#vORd6F$haGGwZz!CB8$$GC%QMwiXx5o3BuaB}+6)M(wWj)NRDC+U-A&;I$9^D!a2 zGTZON%WOsM?x_#a?iyB_=D|h@OtIyk-=~QOnwQ5$W#2#VmTZ+@51s=2!^lYlMBCfP z=Kv??R|&va<27e_$41;%LV&t$*|-iqT1-4QVDUKI%N6jZH4PgTJXe1Xr$YpuuDvb| zlR2_S6D2<8)8SM49~&AP@@@vm*AKg0%W?Y-}+Qm&Vx{lA_%6&7m!tp z^WLt_A+|+Ua}%qL2dP`Ew^Mt0g4{=}*OHpf)FELzZ*WuS zw29_APukD*jgJ3#IkQ})>nZ0OltCRMFDiS#l0)F<&n|shy_yS`8Wc?RH~#~+-**!` zol%$nkE{29=X!7d$B9xBN@ZlErAbEih>&EZGP6UnvNuVgkc5y`BqXWq%*=|66xlmu zWbg5RzB}hW-{0eZ9(VWY-1i}$_jp~`^}L<~PcxyU#HP}*Jd^aK&WA97-q4T|r~Afo zO9?bLihebKmL)#anjYaK6gg04KoSe!Y8n)f)fD4nyD2x3k+r@x@F~!C#ra0mVJ8L0 zbq+PON#iephZV%r@7WW(@FfMK38Cxh@?5b5P4Np@@4uCr?ZZ-p^zspAT_4@C^U;$h zTLAgksIC02%?ZnbnWi&=?a|2qfCgeuxN4f4r;!ga@i0)KNd=qq{=ZrQ+1mA>)M_aoO{U8r8eqq9Ei|WJ%V{J|9=zqRWDP7BSlDA!7@})| z`8hnd#=jdEzud-(-MykF%a3k}n_os#Inyg|npM`MoHL!3Hl3_!8osZTQOWhm?@`Lx ztT@(`Y^E#ngPQ80dfTX@eVWzwo%)*oQ_Dgl+VV>5>wak^p|6T+Prs_23{n%FV_o!H z>Z9-T@k-gYp+e{R{79JmJ$I3cGjweI%I<+1SM~mM`Q{jWdi4%D)NO)ysX6huGI2YGp%oL8K4A8!QzBj&DU`Ch{DjY!r4~xbjA~3h5e8?7Q zl1KigKGdMkLKbDE%#L`+m#D8(2u`2II_;8{))ykx8G1s`k0+ku%R$}gfkh6cwP^y{ z9Dm7$EeB!0gei)+^YDzWv*R3vOmPQ}YtfC>8Q^(Xd~-QVB-n+wU+2-e6%9hKOYc4U zf&KekV=~*+jpx3HwHR<~b32bFc^s}V-p>(?M*7;shn_|Aj9%OPVKLJ>W3EwC5#928 z0oqlyAv8+Y&JYQ*5d0qE;NXQ%;Wqza9?ZJnTwO=A!+6xWuZ2|umGDx00^EqXzrG$hA^C}U;s)z!=t&Sdko zzvau(S#uRlyBm0_^}8Bh5B<#pJu9I*la-Yi6kL~bw%Tm|5vBdJu!KBT?Vc(rnbB&L zK)ytmE-QTz43)f4Ay9>dM|}e&HkRsfg*O+u&K*Fh$mD%Z@hL*BhPGJ% zcKJlFkE;3*B$9WXV&0qspeYW(K#vIMMK??IabOHNeOx$v=+GpbDNmy|!FY42wcfJ| zMp_+BmsM3^?%j(s2bjJOZrpmIF+tvO!NwZqzk}$CihF`_FGP5GFFV?@3tQ;@P`#|y z-TZ6ow3WHuj^CBfxW5$>O8vXTS(YEhEUpN%oci(OyQxXvjE_MfmyD+|zgE!0S5-G{ zzwq4Ot{8SZ-~=ZiNVF(~+xQ7b?$@;HZFoe8FjK-44CbK7CUE#-tNV^z`J5u1@#gTb zJuwMc&vv<`v0Q#8Anq-@Dy1M@b?^B?bN>y8n7OV1p``{!GY6(DVK#Rk_uI52F`V>j znS1Pt?tS>OA1Xef$# z(=MTICzAy8`Z%$(+V6*FXL!X{C(DOcH?9o==d*~ou`3~Y_^rpDfgt7E|FV0f{NKDf zBE}M2diG?p(xoD^CS%3P>wA;>NB79dtQ~V4vV2S)oR=a+sR=iH{+qmsxwW(m_I^p*KD)5=O)ymfcGnK6+O>V4rmI7n~g zWIxtiWw{^Ha-pZv*fh6&37mfnChE!KBl|0q(Z~_hGoUbo7zq22TLPAq)6;1k+Y1lg zD?g6VRG11;b>9?px00OO@VCC`T$`i%gEqI)&%SK^vls3+4Ch!q2+B6W0laACuqEh> zqBQl^L~FxCm&nQwYvB2nra3r%!c31q*Aq-rE-0VhM|<|16(y3gRCkaHS96Y99E^(wGiUgdo&!;^N}C>@@o_7rIL{oa5DJ2^ED2?*oNv zLDF+Hhxxg;z@xOLmEX!uon^~_7WXpK>18H=CR*X`UHo{FSDwY4~xbVZlKTLohrDbuFgi@LslJFw8V zGoll{(Y=rQj|LtN&x4ay1zz*w@3f3O1S5#ZM1@J1{3A;brz7?N( zr75ycxw+K|Z!6BT0HhGqX$1q?q>E2VU~UQvhnk#1$Tz}p5>5fx*Ek8|64FV?c!|6g z`=^$=SXjUVD8J`DA@9YL#c56@Qh?Prh-qN=Oza-aPhk~3zrf02XHI=H=s}my!3$5B z<;?Bcg9?@PE@`Rj)y&7XNAizUrKvfC@r-|%A= z8kwRN{clF6NABPMBjeI|Z2pZz#hdIXDn^Oh>le6H0|;t^+c!2cEH5N4 zuY?xvocU#7ZSlf(yzQcvWA`J;yDPGEEI;FmHf!7D$JENjoWFeWV7pzj{A8tZ2ohi* zI>S=?&-?aU0KH(o;-c6b8yy{>mNp*N?vAAa#wX6alL3`wXoJme+!(&JvJMv7M`S*p z16Sw%{g#~b11@x;l|sg2?e+}!Htnk3QQDJUZQ%4lSv*GVs>cHtn%d1hOA_J%xs84{ zEy_Jn^l=9~TBtz;_*^bKxgb&Wpd?1lTH(P9;{KC6wbZM^)`G0eqG!ii!rz$O^`1M}ENPxoedZx+R@h<0utH+O@Ua%|&Ief?BtT&(j*QQk7p84HA9%FU~n{6o;zXkL=vp6%ceHHz)SB^G)&8=w@5}6$7d* zMg?e+;d=h zhy;~|NCj{P;k#h*^E4*-C3IbcN>d0%o1lM;Kk4k~s0H+klnwIzkTwD$*-@lRb5>WE z6`}{bdh6VFFCa1`z=STax#7@|5?-xjNvDb?V5?{FJ4(%p82iU zP14g6eDeD57yFjFTl9`N^lMF&tdLF=je6!-v{w`abla9BH+FoA*VUE2Hb%n4v`=Gl z;2fWJbpFaiwKoP#Na^wQuWb{qt%19@9dm}jbwGbnm_yTF8M_=a32nN zEB?{Fz=A6}Vyw(6H2Nfg{l`ZAuYhc|NzXe(-p8X20x0y?2ZV(`)L5N^Mjo0Q5}+}J zU5={iF04Y4IOGFzLP6*WtQbJOM}s5@>o26)O$-u}K(H|ZjJKWgLJJMnBQMNAAQyva zf+4`4i4iOb0HNeAZ6PC z`i$QMq&g?v+w`Ls+%6YolMzCt{YPtP;joN+m_ zX9@2+)>t84{1zO6`+f36^U1^yFCWm;uLTvDbO-s#md9_bOORN!eF$m$pyj#tN$RCS zr0>_}FA4M;(OK34b~Cd%?^x!9J^a+~#+g-xMQcp|Fm;bE4$|Ejf(OqkM${)mEo)pl zcIoU zfrgTvjjO$$xL#q_(|sm~cb?g=aFc;(ib6vODa}7ii(yW<20?~60L*0cTYCtkfRGcA zAY!o!MlsMU^w{PTp<+09v$ej)2-$UrUB|@58Br5^nv}p60U(p=6I+uOKPtvDkh8g& zg76fPA=qQS_v1K+qxx+74_*l^oAmvVZ&qVLCA}wV;;+;FU~nf(spPFIZ8p z)y)04-)fv>pz_V>HWp@K3i?$zC0F!Cq5;b~LK$_SXZ8>5#`*6ZXE6L>B;<4A) z3Yc$4*|j_Ato2S`tZDzkeWOQz!Q6+=_pMbw(<}2=X7BkLbCqAOT%23w4d8rrEwoBe zGO=;ea+x1T8P+m*=9Uw4(l;i>7s;33j%3=)cJYNRjxNh7f^{Kfzw28uBxTr&vR7ok zIO~0JdD6e;2J(%@efN&OB9t*APMr8eAUinK?}g4di`Q306jBJJM}q9|TrJ+CIusOq z>IkC36gZwju&U|Y1Ps2D!K)hAotc|+*q8_4lXs01ySffz!l%@&i}z1(Q<^&0!VK8J z@auH*NDe)VuN==|)W`cxsHu>kN_Z9kMu};Vv6{jqoG=$g_DL*Imika~P z;da(Dmb@|S$g{zQWuuM5nJ0(2_fwr{RhRg#AldQa{6E2iw%J90!Ufi4&z%!1;Qv!? zlF5D3R&`}h{JVqXi`fn`H77n9e|q-(`Vh0D^2~yDbk1!5U?79|u7XZk9S;^=UEj=R z7jYadpZk;FT2`xlIq@aWs^W%%_>oPko1k!D?sQ@X{UfRMPUW||p9g9_z9ySk@Y|BB zlON?U@MtC5$B%bvVWzsig#ePLr|rCRxJNeD>m!Egnj+dS|B4Y%+Ts&3dOpZ_r7oRM zKwD0MLF$&ur{ITfa@R>*GuX$vAK^T@*BiP;-jcXy*Npz}o}EcPTXlmjLJ|8(4yBkL z=*@nAYj138d(bojNg1i-!J`DJ*h}4_t1t@W#eanI*C2i*FmGVyx3HF+*W3g}M`jj-|nGq&OQQEP&9%adJQT?p*K`|96#V*u;F ziI(~f6C5`1_QrN18K5lsmiOi@oUngHY_VEFw>lID^no8oT$HO3;{*@)cN!-rT)-^A zDu@hV%ps6QvD=%U=)4FPp-BFZJv&%MBhe2zM1Cq@3M1Lwm3N-O)xb!^PL%SO3Mg76@BR$AND1ZsCS zp@c5>1O?xC&-ZR}L0MJv>gSaVE|aq*-o);Dqpt*g+{coV_0>DZ%mOB&t~%{`QX`E-)_LV9yU?|8*FY)=ibn}jZZB0n{ z{mJ6^QmJt2vA9ZXW9Z$+wF@f?oWGUN$fy5(<8ZA*C(Hhxdh`>@+5{rLK2Qb(mWY7T9F=mjA`(6}@K>Lo!ou6>w#X?0U zNfkQr?%qj@Av=(WLAD{%n^DhAaHs+{brSr8A|1tJOo{#ptG#VLA4>~eX0Xs2&(TCL z0nR(jsz+NgOcy3PiM}7JO)@x^-&IR9#`G~1Bnf+SP`$Cdv_Z-;T+j$DK1K%wtK|=E zCiul{b6TA*PN#1p0e-cts8gUi#z$YwETASOqb}M4QCu+J=(Xd?bl>_ zD}#Edwb)(aTk-Gw@wC63W=lKFF1J_wG@YDmYfMPWI26LZC~svKR#{o26)v8d(n%=v zg22xOyG6I_Vj626t!o))TNhZmeLD?|u6JLUPRf&A`4QeBz%}$9f+0dMOPJO7lxF&I zvKXo$fX_pB4EubjV5`Br=Pz6mQY4#RrUOcpK59!=Iq{) zp}5ikqdv5MYnM3K0MZO?WIFwsQfzkGsMZq_P;5J5X4W+0{Uj&svUc5ONtIi-ZBJYl zDD7X};qWju`a}Cl*Tjk=#Sp*Kt-92i)3HiZw;hkFoTZk(B$={5=~PnE5S``I9JA1@ z3(G5sk2Qsy85;Q4MA?GVF1$IU{>J^yiO;z%Ln}pCeY+{U>D-WG7+s%Ve%mn_s}sAs zF!TPjk+J*2%l5ifTRL9DpHsgnYOe`LJ=2dZEW^3xZ+CsV(4M+jTi#%uRJ=>GENm&t z=MJlS@IEuW3oG&jU}Bi3B1g|Ub@*$XSTy$dnFyf842-qWzTLAw#~rajPEwJIneZBD zPywQ&mNs`s{Ee{dSR^}}@8xvWnaqv#!y8T;^&=CGw7aH%bRT`sG5B_5&hnsDIa|h? zffBEIBiok)wlfa7F`0u~80|F@6#1CV*$1ggIQJ5bk-F*D?IzQORL7~C^(7iBSN1*F zvRUlZ8UFvUEdSnfn^>m?L3ewEW*D}A{}|a&QM!&f7Hlw_kn;biaHOe$TvYb*>q<2;O>f$DUIafk9zX zTe&H9N9mV6+y&h|k1l^S_(Qrp;xPZMyIUF8tgCyH`(0{?+{*E{?dn(0Gu5>f-%Po| z_is9S1Cnk3eCcdD(v)=nn zkfjn-Q*py5qqg~5y3V<}PA<6<-2<`6!zt6pH~oxsu1TS>EiXHF+xu;DK_bO@QyLE|ns3FF7AzdX=asd;H7h!u zuYao}5uZ$>XPq&Ik7%>yW5}i9vcVdS=a1$`XajdCV-V28!c5zIvadIDIcl!);XOn%!V7NlI$kudevjM}3c#{kI196c?-q z)NpF@ydG`t962=fcw1nNBJ-2ch4~e-{&~G&A3IFdf&#mEjpS+r8N=h*-1v8g2#P=X zeQ=I!$MK*C6;tmNwE05b%v(`gNE{eXBeBv`EI!)*dOR&s=N!E|YdXu%g*u(ZHlDEs z<0Lf^LuyutW2F2W!EO%%<#uM7LC=2wJXac!O&BsGSAwEVOa3stJd6?c1OKT@SFRk| zH!Ese&?$yBK#Q~P<>IyU+pQx^Bn{JKU}TJN=15_qwuXGB7xemz*i@W-i^#{x#w@3?I` z?AskytKaVtU04jTXwScwz0g%x7v$#uu8OM0HUC5BPo^>H!}2tgM5}V`_r!2-&l}Y& z*BwW9AG$7UH}!*eEA_TbXW0_YwWR_ZO;P^*7-_adi zJvwKY+n%ICUkW5WNGZ8|XoeWy2?~?vVmX_nXMUv~gE;zwxs<;X{^p*yn9` zW$u1TyNDA>(2siJ_&IB;vZtcH`#hJ~P8PYuNpz5IrELB`0Fa8F@|gGHV?ca9vWe{Q zD*>rt1)Re#Y!jttl^@sDDINR1`NfsvfIOb(=F(@hY%hhYf-^RFi(johiQ)B@aO`?J z#;913>LQ6>FiL3b=IWie_pP;6h>x_sqR@s};!4eZ*LHtSeFw`u66^77Q+|HywOuT1 zM%>zq-4tG%N`1dBF^jHpYtJ~T<{5Kk&z-SoEso00?UJbrOI@8G^3uOK&ll&mD)V^P z<6~l4W!p#Ns)uH{UHW#{nr#1Lxej9cnYZsg2&bl|n;15~FwhL3o8y0V@pq)4$W>iU z;&>F|UwL3*wc33`d7Gp7#s9m}x&s$=rz*kXsTG3=NB*syDm;Zj{l_eSta)?aoU72S z9ukb=cmxppgpEJh3ANWfV9O8*sz41l5s5q?A`?cP@SqYw!vJy6*$2*~-O!pED*u}=S zm7iI2raEK`TOytN~oHS)Wu?{ zFar=K6Ka{=l&zU{5uw#RNUeL-hsE(Pk?tjcH%1Mo^+BP(C*|EVB0Bg1n}23%zuhzL zC6)6FcCbZP_2vQ|*QvRa)Rv0Tk_CGESym!}GqQ;0V|d@`0)weBT-ydrRs@>``)qbu%OeKh)LLHBo1C)TQGF;|r7#X81_7csi5* zNUgl_$1km6;~CEueWrI_{dAF2x8hg2wcU#>23+}aFIWG{?Iob8zv%3$i}aU6=Nw*r z;^zksUJs9=^_359otR=`I60Kp$GK(&iJM2O?X>%}UE4{etenZd6JA60G!l|%v5Ja{ zX6NVoW|n*_?YP#T#XK&mj(m5W@-i1=uzY%$`V(3`WcYpZCMApHGpx9E;J?KL)v3+4 zF%CAINE`=;jPqEszNiy(GFK8!$W`HL6LZr&`zxeGU3)yovJObl>pBglRzzP9;4 zi`)b-8LF1fSb%f}zA{y7f0~5EK{IzM8?&09OTTryJdC)EIF9U!W;!#rJt`)$jLUPG zwtJ=5X=Hdz|7M*%>uP*A$>iD@r}y(+?T`gKD4+=vY3}%Jq%8I&VRM8{K1$4px`5K@TmP8Ba;1+~)N+f2SPi~zN2}c%iDreR zkH@PjH1lqbACRj3IQ?K(-^B;_?}w0m-TW5rWFVF%(Hj2z>kEXU8xvbInDF=P4QLsy z?4RnHaz?kaUK3w5F|bsxL~=a*ci4q=wRl_Izmgsbo#Y=k{RVnIp&$DOSLj=yu2ND` zY7{!Z+dUw<*!jm(pkd`r2^*kC1fGLrNv01n6hX|(>$Jj3Cl7>5QUWFgpzzZun3Syg z;^RNEbs6A806hna#_--j1*{s`%EKp2FX? z68`jYJR8{ZhxWx8;YV}F9=F4$n&sSzPI>Dah1x)NZeHKVG$)pvO}7ooQ0}U#q>V5M zKP5>1JNV3H9j)M&{=;_58b@^asI%2h-P_q`4u2nl?M+BH&{G|gBO$V@A#MTB`XYD5 z+e81n92IiErksh$7pvT+#zrFJ$FZQ(t99Hl@yc-sZ+tfGgxQ>K28Xcla+ddfRUuI+ zhxmG@s?)DBGefJYsw8JRtOUg4X+Q@=*7sjW8)*%V$c^_%xJ`djzn5KFe;XxbANY+) z={FjK(Oh%58eivPI!TA2>y9ceLs7a z_U>H>L^AkV2;K0(V4MV;2s^|@WyK?*V-|g@mybU3ne?AAK==_Dj_<5Gh2Ip-YaR1v zI0J?D`D@ph;djb9?XV;-!Okdh*!$h(T{qsCC5@HK&s&Q5cQHsS*zOM5wsUyLw^K{k zZaEg1rJ5!6I&T-#5vxd+v1@#gddQ^elM1_3%sHY3fFRrS>(etlucdC|0}urjpA>h{ z|KGN&LS@>u2*h6inPU=`W@bRbsVENsggpF65RPMmGzE2h!lgrGnK1Z)ka1*m^dJw< zW3WJ9tEFw&AM(3yxOho!TZKy&c+$FFYYxN}Eq2e}ElpksTLVZtE=F*&>>ZuSUfz2C zurzHr?ME4P<)OvrT3@KIyc6+a`}o`ylo&=jdL<2Me+!g=#Owe%2TQ(|?8c_Xb5{(> z>1L|9IR!5HZrj->ibbn1SP8u_?;?c6_jVs55uGe0BUJgY$Ra+~zoe9kdktM(N{Ds^ zGYQw2P#r`mU_*o@GLB;WX4bW6_b9V)Yx%J=XB-;b5xb6kF}7wfeIcxf&`|?zh1P~B zRIsEm$<%ys^e#h=+G~xE0bIodiyU;aCwKgBUsX}LUEZsYM3Qoo*!A%Zi%^crP|;(o zw_o+Sz6#hUm{)LDH^T3hIm45qbiYzgOP!K!B@<6<`c>N8A?cPGn{z~jDcv_ROwN`o zO3qe|iYe9|?45g)(cP=Qg@vMs>8pW2{p4oGk8v))7@ITnlno4??>-mk{BI?WIf20$ znioQuou0mVKbmH6gbBm0Yu93Sn{6GLbA@aLIcBVUC6H#JkwmqE-r)q%MiOM%$B*w+ z8iw@U&o~Q(@=!OHH8n(x>^2waQbesi1HX)rW@x0h2(57m96Ryk#cK@`VI})ZZdvzz zAMAbQ*xWxdM{CHVpT)2>n_=6TecW19NB4MlUi#kB9bDe5XjLSiGQtUQFnAv|vXK_p=_1Gpoc=op4wu7WmG(i1cXMfSs46x0*F4Ah_-$zs>r zqT|GZc71g=St8tMI*`^XH=2Ug`8Kw#nNW@q+83Ffq~ihY>e===LR;Svm-;WqDe-Ro zP$G;Q(HUa{1c}c{C?l^S)JP+}*`S~c0+^SHiRE7U6NJ?p9%xwn{`PWfC9G(%kh%`@ zJ|N66ii8?cA806Q^jp(x8ur{x6t);xz8vPc9gZX zhd^^IW3{2&+z>q5vvY`WX=yXhAP(!~I9IHn)!kNetXyP&HF?;n?^s5k5#sgmvuG;)U*bqCDTWg-@|VTs)O+Rbfq9Og`+RI*$-W> zIDMqKHuCPREJ+?_f7{Zd%!E>T7HW*KYQzkqv zyDv}4#@9VM_3cNOqN%n(=R7Mji`cBa@Vi{cZ%rc!)x8xz#SJDAi7ybHJh3;U#jk#}d~|8{`zVWhYd>&=-Z|%y@wsOtckVb02T79qZP{t@oz7~< zVZoD>Mv>ks0i=mS3_(gkQsQUsF}%ZKitq!5-vyxz=*JPgAMgx}AYns*6z%W>JDy{J zhm02v5`9p35^E9I8X2sypSb&%Zn5byjH`8YbnG1+mrF$Vo&&)h9iS9MtXM}U_6aS_ z&#PX!A`Jxy3AAC?99xaCecm}I+T}WW3c6lW0tY~#(kT+wU_Y>K%GtC|VTdJ|(;oAh zC|yJ=g#&?zt3%l2TeGGkK#Cx+Lmy@H`EY~^*w~<2lOXz)9b@Ll1u_vDkL(l0%4 zex+jeJ>?8!3ul-*OCy+WW>f0C-BKj!C!hGZNZbF?_pL&VOavhXdt}@U8$o8(81~&P zEQ;_Z=H}*xuZ$k$0o;(gdC#zYCUlapeT1JJ_Mp(T0pX(^{rx-P`E!UuAHo0=w;256 zAb9wLjrt!@G!(a8piPtz{-vQ zTd70Ohk!~Soo=w3Lt|HFl?zqwdDxYM{REy0x7WHm3R*3MaQX9X=7ekxQFw%*3brHI z?0trcWi?n+Te}8UQiO05@DPlO1Bj#Z=8so9)zz_lflm$`xP43fT5w863fUb2qk_?~ zdIv4NzZCn_Lxx?@Frgf(ptpn*iYcNmDq*jt#KbasT7ieJ+V)5uTS5FMWMPsNPv43w|vlsldD9`}5?>)KyEfvnhdWsa{xYT zEprPC#B~IrOcMPH4i~rz{i=)IUJA&MV0YvXJifTvF3!id8xDPqH)bU!hP))#LB3vT zUk8o^TSy=#^6Kg>&m8ud5e4+Zh3ClmL$UQ-DCma0A68>=cx3q>Px!OHP)#LJQd}8m z6p8GzzRCdQ_GnfA=a_0yFNo#<5-#c$U6J_15}gDif`Db4h?I3yR+yT^6-<0EmtMVN z&9@!eVw4w!SmAKU-$4OwG{z`p~}3E7iOlkJTb{A6T$TLE$|uWZbH z%>wf8rwu;^{f2pHf|3#vHf6M|gtKNQCX(GYjrVYDaF71VpFkED3WkeDvAYoJ6bO3L z(ECjWS-Y2a)5(*IGft>cQQ(8DKN<@5T0MxHA5yAGwH=z4v96-%W0zmvs%CKt%$tk2 z{XZ?ac=Ge--XQqLRR++*ckZu1Lq44 zCenf;@qIn+JCjsLB&>O&NDv-7TMxzAd7`m4k|#d_XMurqI@K+x=32n+b5(MBE-K0#{S_vO2LuFKN-S<;62M`PKwpO8 zJrF&fxuFS(J+Pmxqk;Jutd`=K*e6M8Ldtw zk+y{+*aggf;+&z^v2Q%~r(PyVFeM)9uWxgMTAG0^Eq4QBtqMWMX9ti4M+i_2LY~jSqeaC!CmZsff1# z2Oe%Gx&G?n6m~P%j=>`r4HC3+pYS%Nq^GlFy#~KxFXuHmc#YyIg;lf-0{+Nn-v&ZL zO8g-(9Gn5;vnE=m^zwd+zMbWlkZ=xqvZO~Ho5%lbGX!b!d%6BgN=`2)LJZ}iJi?r zvyJ--+9Q1bL{NUQf1gU0Si6t=4jrb*i}+r{fz-4#BkV?qjX21ce_u{$e;?If{lC}X z3N9`VuwoW>XUJ_Qsw!?M zJ?NsOYlVmZbJal1G-W{L0X-&i_*$RF+XTo47H+Yj#!n(5F6-%Sg#Q_`%_n-skAM}i zyv5HZ1;r#P^!s-ekNof7@AaV(2W?sE!OoNyWWfyHckbNzR8w;hoFIsw37nWvu0pxL zW)Q4(O3ymj1YHr@lNr$aA=E8Janmexo)R+u6GT2u`S1PO`YbJNJN!KEZB@Zz16{dY zP9eHi!bb;*FL;OGWYc?Vv78mBmbEpPR=OI07y}Q&2G6lV7Mv&7*YTLWtwJs$CPo2e zI6}`;2p1L?A`)^BWX1QgwJBoIelAOj3xk`1#v<&=6HI4PN=nq2e>ziM`;q_eb@+I; zly29q1Nc$UcAzDUYcf6pIhxn{DwoF!;6D(kfk#$HI8kYMc%QxUJ92gP=gU4%MP z;yYR%4*1Cu#|J{RKk765$PW3hwA{w++}w`VekTWqcU~Kws4p-+!}v}_ zu%LK%SM^V!X%PPXu$(CR2H9HmOSYISE+{H)-cptg!xqA~8x@qRXm%GSD**9RP;l@d zY!s&p5j+T^H85EMpY}4rk8;YjXx9Y!>CKdk&lSlJp(pysJ%&j)qlJxxIIZA=1L?m! zSj$*0@`SZ-?VoZ6L8=$CGm$w0?^BRC2(CH&>EPxfvm7=?1dRW!G8Ha47#qP^#S@xL zF2bQ>`}r`$iXw@eJxe?fnT5)52m^n@@q4Rsk2+$Zr<_HRKM(?AUaYlX$8AW|y}f&( zFZ~2*_~)zYI``VgO<+ohV*`%}JZurx!vfAAz!v1tqgffJu zY2G>$C%-Lzz)!)nbyEKw9khL-+J(;CasroG|HlPDArl|9#4aiYff-9f@umQPrboXk zXXoZ-VwNKWH>l;H@(>>qb1=as0^^W4tl=mnitQdAeI7h@aN;58vbf^#V`sVzLnSCs z0I8!A!S$Jl_f>IU-jRn*K4{^{E}3+gb1f=d>y`(LBmaB% z*eg!|wLPGuTwLkis0&xu6*}%3LJXlkoLm^&z)V}_ihvzkNQfi=2NImBJy21S?&swV z#nFmYF#duG&Na>!Mz%CC)p3`3AS4C-O+M*ccl2)v7zxS_EK#<&cZvuLBeOyP1~Thq zJ(mLADId9?54?Fi`~lhqw5Y2y#LY=feGYdS#N{wyvjq6ciu&gdYe> z&;%f_ARuEF1Va%RAF)3edtZa}u18WHio4*5@b^)bz1Q~bh{adOT|5cg=kHyRtazIZ zPX*M2%Kl)9I_T9gg;Ng?t;kgOU^?>g)U-U!fO`f$ue&%KToNU4WB|45aV)4`)=<}V zIZW&W*}P)<`V74u&0-n*9*OBhn5B}E(%F^*7+PSuIsI=h$CcM85KJ#5$kaChLX!s~}qQaRrX2R@;s&F!$=4!=&M zz`#w$D+-Q8=um7%({s1X(kuPbdVgzc`vPIj{ovpT`nDU-Rpe+`*^4VoVeH35wBRoA zFve}t`kTWBuI;zxX5aE&7!)m+BUTk?Bs&Hlm|4uadYojiandj9CIYy&ZG zj-ZebE;TTRQc-y{rau(&zsJ`9l4Rm#BgF@$%@)-^#$UcvxWmd_2qEv=fBYg{)|ZAZ zC@aHi)%yDm#!#d*!>*;0key?ogeei!9Ge=Nn$Ce|hi9+3Sq*#iEt?HkgDK#Lj~*TS zJOenVt+(p{T!TvoJU|G6CH!KXi*#?_W?CruXOO~|p%5G4IGgTcvV4*3O{;eiTYO*` zM1h|#n!8>~Q2GGF;_1To!9#`aV7-(BLmTb`ylw#@AqyM@eKk}|j8Cu8O_cQ-XM`8% zE5ur)qTEPRq(svYoLf(ER?+O>8Dqs14`EUHT#H!}lic>!e7hkb&1Upf0E~9X0hkrGH1qEc86>}fAeN@o4HvJruo}asb`;u=?MmK zaY0-D^XJd)3-twBUtvFl4mW3m;rQCx8dko9l@isKa{t%;1hJ!PlrT8iSiDklh0Wo=E)QGX&fJ&B7e&258Dkvx*Y{tO~C&6v7gKthEzD`Eu z>9O6o}l%|hNyoK3$(;bB|Y6(V!*WupbasvN>(TC^iG8HFnoiFT?qOwJavHJ&?4Pe zO%2<0UvhvJz2(ll0SU%`?`2AZec_%UwIKGBa(7sEs)WfWd2Qv5|KFCO=ZCspQf_Vw z8#&Gp_mN)1ipg)-DZ$+yGcS%UC;;(J8=yl0LrGqW#YSz7M>v{Riu~kKuHl8vyR@WV4BzR$(;)n^PB+lK03d@658MRrel;n- z&V!DTLJ@n(2Tr7@UI6*GC;~@;xuwLLZ>V!GhQb$f<%&U<_P+Rky^diR!8-qHf*>;T z+byF>xTa`_i46f_1>l1hBzq3rWHc5&O4w)ao-!wVFLQEmit`U=Wn=`SEd>VznGDx) zTA~WWfq%DRjJ7Q^@w3bQKR|IMzy~VGr<9S=lZ4=`vdbFErhxxEeJ@=O-aS5kWQ)rVZSNzE8XWesX$R%7vlZ8Gc=N=f}1EnG+Ru_TL`oF740* zrQ~x+dgqTWnf1U~0Pc&AR79wE4gF?5j^xnbwbq6qh35^Q&yHlam}P6B+FU1lK=R@l z8!_atZ~CvQ67Qob3e>JQf4{Z6jQla!ApZBqcwZo$y-4x@zutJyo-KzYqT`Z&_V~ZK zr}!nkuCsSpS=r@Z8?fPik(D(YxUd4`>?f%4Ev~gdC*z#^wvj*-@e!Nwl4%}c5fQ>} zZE@V%>+cY^ovZMyx%p_x)c}mLcEb(NGu%r+-`t8C1US@dsYdU5@-EP$6}+V$mg2c4 zmH+R#UVKW}kb^2l@zvbQs%p>{qmHXCs~utLuJd6x2?kSyI;npk`W&Lzp}_>49Lu)a zLjhN_8N|G@1Xs^wx73(qVwLIHsjXASpBOChq2GR2C5$?{0hOBwksj(NnqoBk@a?3-BZbcVJ*LW8*R^NHps`NYd##6}&jT7jR8zII zJ;2w9RgbHi8yc6Pecg*&fcRpm9}P4w4)8X#|IUCRF%J&H(A|Bdy?YC>8-<_Jd)RGD z1_LYnL%>-w^g09a0vI;nWde8uQD!57qgm)u(JG^vMKckKf=#$n0>EMOTx2I9NfXcvWn~n_j%C7&4I)xfBx?~Ijm=wJSFhPr?kR+8LWk>U zI&^}qJO4T=R-_yfgZbXy$EMHx+s$l9BxrtD!cCtFJ3xdyuttOt$YH#LAY~BzYV;Deus^BNs6kp$mj;i;D1o z0K!W86S$X)iwkiDAkR`&Q>%gimvDu^8XEpZWTvmpfejMQh-h$l3BCpN9_w!@p1~Lk zX=UDo1_v)FUQ#>Nu62P7T9<{OhBhFjb} z86#;F1{W(x)Z*ypqyZnNrD5F z8~(qStzZsP&lDJA8LO}FFPQe@fmS-=s1SbQ(l&^J92|9Ws=HD!qQb$O@Yh}cVTnmH zvG9Uw6@#}-+7BMfwk*l&1!B?w>f_aWzg^_dn=J$_#Xi!h(+R-cy6fQ$?py^MY6 zm(hn67FoF$kqxb^xK7PecL1wteD>|;r5jl(Sz2LQJC3JY^%TnbsHW}93sMTuVha=& z)Oc`eQ&pZ#{~|>77vQ1{0@C4w2SG!TF*W4?uuCK#thf8#ySIbVnVFgbD6G#DQ=X{d zv9T9;h5=Y_tit1y1S&h{W(WA-p3flo%KpeG805#lEXe%u@-OwPS0Q7?GiQ2@L%%^d z*3v&4fS6=`({&z?Ug4PUpfNc(%sq>{1l%cEhrmI(o~eA|#^Zb7?7#Pqn{rWe=Kidz0<* z*?j7ilYlcoc0ivH30gaWR*?kC9z;nY-Z!!gy7*wMm?eu$5y2%PD3pqe@sAfA)~V}D zXpO;YH{y@3&*Q|G;9a8*lC^8=5+OJsga>X&2=|S3Jo1E>A4EsEFn;AW%_>6*_%krc z`#f>V(Ur#KAhtIcJU2lAN3mH-&y)oWwXDZZ3Mf9;rr9!yCtI3iWWm+u`;{h5ouEV$ z{ok)rU*;x;?hjy${T#@DGVoc$=`40xg{i6GZ@dj#C=z!xC#t^U{KO?H=20{&q?1=r zFfu;!JhxqPVM^YDB4BuYtfJGPy3^`Bi{T+Y?rla=2deH$OVLp%?KvK9VZr^HcmY5& zD%9n|TTTK!CdxWB_Lcw>OhC4T;_?=th2=l6Ka=tDl0ffFoF+g=Q4xVu!H7ZEeM$xk zT+qx6f!1JWwH|hRXn@;EiL<_c>K5d7fO0(A9AYsy6FfX(fsDR}gn+6rEW#25(&xZY z`<$+G*gFqp&A{*x{zPtos?R-FAyy5573=e2koVQ)v7iGk&ZV>;1onZ$f4Q9Z-(vCa z2z&5JT6XxGr=gNcJ7Rxa6}>^DMpV@pdlUeid>v7mHbUpX%;i>pBp@bj>t_4eA)WRk6=T<`{E#C=Gln~2g7T^>%H zU09%lD=ERPQA#Eg>=%wDMn?jt!pOVM6cZL38}!v=hDKcgU=eOgeco$~NWeXu!Da+} z8Msg2p^)9LPY>bwuNSb1@fp#ng#Pd1-OWs5Y!5m3^WsDO6UVAXZ4Cm0${AP`HKaD# z2<4MUD^5oByT!~VmBkv!nV;5&YkWoJ+Gzfw`>efv&yCE+&W5wvjik&w=2B)|Yoq$P zO-&3KC0ISKhmG;|-GLk%A6qQBmJK8#JSQT?>nIOvLx~9qd4o^1l?pl#7>Uzz%hv!r zdEncXp4G?%q$JrwK|v93+omQ|T!Hxea%CM@TF;2G`})g20KT z0$QVPY{f~?HzPlVe`7U(^MgNr4F~4Zqs`bOp8Nti6FVOr`e&2CP}L?bBt7cA7IU-> z;i?pu+XQPrf38r_yvKer&@iv%vRr>trers&3S{20BRc%o!Eb*JB zk3Y}CTpJmaDm^f;OWfx1n1bOIC@7eP?fn5+%5kGs#aM`40DNcfEW}Jzst25e&eLKrAXx}h_>y*KW&@8!Lxo1Aw@Sz zv*R5>;>RDPj9EM$s+CE+a;Kgmu*0C)S6=S=A@-1vLj%A1CT#W7QWK`L)di;q`ZZ>L z>Bq*N*SPs~w>&vjVxx1LLEpcH*ZY6poBjKHYpye!qesjv_PhR4c-gVaLO?FhA8yQw zwk~$Li7vJzA59f~D1Ov`gzm^>=AZ75i|>xn4=hQ{ExS%ER&uq%`o(7CwdT;cjXk?; zLgo?L*fZV}Ici!bjteeMT5o+AbkJbRSXwEXQzVf%8aF*gA3&`8{_pl}+EL)BlFiN* zu6DlmwWbD^{d&svrQt(D--S{aH8!_&tQ|Bwa8T23PQXmi=FVJuS8xA&)dw@(hvd?B zd}`ZQcJTDw^N$2QwkR4WT`A6aXv9@?_S^J{`%zBs#$x^!X8e~d`L=&rFV1Jp!2v1G zYgeHjN<|>%ZdN5Pz3!5-*zGqKyvdvkbv@tzD!ArUIY@H-<%`MYH%_VMHxph=3#xao zo%6Ks-(k_EBbWKL>Q&Ok#ny#C2(g>FG_`ZWb-0B&HAVlL;Q_DZjFqUTXKt-V)AJWr zo~su<*MDE_*TD6e+IrT~U3+D5{z`cDU5IlZcQ^oRWW^}a7wzRwIgV4+=MDU`$ck><+j)gl}=f;y`wg3n`X!RzT*=`OGilLj|Y=Y4om3vfk#x@rA$48K!LM{3RGzkr}`g= z6f4h0Ze=Z;p%9&)7B2RvFLGb}CLySGwer-)OvyEIFV^m&<>=MbDUSTXS+STjg%D1Vj`vOG#QhW#k_@h0|K>+1LTuKW7W5^7azb# z1F8|G1WfKA4Alt=#VVo3uX@)Ekwx)t=1VT<{9G-rLu;RNdw5_l)cdh)qGU!39W%3g z)rE`}BWQi7sbx9h_Za3~J~|xXPF#=2|DKdXt@p{;E-lwK-Bpe(4g9k~qNh&3#yRvT zqouE~b+xy8Vfwo{JP-So8z9|4G)rq?fb%a?nni1;uf`Emq1r7CU9A_!?p*xTUF>r! zber~h3W*}i9W}pnq^9^LW6;B=lgrUPxi)jzaYZA(_qi~zhx>$8;BbZz0vN6YADSu@bQC3i2 z{u%lk8XLVktrqk^GDnVuy>REVv+ya$HVGc2;+FaeSC0Et&de;in^GlWbi|a+%vV3| z*gvxb(_w7K;8P14Fn+Vd75&xZ`^}|g87lT|PU!6PFKkEH4Q6=JSM53BiCp6Ki&t9= zSb4YTskgkx)CFB6OoaMx2@)S05iJN~k(R!@@%=i_=ei^RA7O7D zR@K(Uje;nsltoGi3J3^@gmg%Ww4@*{f~0hZqI4VyL1`)J?iK{eO?P*9*S=%x@%_$s z|G0NQkK%){)|zw88e{yTL-6ATNk?e&!+%e+ma$|AchB;yOS73}-*-l-ms1)UcpX#3gB>9}en9d03vSaA z?S@jziyyPTIh>uQh9HsYT%95s$|vlkVk=bHDtzVR(_$o}x5 zR$Q>MR79>$BThhF-RW*uQ|aDt#?gu3gx-la<@ULtmd;O_h|M2fC2A+F+N^YRQE`G> z_twX?V71nnYWw1%0}mUD`_y4=Gu$k=+#OZ5zr5nyh%? z{=S{Di3xzYLD(G}BE3Ks`FE8E(6$Z6MG&7Qt1WakQ^-O|%yXXicUlis`vRT@zToLK zNQyxL1*(Cd_%l5-!|Hxqf0e2l@6y$!-}#Vb;J8n0Dfb;vHfh@%TI64$x_7Nu_v(G& zl=t!PuTprW^6sX*fAapz7$`elXJKc0GgSgqPPKf4|v zE-Ln-%u$ds_@wjzz_cWBJ5>j?2d*^}i5?PwW}D?QdBCjK)FaoukscRQJcU>LPqpje zhBoCw!a}TJmop>U;@I7ff)htlUi&Le`L-+QrRUvJ4*GKpEg2bQ2g8nSJR5uv*jn(P z6Wa@(a}BT@GQAlKaoE{vT8#TFjx1!Ss92Fb-*0(Bn59mERI6zbxRV_!eSsM=jQ=)_bQ+^BD zEQ%fs|NOP3k~_^`9uy^Hq(eMH^VJl zI|2({Tg_yCk&wp6zcO`%MOYZMAAG5XdoB2l!@+t3K51KBvj39nS)lPOxzbOfA$BsZ zr@isQ7isL2g&XK#b+p?UZwF8f6rE7|e}JaQ(W;6BZ91p-HrJrM3xUQX5F3jxTId4= zB`5%(jGN$m3AuDY;bMU@2@qJ)ji8_s^UnneKo)+Q`Sn5@Q5U|!x*dB`yP_cM^7J%b z*yVI~LNdnn(&tGXf+UQqD_>+~WSI$uG`=^tQ)Q}_zo*!`0=ZQXQON^_97>Z0PWBL! zy#yQps65+6qRg}LEh@J#6;q^jA$217<^?#uO@sc_3;>m=K`^|Yas~>Xpu|414A1rh znuN-eL7|-%GWn3;>8Y@{_{eW{5hHqEkmttrPm~gWy4zBz!h+?x>#^R}yLTPlyKD6s z!2&;Eu-WLKYrMUzJ65hxV9l%P6)Z2zGc721e*Pi(;M>%sFc~byZd+yVDV92+3<@=0 z@E_oZ&gzESp!gF)LLPoIGu3>C-QN`wVTS2JJPE-giX;T7rN+BK^nbAckkr2esO^t8 zu3z8ULs}|b_}z)Ad5hQ3KYbF|Vr(vD)+{v|RU_}sx#HtKuX3dD9|RpfeAmDv`hx1UthHDEqP!;{b^OrC{D?+;>|j^|jEMy{M>5 z=<%8#Ob#D1jFS2^>S$(UTV#8r`zyIiQu5c(vKwh%%E**{joK`K$&h}k1Gp6kLKc&< z5FpuSKE^}gyvhmyy)Rsr)F9qz2ntLB1nX#~BgKI*N^X#ox1)e@kiQ)6(*+y`KwfgK z7i0xaR@orl=3a=lhD4w)JpbC~KFAfCrQgHV@(Y~t$8 zB5WL-S8$inxAnNFo&tO<>JcC*?Jc!o8S}XgO-qcAnp!}T-vKr4gA!{GFSZDrPq6YY zO!!A^?tT+n99u`O+QFY zfzI!2g$#TgU8pdMB(y}0Ke>NE^E#C$ix@N@v>bh8UE~6v-I>NM4#Z@6WJFhC;5gypvthT$LHtAl7HoyPwJHX^-j_oml~R`50y|}(#Ti7LrFwP*iWTR z3Fa7pUFrfAF_cH1l2Vu)Wh%h?fMbN>vZAu*0F}HAGKUvxSN5#H3lzMVP)SG>4hrf$ zKv=+#*Vdjee*qM%1i)HA))Y3VMqnZUauSE+(FeE~@cAfRHqlYVaxiHXP;UCOLIO(W z4kM#K=v)SXUjQrkF;rn=Y|_K zap?R#gT;m{J8ss3!sq8N-Ir(tjbiM)XRs_LSSZ|XdEjfiylaRg9!E|zy*%|Fd4b$; z?_v@dHw>zukKz3Sigx(16YFnvPGYA_R`+as$+(1!jO93X@ml&urC}Kp&$#4SCnV%T z)+OSlyS<}mIa{a%XiLZpLpf0o&_<{g%^{u4%2wWLU)FKU)Zz&aa38zZ$96f?nVp=?GDk}H&zU_XMhHb4~B*8=OC z!)^p%jjUJRvafKO=?!KMiN8=@=R#gxr7NA%^YihXv|dKUTjF07xd+;qT? z^E5h3K@i(CC)yy=7c-E-MMG4c^Av29N4@J| zp*3$)%hudP!=BLWs9hqW%#)cY9`}xQj+HAmpBcV{eK@h8-8udCZL5fT{KyAMoElS3 z_|fw!j#ExCU=MIv-72ov=6lwpSip-_5QmFo)_fXkhi+*Ys8V`2H48-s0L&)fS^$O4 z#v@aT0f;Od4>)5(eY3MOrz6mS-EEJf5f%|H&{zO~I7-SDWberHGJ&+OUofNw5}!9ubvw83IB=B3leDzleI{%E*!73c_0xqZLA1AL7&SBVLk0I=)O^-P)C8Tx zI(##$Zs)bTapP9QF_E^>!RcewY`vWz@>exmJlq=(43G)migk?O_ealvCGwpd-@f(v z^M%c*+w*KrzjV;7ws(93{l0B__VL**#I#i%XtiXde^1Yv3mMs%WH}fW8*e#SBqeGs zI$%N5*+UAOWPolE%u4M0H>1*bcIbysNqj>) zlrc7HzhS=q$E8l}s@-g1iPhXQfFpeYax%bsW6Y7(*48iJ#ejetEi9yL9b7XS3noTJ zXgZ*)g~A^Kv$g1~c2Wv3PXQGCq~7&)5|pl@0C5C11n`Mbf{6g|{)M7E0&IX+#+B{S zBNX)+cA(6cWzShkWovchabcMX|96>s@Q^vS`ti8*y5C$O*?Rc4**+zY=;}eVgzj2R z?1EpK;)qjqZ~x;${?|onrEnHiYg>~TtI}CjQ{g|rr>_6;-NLj1fe;^?VyUC3Igxd< zuHSnwk^7GA^~)a~OKc8~OZmkt4btLwYsz#52n)V!-R*d_J4ux}82J;<$RwjB_;(Rp z7@=LimnPhtnrY?DU^x)D(DW4?I^C>8NOZTH}I8wdC4c zD>nPV>0rzrV$eB1#%!Yj>twd2;UY$0MgXmW6;7g~V#ZjUNiok>iy9{u=MY&0V*d+?72%Ec2I;ppp7Ye3{qSSy3R0dHj zf{pCD8yqk!I=O#u$+8}iQ+JIRnCJb)a=H(GEM0VMC6dsb(W6iM&ZXz1Z_Sp&>>kX> z64|&MEI8jqbRPKAG{vxF)^6vgxLDEc^m!?!eL{1W%>&b+B7X|aisFyFXz(4Nqnqv6%SlhlJ8}cU4Pk9X;dvqJ95u! z??Uik_1>oDEe|0Qty=By5yV+flybDzC=gHO=#ZUMuog)IjnVA*Yp~$dl>52=4x7Zz zjv!wflJMLcw2A2-Fd6hlmznLj^5-6wUy|b&u@Sw;8}Xp=b&(Y;itF^s;ElrHr=XV~=HNe*Q#!oCS{@ge}UmVMc_CPC^V9)6=Qts+?N z?ww*wmK*U9_Z?}9x>bTOQ9j`IfiNztqC%J`9>_zz2!{a3xU8)>dTQl9k&APlmAxG`Qh)QNA-0{d1N^aQ)Ifdgh?r zuv_Mii}+zGDiBo+g-0}LWT>*~&R#|vrNGA*IKhW6E00|phvftfrhi?Jw%>p8K%*p9 zuEeZ<%4Yk-5LtI7$A78z(oDxx9+CF9q;Kz+%X#LjDoQb8PO zsO64<00rz01X+6szQCma=ve8fIU(O3drxD)QO7v@giYa|TiQ=utjQmF`bT>caY;kw zbg-{jXIFbwTHs9V$T*K{H&=6HELk6sg)moNd_c%CFAK0+001dprZfN;ka||C=@}G` za41Hdstdrm7A2Djp-)ps3@`fq2M>U#wIXH5y#$ph)~I#~95Xr?rm2E^e|F@$avX|h zqBZENPWx{JT-RTe2NFw4*PNq`I_@dMN@=}zhRvn+Qrg9aeTSv$g9b}nAn3Mk@1%Ba z{P2gBaw?_ubr%zJtTP1?yC79sVEGu9SkmnB4Wz@HrAJ;6h4SxYPr<^{-pl%>@}xI( zbZ=1qm6k2XoN}K{VBj2RZkIXyxail?;^Q08ux1zfXo>Irg$suZ7Vc6mHY>ov9!HvF zYiw#fV_+ceO?`}DDy8%w0ix4^4!WVHB@G z!y0D>!FSW6H|bt%>49on*#brS$})*vTXqW*R;C|h6w8HT}w;U|^Mbj^1W)O<8^ zg+s;P@*j0nZ!_#yl~ndry-wfR9*irx&Z6}^MVf|ZhYV+)@<8J|(8o5y)|#LqiAHRF zNG4)silXblf&9y3i&(!YPn4TdV=$#0@LDWij6=be%Vx2Yl^=MjD5*p!1Q{JR9)YWB zcdmLCFt25>q-4thpwivhIeC*xA95Q2<{>w)V8nO#l8E&{Y>M=q96higC&HV)$&@!OKy_>pKFKWSo34QUEkkBI{l2%uf6tS(PwWjpARU_s%^4;luI0A_qh42Fl( z@3EQh+`s?bi~{H=0I*Nx#YaGdU;oA1dy_8~kdLUdT_!ikLVbf4?$}Js>>+0K8)TN+Qs(f=DIaI#?dWZOf=ldyVTR6w>D9^is&b-i5=9h zdtdafcO*NkVVP>~lDZ`%H0&;kyi%7lrJ|xU(>OKbghg&G)V6q_Pod24aWb!cH=Kxe zJ>Kosmsuu2dkK@&EQKO-*j?#N(?l=&%2IMEo z{};l7s|2nuP4FrDghd;O{*Bh!Mezkg7pJmB`jlLXef7!eoadCe41b+d%4MjY-f{$+q z*2)Y|v5J8mj#AeE$Rkf1ryMYP0miny-O6I!B}QcHr*#iZDh)uQ!0g~;Z>0&uDn`~f zfXoi56`-@A5%bzTkmK9Bh=y{&1`HRdQp2(U)XvYJKPP50LW%{XjC*R_-2u5Ho|u>Q zSQ&VBsH`iX*Y=Of2m1TBA*=+zFo$m!ydE6d#w|LPGo8_GvD+zQa0(-U1oklkPsx zaZ+sSf83>o(R_&cU`b>2B5xtLhG z#j(-WJ*8xJWP7-SE0CIE*U8BdbkX##sz#R(;SV~-ltw?l*!1)It+=NSjdwyS?CDA+ zNE9RX`eVH-|WsfYYySZ!(t+sD+~+Q&B;tk&cEQSOu!-LovS*~`CP-lsu~YNOIk%x zT7^wKlq7NJeVyr#SH(Joks!)LEd5%V5L>)}WM+z`me2e#MFe(9kMF?Rk2R|)%ksAs z(GHsCe9UwdCDH@D^R zyQyI?xQJf9MTaqiVu(Q+3*|%uI59Y813{W#=~n*88kn?$1h)uK&*2ONdP^wEf7~zv z)g@rS&1pXRYX>1H2N5P@XaI3$<2OTg{d!#(y&?*$40U{L3Drj>4XGa4&Si{D9h$f78qx-c&>cY;`DXgm<6I64jfUB*9+@(P(JmKtW>PTFy8I@QgX zX{L^tH?7#s*p+P#ua#=3zwPe>l{+Q@3gm~2r_(cA{=rRlhr=72HX1H`;u*?J&tQ>} zl@iYg_c*+GVftpZwSb`+Q->GNs0>qckkZQ6`WiG5yO2+G8t@0*S5$Zmb0;kxK~ZWn@gkCio#i5(T)LyiRA z4ix^Cq7^})!v~7MU=|BxuKhLl@%Gn{p{xg>_((?r#D660M%PfjMGqh5imVR+nl1Qv z5aq>ZR{{FDyK5r{K8`>iFFTr#8j-mTUdx@N0fD4@$}9tnuyOhr6f5B%mFRvqwi}-)!oS>XCmP!>ctani#fVa8jZCtKZEW) z_AW8+ii8Z){`S=epFVxSA$$51d4BO=L++Oc`iI?(VBwm7P;oTgj~k@vjS})=8}h4M>lV-%XNFK6JysY+Fka;b6t2O z*PnwQz>L-Cr}u#1r$ih*&dYbQtKnFA7UuD*bZN}chbOQBAwGTe!Cvua$w+kWVE#WE3S8(H$RPi%e|C5 zGhTu5thmHEJ2jE8Ap5GdCV}<_@y427t*&XU+Z}JOGw1u7hm>Fao<02Nb>q_)$=Ss& z(I5&Lp@VhfKv>G)W7QTQu0L`Or7i#`57bExrSw6DC!ujIEG$ga!J+hOKRTS~P-t>g znH7rE#ziPWHaHKL0l1%F8CFo6=S>`wX=(*t-E*z<8r5Wmwj5Kg-B)~Zk_{(bWnMaY zyLNVQ-;JZD;^wWv$vr*Zu;4(KC)J!|<~xaws+?j&ad|sIBYEPYH~4KCSVQSinI(3HGg2NXE&?sIcu!h%E-KR zTL0Q$%hkMaf*Y7N970kBp_h9 z3J5xfZzh3c8mJmT9TuhO0f|s3ITcqNo}6Sj&!nfD8eP0L)6zYS-+5r||^L z=-?TE$|$d*;sp>BAkstK+in0Jm0>zq9ySCZLI5*vEgMKlu*E{2wlhoPF%(=-nsl_G zl47uxeA=*;Mwe?2p&@gaCn2@6_T_cH<%(#j-Q41-EPKJDJYxCEa_9<68x@%m>+pAH zBsu5Vg29uHU-2WjkFPn`U1A9N{d_*BuYi0A(*kymVHxD>J19dfko&W%hymwTAQ%B@ z!K?ysUe^f;LA^^p6`Ky~lDN3IfCooCDJWKqBm;QdK@mm`Dyvm-<#4yK;-0aW-eENmmu?hkU;o$}e8`dRs68e>~ESFI7s*f$~m zVganytD|~P*6(ilF)H0bm42Z3vtEs33e$8%#=h(&Q2a`;AHg0rVmD!40*+lE69>j` zg_;*IFt!d3EFQ0|5CL9QeYK=%CLt|tNrMIOPvEp$90mMb&`cOKEw&R@1+7CE(5MCi zSA57+B{4)%Di!tIk`qTn;zND}tFDVwn@&ry+!t1se>#jK$rj{ZrsYZD=mrY}?ycrI zm}I26ze1PEsq$HimK3e7em`HLUC;CArf0Kgy*AQ^H6I(@I;UPkTWT*$uzst{35O87 z?tuRT@@Is8?y!;D8I7^KE3ZS9D6^J-vc2H)I+8|M5J_Ngw>vM0SY|LTw(i<3=^hg# z?cqK$alY7*y=ohgXdZ0)idI3YziYE?M$J2*w!4CIAD2?zb?reVQ#xQAB)C0XRGJ`86?q%EZ5s!m)k5oiD1?Y;tBp!>jR(yu$o3LQG+yz#0Og0 z)SHQ2K0~IEU?|dbcRV^iOB_4TANXfv&Ag)YW%fqZ+1?3r1a@$f=TE(({)Y@eO$Vyf zg$ozJLyzv^!+)R_Y|0r$>J`0Txm*VuUX**3>xihm;!R$+b8CkFY?`Gu;SXekz9v&_ zO>31rQ*u=Sa{*Mnf-Zu^tT!(^pE|xgu`A&>=XHJnFXL%#TiJ)xb=GL!lJ4E%nk(f~ zc2CYX@Rg(~BqwF;Z`ky(yg6*8tkt7hOwpcZ77(ou1+n^Tx1RjMaQ_iogr{#rd>!e8 zVPVZCgLLz%Jt`sZ*}tgehAWd(jpi{?)^jm@e*GV{i5hal51#Lk!^#Oyf4@VomM{&_-H9BHVSa zUY7SK{5`%uDYpFP#9hY6N7fZ`X$H)3W zYZDX{Bp2G^$HXA@gv|G2^6Q&n)hEoT4x>KV)te+4%gb@W7_fYqz{*275_yHa=IAO@ z>v%)ik^U*IG?mUi!bt0w7A+8Q7I@r5(V$as-C-@OcifdNDEP6?Z8mg8Q!+GkwuNbd ze@dB!fOy??_WHiSuJf@Bx%b}Q!e*?; zTdZ15Eli;^N_P5_3hWGDa+Pc4bZU1vUIcWOGI8Sc|w$o?9P zq_IY=GkW%)Ck6HQS(#EDmu{;e_@d%(Z`|4Z8s#&jCAwJej_h|_%ZQk<9lUb<)Aiz* z3!QMu=w44r(@L_zQj{7d9_?Yr$rb0_H}B0)2)sOM``0w~3DM9aGz0Z#)cI_S=uUNx zqY}Imf=-(#QxEqB`pQvx2Goa#7gc`PdePX(?|i5?&gT@wi#=e1RWbxJFrzwwf{ z`p)X7)Xk_zF)#wZZE4Gq_vkHCR>!3v`Q$p8?612FV6fM0Q5u_{4V84PFw=iKE^mDp zDSdIw0jnM9x>sr{x8^FCdep9ZIoclEZ9z71%Gdji%hpi8Eyb_;vKj1$QEy&A`H5UU z>PkqPjEmb`IQ#lgA|dmi*Gt{)OY(4$9hD7eiAEmOgxW08L`GD($8!G#FdYk*O11 z+v9rg*AF?+vMc!~%J_qV`%6YB2F_jA)}4*h)2iRBD;)HED#DYBLodu!b9#<%>~pD{ zOJmR(5rgAmlBZtwXX^a^JD7FdeVLxx*uQpednm?cef)~~;{xf%?!VsnG(jWSM>xnd8TIXCuOE{(d>q8WVc`Rj&<|Pm(h@I1tXOm1p1*1 z(yi)-nCLD=hU?8Zh3%!(RMRotpFgukag7tz?15jyJbPeF`>VAM3q|6$?q&XR33$o z6`x=joq&3LYO`K<)ap)>VZZicY3Y#nc{f|gH!f_NX5qmJ_lQmR%HcHp%pQzA*~@|} zrvK-a$hLT(qp)?=&5D{KXhWXDow|;04 z-~EQSQT1t3`z$Cj>tll{)4kaN_lu#;bj$MN7c5=7FMs8e$$I%`_M!f6Xd#EHOw7ki!t?-{vo?!JoZc8Y1zYv>#^$F!MBg|{9cN0lzVZpbh zk0RM}11ThGSL19CNqe~yGD*rc-DA{C{~e!C>0Z~y{! z;8=JA5w9=r;8U2zJ)0#GXq!B0B%5m;A4r3~N19^#SO1 zcyDH4!=_?J_7P!~>?itw_q6)nWArPXpVTmMQLB}@%7dR4EjAC%I?xKfOgg(sv^x9O z%_PjlAaB^rkQ3jfX7&1b)23Ck@PT_p{hEdF-CLYba_B*kyq}kt_bto4f9E;s%aPl> zg{;pP&cN?KL`csAcTSJQ zi0gk?x>SDp%A1W9|E9}7Qt|mx{yH|=*9rBfGpz{QNKe%_-XXM?rJm{ZCI(;Q(l3Sp z?B7pe>hF=zd}?-61|9uX=1ZBS>5}HNpJqy7WYit=v<+6rYaXfDpT9ACZA7O!Hm|U= zIG$<5t|qJ>94H)|oCG<1zsGS}$ZupTd*A#5j(9io7xC^;gl>S(bCbUt-lu&W%!l7` zV74ssHtG78ZBmObP~MsAYNF2<124s-?(AXavOfM0$JqK}Xl*CU+?-RL^%jND z|NRMSSy3he)VKDor)*)*+Pns_hPo_5P*B#)g<<5j*)0y?0*y<2U0=uKdoPY;Bn*>2 zIp8j6KApyPszOrDuctBm^S8ZZ;dSwV{BKYt2{xGj5M?o!8O@L5>W=%F_2$rsDNPAs zi$?8~0&6glcWO~eg^8{l6ESt-lKlb;m&pWr2y*Z0XMr>2|GlvzH!XJ2C@4)lLPpYk z3?>yjtY9R$e5+>H;_CVSMQ&}=pUbv4jX%mWUW`;8)$f{puP(9jbKNV~M<*mzj@Giy zb2$x#O8NZ}3__R3hc?FThU!O_mZ@HUe87PAOzV)2#$QVx2?)t_vwOc5X$LO|zur`x z?2#?NCVeTtVOkZLMM&+G(rw)>s^@OUG{0N@H~jSRIlYJJS-ycf2+fdIG-$cv=Ba99 z2-SaX534z6AXw@DRKrMQZ^q_Ux+O@qe;B2n<9c?tQOYE;XH~$(^{}{EkE&3EnpFg| z$D-xvgY?$`)_i~Ur2qA#;CTN=DlAn8(YbCM!k(Bn*^M5K;ZIl$mqaWdj3@8c@3F6r zN-ou1_-gWXlT9T4%4s#>v05N`K_nhR6plcW32m18 z5?}D_z3_MCm~Bw_-6^)+n6lW5pPtpW3(`%^$CW_N|D{sR0UpQ7fI?i1%-pyud)VhG zJFYz9TGNXeR~|I(6Rk{{^hh4NSUJ}%y}^AOJyFUvI>~byIrQq@L%t93NuuRYARYd4 z_j1(3D^iGY<2Qd_1bnp`jqYZfA#Qt3ouc)$p%)v1;(>vlN>@gi3cKz~d;E5+eSJYC z6e$icvx6(Q-*WQSuGGCkOH9~nx-714aT_;Fq{h|yI6_bjm5aTE7%+F{=3BenGvBS%cQK!ybC5n6}K18`JxF3KwyB+j(0ts;bot4DLEdWEYW&7>FC~`L$oaX8%^Aw z1QM}brj56Vedzfvg!cJCs`wV^`!Xr%6|*P;sR$!e`n1UDn|kZsvn;Hr_HFs z-yeq3?}uvecI^8IccA<49bRCvKZUi&;!j!hZxjFD-R>zYb`3H`|LGN%aB;(%aJv7$ zzEu|=0N0oJ@AZ|T0lJ zf+wO4STUc`gL~HEE3?@CcXT0u|MfgNPsShC8CZeNs6SKrTonM zVW#@_TPpCyq(ZYtNmA)8PQttE7f-yeEiMH28P}P<`)*8-Xq+s}uYOj%k01sQ@d=REw8Ut3GBzC3;JfA{n?kcU}2ogu4MYyF)euKkEI zpT->{ZqEH_Xku)`uUFrmBwpSv>8eq+cS`n_e_j*p)RJajrz$DiG@C?`nnw{JbYJx2 z6Qu#Q_tLbaV^~M8kmxFA+D|2IufHpn_p(8}dfQ@zX-_HhMAW`W{O`cvuD-Pn>tW^$ z>84A*J??F*&jnP5+sv*_`t~7ByGEMXkYvKmx9Ob|y-&E+TJl7No_!z*u9r18AiNz> zEh6U1o!FE5@J+4sBj>mrz5n%F@Hf;6uzE$}65j|mXC7R6{A8Nr#*fgY(B6pV#74__ zbG8$5MjpA1=$T(eMKgMWQ@+>cuf~s7ht_1C($u(~IML!)21sJO?#@|}CqR`Ee}CK_ z+M<#OnvMEj9M?K%+K>xnqh)Vt_kylA;*$ruOS5tZN)2l6QQ4`^(2sn2XF20I)qO*p zM%zgmA%#a-iyiU#A@|w*OfgeQ%pM%CEGL`XH@|9@p5k36)E0Re5@AM@adgz$Q+gg3 zs#akQa)Ez#5IFS+VfF^Yy7l-ho`O&6aZQ8N?el=4SKsWdET%)A4{29jNLQ}4*s1YE z8feeW&*VSw@5AW75%Run=w(A(#6+X^ctw;+<7jJPowc&*-!}m9sq7*zMr`IN!Rd_W zgg)9Mtmyh`FZ{uYO3be{&Ix&S{H1!Gluv!hM60So40w@0yiQfiRs$v;%9s)FU$LLBV{~#aUhUeo z@UQYow4ku&^pxhKbPJ#R_kug|@nK;HE79E2N8u+Y2Bown3XVd>3zwN zj`DeTbJyLGc67Sq^lsR3 zzce1x)`U%{>s@`g=4U-;^Op_UHu>`(WcyT3r_awsn&_7fjSW7p5BM+#XSknig(OYv zxhhXp4=f3u%rjQ-iG?N-eNVIxGpkt<*-&`BNI)HE*XkX`vWG2=DTZv+!( z%5Uh3S5k7ld+ROYL-GYa3&UNlJ@2JSt*j`$p;vx3)z3EE!#k-W(w$>LX15o&A$!tYS(f**@LP?|Zz`%aR9@#5s6Kz&w!S;EnKE}Pjd(8TtqyTeWNK)`VUsgm-wH!1(t>rnbKJ!iMs|YA*a%Kovr!J-xWaJwSsH1ktzqH9ac5pg66(>)3roUsku=;x74+NQXiF{w zE>t+OG*{Q}lQYToZyu2sEp;{p82xE@bYm^cCYlhNZQ~6y#*&(Zhyj6Qg@HiTXGe5A z|7bgQVeQ)NN8FnWOMMn{mEqCuREMC{u^VSA3-`;gdl^MjbO^JW$sNPb>!J6Q!LC5< z3q6aWyCW~w(~#q$+gWaF;v>a-wzzp?f(ni=LrkfHw!Bwco4Doe_cia)g+}?M=bMhG z4t!n_Iv-e`e=I~^d3R1{;92ufTy!4=3!QuTK(xH2a?rgcqb+mE{329KSfi_2l}*xn z;y#aNk<=3|W>?o3zWOtgg)lu|(M+Lxyly7ktSqpM{cNU@$(voHIYGdL?87>>Bzf$9 zARBT|J3<1G=4mXwLF{0Y>8DFkY$n1EFs_hkWD}Cs_tdWxElxB`H_TvwqkK{+3rC?An4rRRe!_lO) z3ie|txJAzXL|4Fd*R0WM?-kCFE3e!I%ZMle03_}Kn9MquzLtlQr%_CPIbb!^tiO2uU08t&>tVNc$17Rh|J zVW|+id6#s_{v$s;(ggA*)r{im`AmJ6s66TG=Z{USb|;G1P87!o&m)bO8Qd>dGBeQ` zhQ5CSDuN>seO)=;=IfS^?~?s)Q~V{iUqaW>;=eqi;Qf?R#z@iq&o8PP?$J+4$6o48 zr*V|c$AiZv`c->eXH&fHe~cwFPUGq=>Mf-x-D znX*e0l5`oF5R&BgRWJFL`6pq_HNK{8(~z*RB5}%9muCXZ!sQEJxfyts<0Ci&72nv7 z8!X9VVeuB>77iepqmuOLx{0U$ydx&!i~@9_9Rmj{-Si?^j%PV95;0B43Et4=TQl66 zdaSh5m~C2U<}&}q@SddgLPv5vn#X}!Hf}qV&R3Or4*;D@BZ+~9mvk2m&7*zV*3#+K zuLoDVaB8%-&hU+fHuzJ5i%&&nyhf9~6axiE9di+kSN9j~ItBy;N}rAd({=6$8m-M_ zBJ7ZH=Pu5l_@b-mFaLfpA#4K!QhYRasg&`A0s3SI#ZaSFjgizYeWG9Eb@v}X4z1?9 zmeZvW{QTPQANTm|7x#Pq%&zu6BY4o>|A3q4Yazpu?V3P&qC&Ani9yM|H~ZT-JlJRs z!E?i%rkN8pXX!D#B?1TDoMGM9VKb?T{DFbi9@1=V7Js!}Z7%JZ*hf60FtgV4^%JCn zQRW(kM@lAlP1E+#yT)}7!#Zeu^QmIUJ$J-4o(pJbgPUV$XkY0Rbzf9RYj9L~;bS8` z&5hi1UXt;JYs97pE>SMR@C`{~<<~FT8)PsDC+9P%p)*(e#?mw1A3JK>UTtk+yv$yV z;3p-qbx$;%SPu@Ce4c1ViNLkI$KO-LA>+43Y;)%rkj4g}jf$NjxX=g{; zOKQzpFAS8|o9kh1Awmtz5_{Jt*4vB-{>Sq~f)_7>`{$fS#3qD$}P zFO2%;X<-odXPrbt>ue)#(&80M`?AEqQo{a4e4~9N9(|3@NGUk=meD%3C(f`NpMo}p zn}#nI;o?(;knv#wnKyLR$af>c|gIiKXOwZtgREJvYQymt7vU`xTp==UiciiJ);N&=~6}ZkS6+|0hZC-OUXhop%I(DZhr(00Tvq+Zy zqlWSudPT-if0*Ws^eg&vF?`>iNqylYbIfVB`Tp~Hj($@M$9(x#`Oa6thdij^h5iT+amCQ;_Y3xw+4fB~zv; zy?G;(Xuf-@%X@2?K-byjumSJP5Xon|AIQD1uadD>*_6M$I?!Sw`>UrJu|Jro93?*S zDLI+rnG9o>2ZczX(P@OSZS0WrzYRc(Ut)_r*ZE=F!(ri4>4zQA!lN~0bi3-z;r;sB zp6XGBeMp^7m@}g`?(##)lWoqy;=B@*y^P=*M&~T(spf&?7}(g@u=@0`&REZ>Ae{Wuhws4vkqq5)OWIJs*{B{z#+dWJd zW=E}Rb{ajqzTSDC)GS;%j?4-5XD>P@N9M@8Kjl;;B+O24ge0fxwB6ls=9DU7g(QbR zc2F?{HK^SW9`fgvM`Y$3yW}i{sh4JT*{C~~iItUwKl&B_iPhd@c@l&oclFr+H%XpE zx~=~d*4*ff&$hqswvyqbUvJ&g$`oEA$LQ!>V%#s*OfRSGStMNGof#g}m9+aU=9t}f zOW8tIp^HA|e&%yel#)&4-8^%E z*5BSz|L*_Huu+shg;gQ=%|V{U-gpVZ#Ja_4=nE;J2=5mRDd6GRDed0KRa;h8QAwPh zChb#OzBNtsy~2Au!_xJ2%h0&=yT2DRnsV#gjqaC1Xx7Ya+66BKH+lG;z#uSm5 zC@d>W3;e3tRnr`mEa^wYU+v#z^>4UKq{1`z_1R8L$o4glcL>*2*Da55s1Mke%P3HZ z%*`*h`&|5cmzu?VnT(~`0gaebCn?Vw_h@AsQH>tKzU;Ofo1{q(&;(OfQFw*zB3r}J zH?f_kwv4TzFQ$x6@4QZ+O4eDK+;XMG@}I9u3OaI~c4adYdKBDxlNZ-T3;ExwaTWn6g(xTCnfWa+tC6#8~xzDe@$MZ@2 z48O#{MBmk%ZlxT@Lz6)Y5a6)7`y{xSB!LqX9S)`sf9bIQG77_K+`ynR@l?je6+AU5 zN}uv}&%!-EKYtUvvU2;LWEL6O-0CcKfq$xtrt9p=dMfAqog?RBRo)HRt6S@|77=Je zBis+unSa13i2efF=DAbX0O#9DAs!O0;Qyz(>x_!>YPVxIMkOYQf>Mm2fPjTjKk14f zBfX3xFoGWu7%7SfMg~FDSdrqOD2Q~V3?-}kpShsgj^5$*r%@65qv+WubrT%iv ztB_MqeHkJupP|4>DAvvK6uH3@=EfFUgsS-Wi7B9XHqYsfcj|Yd^GyDp)>&nkxxKlf zs>;S_sgnEg51ez)caE*|-l3Xb@wl0>^hBV$o7?q^AsH><+TGm))k%ea0B;~Wo6-@x zWc9y-tAFTF!{#vjH>FfYSWK)XspOY0Iof<~qf-KtLZNP~R{MBW`Y>okgy-Zx!X9h9 z6@DF=%4YmOkpJ+zd*1JBB&0-NUeob4JW*J73r~_G_`mR#v!O^N`1!57@c;7^);jFt zPahZ<$cn74s%nBFi<}_c)Kazs`f^`6g`!pe_Wk>emoJ&>5Y%&2D}jFAr-_La?3w*} z7DEgBOLh2Tz&x>TFAo0rJD5HoIc5m_m&&Q}-=z;f`t7^n4nGGbFXn?N0qhm#Nb zi~aWhK#K2LTwI*Nx)7qUyhvaTHH*V!G5dz*US0(Nynuu0E;Jr26+{}Fno{oG)h(H9 zdv9T5lMY0f{MM~>s2jjSgFze))n+wy_3n4?jFt(kCtQ|1qS!s4O6~3Kn~z|xv%H*~ zDUEhHA|j%zw^uH!+2wmT+_uowb<-_H{upaudt!=rma6C}l8`RX8*e&O=ls`;bYrmR9 zX=4^(Ug9bqdSDn!$;e;;THKgyzJA{P`Q)h>Z{iB0qqP7C*=uM>cXCPrD>i7wmP<&a zLo-Tc$+#$hRl@u+acf@ofkJUx4(yc^)Hqr)?fqNwj%I+E0)vz6+27=JRk9KU@DPCo z%10$04kyL7#J8_CF9X1eUW1PHUsfYy_ADU^g`wx;Q-nR-DIiWxNlMbgKIkiffsk`y zgcJs1lQ}R<8^HI|-rj!Y@?}#4gR8Lmo8$CR^TC+-;rxE*Fm?iVTJ9f7^tDN zx`>0`VQX1XJ0w`Jh5K+>pg7R45R_|+2dkR$!kVAS7~q#am)M8WJrHU`@ z+7pNwBnN4J-VarH)$T5$aG!1C(z>dHdon2;fewmS$adO zbPlC7BO6%MG@#SFUno5as>lrxRo2C$#z?V3zh3<852!y~5v*;uYviW+T0ly%L9N}GpuZwOTs72EwWJpG+6|cfA}GC; zKYJD}#lH__#TjBE-@A1^Tc*g&H^Eyrz+$pX#}8GhzL!-|3Ab-fkCyC*q{2~iK?dv>wUf-$j#D2VE`ZmrfuS}Wa(D;H z2xst!LpQ5la%Oyw&&SH`9BFQ23Y3y;;Az17#uc0PTr93);gDrX6dC5A-+*6-8X4p9 z%dV}ty#RxPc!L>Y73$hn=m{br;#7f=rkj{Z(aI|;8;Qw*41lb0!%izOqj8~UhhuNd z`i_4wx1}V)l%B@xI6>hnoO+l8O^w?YtwNF-3X+nN>LWGUoOoEgCDb#A$HqdX&;Rz@ zv&WC)o-?a~yc&IdQ8ERK+5OnDf4d1xAmV~3R&0a=FwSH}14wn-;(mR7J=9+0v2H6P z)vY;Hui-M(U0cKg;Fvkm1^4fB@mIO8GQB#^EEp-BBScN^7u#(28_vjqD9C(S{;QTA z=8xM$;zm{-eP9asgkd^lK#npHM#Jq(7K>5!Y)=i%nOw%X{dWnT<`Q|BN8)NHO^zHn0%M9>8Nfsk>F(=GL9@<8 zV9hn1#JgHS--YVgTc?9j6ps6@=Vd__S#yG7f;B|OL9qqe1;VRW8>|Vx1W|c=2M04j zN$~Xwu*7+D=f03A!I~7KvVuXB6c0877RWSn%fJVD-(?Unq6TDi$?!HdxyMgo-LZRO zE_y&D<#1g*jSc*ztMW}SL1v#E>eOxAj?jyF|3kDIG?8-PjXd)`|HZ7-ev-i`5g+I7 z;c@-;?c0L|P%9yq;KW0z3Srg>8I|LpwYBvIZ|_O{rcl7s5wm-MA1vzdLCSy(LW$K1 z43#+5r>yuICcX1q+3YF{pVN6pJ@fslmDh>ydz+uc1qN#J1h-7Z*X z*(_L-p9nWTez%5(#)=0%5F50!v&#lAfcl5hIem2r{-2>r&pPUU-c3nC7^)?n4sOQskWnMj5)9Su9j|Yyci&LjuP> z$7(BHiI^Z#l0^#_ngF3ELqjq~CLkMfG>B55e2g?dd^kDMXUwuPOnJ|SeW^9z7^GWS zr9kfR$*%Q5qjm19Rz}d*Ds#=3aiiZKu!R0UoMS#TT zzDc(!vVxdGJ%nhbY49vOXh@GhAKMvuN6YX3KG%MF#wS2R-3oC38`78*S+GAtTaHWt zXi=ce7YhOFXKif;HXQ`cja~W z_9g=u`)Pc<2kf(1u6giCB&0)!A{=5LX|Pd!PNeU|;n8<()_~EAsk5_DrP1Nl0C98% zdW}T!5fZ+3?D!Pn)6v-(i#%)oCjOAJYWa(KAD!N)vp@|9=d6}o*9|l_w1u|1wosc} zTe(QuPnriBCn%OX-gyH-+**icL}NyA zem}764Nz-2lw&1B<1vpDB<7(_E2U|$5_9;0?!mz{NGkT_wjK$oWmzE0gm03e6&Dv1 z!KUtkfz*=e!J}dtr}Bv*cK`KPq^IxEqem5OifBh?o zM2?k<$>B&=g~i3wuuNM|K=D18%jHf@Pj6+9uv}l}o00?`v|!*Awx^1D!qsp=0MwG@ z7z9Lk5{wVfsohmoRfV8Vu5Mm{Kc#>Ufx@>#Kal{L7I;7m+6^X?spKSSYirv&je2hy zhRnc{K~la^RrS7d?qE&KxxwPv@#$9<;BnMlZxm7USV&W0`}XZfoc8_t@>rSZB&ZC_t+Epq9ZjsPv!0Od)XQzS=a=`^l(eK9(QS0XiHe>JHv}-@ospV%!{txu7$d zF4ifA97VlJx%KPUV_ke}5lunLc1lls*F3fTJiG#q(x(u@A(%HR)C-k!r;lBz?1iTx zj?pkm;{XU$Yf~+=8cI&jDCZ81jWr=SxCB*HRKU}?J}fT?oYe2^>_qY(d+g0q+JuIh zSLfyRRF57LxZ#L|hl9!hUchFGi z=?sx<@7zJK9SN^onFP$fvV$=2k&z$sK@f6rsd!!R8ts*T@Xb5=iQVOG6fOVm&QABI zb-%3OBE~`+>e|DDHDDP^fC>uA($51LplxmfM`j|lmA$;Z_3JFNOw)_TtRS7rASF4H zrqRD{A5A$u^VzX7xL_sR8F5vB3`_eziAA8m(;A?Lc4{lkk#26Wv9VENFc>>jRk@j& zW+>|+34Fij_-CjS@ALG`fqmzI7;^OeD_c~gTfz+X8W>n;YoCK?dMxDXpF8C^fs7V^ z*#K!%xYg^oZk?>!#7#-rtIi%d_>T=D5%UwNc=ALCG)pDy8IrPtr1gfszkhnkXLg(K z2qh0D)uui?hCi%7{rRILGOB*)ADbfh(`{^yw62362iXblWx;XJ;V#^2WGXW=w~%}f@^jaVKTkLl*M~7E zgv#tlA2-7Z+3yO^DyXRH!luc4>jth)UUejYCuRxKyb%yV&%onE4G#^~f(LCq+7Bd> z4ZOI=o*F8%-x5akojQr!X(aUxRvM^pF3%F=C|1;Sqr6mO(%>KjJ3cs?-F0n`>{FR- zIHNL3({|RZSvRL%5Dy8T?)yH`=7pA3(TSeTkFJI}Ji$aI7LZ4KXM zwET4uZ&>#rl^F+nK(H~rsy`rfdi)&v6B|Drt0*tGFgK5bLb%x>{s}d)f}9B&R%le1 zUeZrRK28EuSDCu+RDMg2^Lp_0UYkV@{&MkJ{Nq!29#6}lBUJ(!&lKQERwAAjx1&h-l3DUZK4zUL3svn z{#s4V5^lQ)j2j%&y@*d}3fv_11$?{ZMIp&1)KraedxTtH6(0a!&jsQ%x3`}}kFop8 zrAsyNbqy)>4a7Q-^rOrUl|XrvHD-O!?mX1u(?QpL{=x6sU zT`B0V^z$+puupKFDtwxpjLHkR*@|gw02#Dsz?6@mjHS$I&qluc^V+qj^wV`~L*bMnL{OIg=zs% z<(HO|c#Gaqo-GghjnPQjH()-Hq2+!|Oh`D~TbB^N?>MJs7EmY$TARg{(OiSik1 z-k3Y&PC`9W$4b9>{6XcHvWu21xdF^GnA_|%8R!=w5B7NKir|;a)0~+)PO>AUABz?* zZb0ps2!F1}L7MaqJa}OS>qyyH`1-;sVF?K(Z*On)@s4va%aGK4{g!Xld^Gz7h$NI$RaH?ww}#%EEZAnFgr$TxpZYB5QiSxd{bN>e%3`5Ur4Sn@&dBKSd$G;ZEHdl^)=_ z3Zp@*1NU&X%G=&abR`unGk34r<`N9UA^p1UZu?ef+tWGdy04F`#n<}nt-dSjo>tf+ zd*Y|{Z@-im&-rCm13DKz5Dmr>C>~f-{RuQdNW>KP|E`4$n-dSuO>&de)PbvRkI}$H zmnchJY2(J5jZQi9sG92Ug0{K5h{n?D9n5=0dUzTbYp^(VbFzorLA}L+n?xeAGKoJ? z6wQMO6BJ)Jw3+VQW41JII#^0U20mkEXc&Nu9b||>$OkqAFEits6QVj5`hHH%fU^3uIq0DZ6FS|N5@W$U4bih~*Hz z`Iif;#l=S<4uFjb!LiJEG;c}Gk_ka*e4uE&Yq;v07T)-B^gT4NbV((N96U~H1q&S} zn3p+-C8$vU77aMHoFA|#<69T+LqAOvO)1iXx`F9NO5NsOq1e}6q^h&yqR-^mVYC_W z|LQL-Tif;iy|HPH3(7SrbNqWJL;P7ep>%BJp#R`2pPyw=gv8`l0S_qN8&j z{TvWK%WT}3;oy~qVvuzC&CEE+^F1KVD6gVo1zNW=e*bv|(&HiB9HN$Hv8V_xHEP zr^g{2ezA6v|0WtslDZuZ-eZf@*NgC5kaV|!7n@1CkFZYH)4N1IB8Z5rLnzm6ZpWPA z8At~L{aI4(HwsqhChG;`-+jFdzvoQPg@`X{6QMPL4z&p?QdD|ie38mI(l(Kjos2vJ zvXKmYsXz)2cb*6d-18SNZovDY{P0*UScT*Z0l)pLE4_U?Ph<>Q4!u~EXf_0wl$4+n z!`p2@%Me~2o_yx+aq@vEI~(4~US2`L!pJBPj`v1L$XY}SG?J3A(QJ{B&`nT&DSP^T zzZ*t{U;d9|5wQM%O7Zouuw=+D;&k$T2Jb4bs7RJ*)k1II2dE5RJc|0~LsZKVau-EK ze1%Eudi{D09s~8Y?50g7$Q&0fT^h>eZg{f5SLW-u9E^o6Q*BTM;t?1pPmWt=knceG z`TKDn$GJPebc0XVH>3*+3(IS3hpu*%xooSbuQx~i_Gh_Z8L?vdPa2C%2il6~$;0Ep p&s@DO_!Iseefa~uu(4kAb*F_nCi!w97z;c&({24pPH*^L}f;b2D$n*DKzi=gj8r z(m$F&#<%!B?9w-^=kjGYEZ#Eo@wVCaJY#7iXanQ?LU1|xwC#;wI&SFDGr{9WXC6~g z)6=!uA>SWwrgl}YfPEL8sqoiLKOUvXq!k_27`|_N=RQ6b2`8E}TT;#E168s|k7v0U z=SGlwV^@NL9q&9}41-@TC;a05AJGb!dg6CG$o!(sy-fSl40B;0S1)fKUmmVQW)EX_ z7BOO6-fFV%?+NS=Pb}R;;n5fz#n+7j#D*EOL;2TN;j2d-4}3bRC(9qVKhbJ-z3erJ zpd?lhe4?8!`}5KaNe>Sq1j^y@bnJC`B;d;VkRCy~#wZn^Q`V`z)dDY-$LH`fI{IW*lP|=} zrT6T4z-M}y6vPAkgF*1{yeU++aN>p(hg^(BbHO}p_^N+=Akv-Xj1i?H^mK#KAf5#r zTiE{E#2-E5N6FkHUxs-;C&wiH#nv>9zOy^~wQYd!LO+chB2Ph9lJvRd$U1>OQSMdE zdhX9Kt?XpWUS`&qKzvfvcRiV31795G)QS#tY$_}7cy(-MoarhX7rgNW?jWHL47^V( z?*%1XLtu~w@$`haS$E}BEpp8lmM!v3l?7!r49w@}H4H@ysGz9ot>%mMhmajYFm>HG z%oo?)H+Pk6sR?-=zpEdbzZ`R<;jxjb_)) zy$Z1&O05%L-$hsax?F3;^=bWM@(*L3OJ$CsDy+FE1%2{BS%$p4e=hdDw=A%PPZ5wBLANosa2H zYe%N7{xVAoBS>^g-lE~<)rIb)TvIRWzZFso|0GlTTon1Z)C8FhW!i)ZXA{#K7Rc;# zew$Vo<;i=|(Vqzo{h+b`o;UPxDWz;~Jv){PzT=>OM4tsg%V02CT%Xa{nU)7{_gz3F zi|$rg3K=a+`6_b4o~Ko0!+5xg`di(dn!LzJ;UtpUH_6($0urpFU6TwWEfm|cbPH=t zW7vsHttfFb>2)W{+fKKn@@AJ|RJ8GeUvZTbiuJ0~sue_hyI7PRgh{{J+OjnmmQ}5t zB)&J&z9vR0?{NKPO!SXUT@)s;-7A9{q4lk=>*mWhW-Hz$jjU0}PaXXulQE8Zj2jJ) zcdM0lfCVGp3v11(^OIDpbtW|?Mg1vm2fbxUcecWrzSR2E)x}k(VQNA0I1#pv*+wX> zK5no1U^EgO8r{3h9{t4MhH1Eg&FkgJtQTGO4Mc`?Pr`dj)R?J#&yo#}?k)Sv@(4C) z4;K4x*Xyz{HUm6(h`7NQ`urX1t z$gzB7=gEb4b-sM1V=*Ax3>gR2YXiQr@o%&vH42$!Rasrv*Uh`I0p0o zvguS!AoErExs+%|2u*&~9(7+#n_sDE9vPx%Rr0zXnUI2mnUv+r7-2J#{12$WNS@8d zn=HqBfnioC0j5VyxC_i5C57%Li4>}G)@Y9Gpd-s)-D#9KQ9rV2>Nu>A)9V^*(kd~j zjLkfuK!lj!+Ecr!wDSQ!GW6Dj>9BE*m^}$nsK#yU@<-qV7&I6N3v+(P!HcHH(4lKU z3?lb`5!IFyr)fKPVPnPb;CyL`3`ee94R<@MdFl0tZW3o{>gX>2R!_oxeM5~msk%=a z_E*u$quKeYba^x~|J*WYn7+gt#HNbxe=2A~gE{T6XUu@on0t1i3J;f?q~NcNo14ts(|#!dROjjM$7dVcsn$kM1(0VE?-I6@~GC8aE{za~W)a`Y#Zr?NXV(}=BH z;zT%hC6%)ZL4<=n`khtR)F6 zxNs48`m#mc5bvt$JR)7V)D(E=(jv)0rkHW&oL>)t7^YkD&wTGW zb!JsQ>Gli)?tCaZrgV`y#h;_JWoda49P^9_j;*C?|K-rn98=1%(mc&;ftm`}r9btX z8&ZYydN|Dz5t@b!dn6=Lq2!=r13e;94t)yO!3+MTX6ljOFs#IQL!lehH~-`nnWOm> zm7%d=W-N+L>FP;3VVn`e?w2P>Q+xL0uUc?iJmCwkjQaJh0FYtS? zkonZq2b?_MH(R(XKhkwXb&0{Ez{<@#V`z3&@kwgn!8>okNxv;EkZ`!D;0{79lTI|m zHF%NqR8EAL&?hY1@+C7B=1cNJ2vXsTf1infm_x_zN#=v<>z^A4iWBDXLPfT^fE(`H z>9tO7*n?nhM7I#lK|{x$e8TetJe$euX$bmi`ExRw?+!sEvzZx~T-Fk?)8$clF%-LH zDyU^--SjkVyU@j1bap+s|AK4xmXj4JumR+r0QnP)gp93weTyXgH5UUeR&IBMp=^N% zDT)&LF!8Xz6+e1Dl96<;&;(|QtzJBZ^u(jEOKY|qeGv5aDL5MhOQ6$A*57tnR*m+t3{0VRPwXZq3lvIfo=4Oxr-St}m;tNSD zKgr#zttsHcSc7?>kVIC)W4_TsdIk=ct|-9lX8pwo#LHgh#|}M=l3uBZnOBp7$%nV& zbT-v4irP+)Tk$pR`9cj7sAPjdLNXu`9LrxVA@Q4bm=o)TEQ7scS@a9+pJj-5FW|LKhm<{1Q#AKXOk}Y8$#s!?uF1l1lcT{tnx)KY14O3A*styb#>jVlc8Johs z7@Kr9HFOz_T5MXgO5<#QS$k;`&@z5X_mcg~m9CqxZdoV6Goo_?uk-4pm!!-UD7WO$0nAI3+bf<~(bzAayw z{=oQmHqO&Bl}V#;}LP4}RV z%Jk+FJ4s8yiodVEIV!J;gQkW9n{NBOT-U-5a+W%=+TpN_SgrmTxg)OzJTF%v`@CufWDEc zdCzOB@eI9BRQQ~8^oQNw5Y{6U>@c-x+aHYBnXqVzpOZKaX%M7HCgSx&{Tg>6!(d7B z`<2QnjOCkMx7!Rfd8U(QhhrEI!~ell1UfSR$^Zjv<2S*iI(0_O{9GRYFc`zYcCAq8 zqzRRlGT>`b+iIFq?^G@D30tTf#yb$w9=UB0&)F7Qldt=f1}k*=_l>Fh?|CZj3Evtq zc0z0jTomcxMJjle$ft;w z`iB|Nolgsw?g*U@YYV05@?jl=d8g~+N#S&0>iIP@e&!^wO}usY{(z+w+p!|#)KK+* zEGVbVpEVA~m^1$h`Pus$g&RCNhq5WHcVy8CblxgK4lT558vEP18 zKE|68@eM^e-U8cfG>lqhNr7*$u6hF2ti?pu-We%IVqKV*4m>)HqLI#%IvS~D|LXu! zu&{G)+1Ag3lslP+svhmxKNnbYiJbEycQoDuUFRl)g{tjaY-J8)#w-X=txir> z>`qe*8;}tH`NFjxa*rx!-q3h~(AW|_!1k4D>_}tvvM{q6XXV$qN4(W9>4OkC0*~EK zrk2lH?1J@QiqwleJMiD*JU|O7&#Sma5zw8DLXdUUX!vUIqy0OWyUUQM>d_FzuC0}! zT9=UBVHK@dM8dge6Bfx6T*bB#zTRs))Pg;&vv-v{dN^1vYv37;VdPChk2JyOzmmeA zzDVs3n$dgD3}jnBLX2+8p7uJX@l-v#&%bm2cs^#8wod0i^q0`VBzV;3bN$;a|yzpZzuw26|W)B4_Bvb zVQrc-H0Y>imV<@rmcrmFFpWJqX9|r6I)T#6!@Q zSGMxq?zJ0^dWqTaHOrI|QX(LRdVOgG8zx|0vg_)7Kbw7>huRdxV7MGpJ=46`)9%%w zoE?#fU$F7O=o3Ptmv>~&d*4*Nf9)1}E>wMU|vQMgP~z z02&zCeu)B7eP0L$3{{Krv7pK$xXnrxu*Jj)8sNoCQEk3y5Xv#W22&wPM@1KG={Q}O z*8bbtsVEOACxP`3YV(P2^9WR8V4bkRhhbmm#HcMzm#K~l z(scd#2?93X&?1$ETKa1}f#Lndus(*4>|ujo1r z`no59M}!buKl6-Z_HeX5vQ!e`&|p@0nqG-ejT}q_xRvu!bH5-LqHVwgRB5Zo<0MpezKXtJ&)>(EijR z>FIH?o1-+ZfkEdXE`Qe_QB)na2)bu`DrW!Vf#6!@)iHnn^$A4rtNa1U$q6>*fX1g| zpp7rn=lNc)ql;MB-Z|O(ty>A`FhQHhN{Rtz;CK{m3jj`VPEy(~AP@q^#~TcknT-S7 zgmIOY7l-+afQpTZC^J9j1p<+Pq{W2QJXcQEy?oW?U*9hm=`%7Y*p^2WIHh{2hLORs zlt05p*}iI2sMo6>D{R{~G(<2oM$H@A>+3+J`76^p&;-N6sw_i6LWZJZpeH5xO_|+o z5(lY`swj~loFDG8#E-AF+~@iT9Zv3zzplAdZEuGYBa_TPYgFop8yFBB9UZ|BdN^^r z7f8lyFpG&POjl^vVL~2#x0uWxDN`?>6MP^#ot-X_WHTK^gc21K6PtTeeO4@7XQP9h zN&Wr<6%7rIr{e}f9r#4-R0xfS3kM4vxc9#!F-{zg=zkZ$IT2an|Nm=ikAv}yzTJ4C z$s|fy1@DY_p||wM>%*qbw_W1*;rG|gciMC^GBW2$pSQjJOJ_6*yc;ae!bYSJyC8u2zSzM;fIG#I^)R=0C?lN#h)|xi9wzPC~ z5JrcSIn*6`%F1X^P*9cCk}){Ko1K1GO28L+N(3IZLe|_C_2=g2FAIoYVM}I5=6>y}V8&r}+M?^$qlLIoe4*0&6=)PZG-ARTDn~;B-Okd{PGjv=?@|+5~YiN>_ccm#p~P`_{%{ zDtBU5QD|b(FkroPBNm_QYED)0awnSU3b2K%huwHpef`Q&K$D5cl|Oz20#XRe74Z4( zcC2CG|7hN5zbfJG&dJn%0nWj}0eX2o4=9n0C*meRW^CR9U#QfD>9)-C3+pj5`ZxCr zkywx*ysxKFI@yUgXU*#{#}|;WnwnZdMh0A9kI~kOZS{WV^O@<@-U#U9qspw6Q{{U*uc=k3F&K-#`1Dj$B%Aizc99Vp2~SKz16#Mr!F+cxR?qixKul87lr^Jy zKUFub#h`joRzU&T@A+=v)cr$#Ab11>?OGG4>FH_Ldyp0vEpvT`oKW~m^ z!%+ku0s)cdXxCY=Sp6X(BPZ8xuu(s5A4_G}J#E@7_Bh|b#KK~6SmOrt=k;R#sNWC~ukuUPZT#i&gq?NJ#s@ zmiE^@Hj6B$azShU&!_y4d&zcd&51un!>=Z|Hc_##zD-#4nXx8*|324xmXLr7XoCeW zmj8O3jh&P8YRNSI>uxL;t8p)6tK0D)U3GhJQJO*7e|$3JZc{PfNwuo;$p#$*1NdP@ z5Dg=vpoNda^}$5ttUV`wG&TbnEp22}6nt<<$mOH&_taFArd2H8M9zH3_&!n3zg{ys8a4Xz1xFI5`_{DZ00MLUa##vbUt=<)KJ;dGSD9 zn*nRA;V8s$(^mXDkbT`j5MaZ@!z7Q9g8;8AEi2yDKB}H6a9jjcUa;FbP$P8Fe^ST45LW52)FMe%pP4#n= zX0-vx_o4@;La!yMy`5h@3|N9IytTFUn&17p-9~!`U|P=aulFth!X#&9joCM?hpjst z7H2tt8;yRaZNKP6;J;fkT{?BIYQGwNZ}o3mSCE&NKmJ4Xegq&CB{z4vB(dN3PlmpU zs}5~QKN{o!d7<$f$+H;%oZxN+h6ZisXHnn zvUy}Kq}rT3JsT@3D#(j1Ei882+eW6Q4u6j^lJoIp0TBEfP#GZq8Qz%TAHpFuI+gT> zoiE=zLl<7$*HgWVdPPNQNA zh$Z$NR)--df=YkHR}%g&qo6^Y!3I(asP4bh1*>-W?x!mQT${dqKm?F`>=qYm+9pXv@gJ8~R>C zIksOy2Ymqn=*F?AH+z=M_W?QoIh-A4we5IH2#I_)4zIWGpW)!)Rg^xk`#(qFx@xc_ zBy)ybx*Qdh$p7vF$PQT`Lh`@g0M0YDG(F`1@9Uobuh;2(SA#yU2EP7G{#~B}x&!`h z_nqJGB0OB|_MKmE55;eu_Yq$}7_sB9;K}2#n6PIsoAjD78?)oF;K?zZd(9BZhRu3R z8jTU)HEN~;JvO|;pPsy-cKCD}Y*KXNKgk|EGQ7={pbCQKe1rfCs6cq*nnN1O`{15j46w5ZDvSqdWBX< zaBXHK&K&8#?>GPEWu>FeNd*M-g;5h-X13o6WiGPu@-}5V%2UG*@cw0U%(dBASykD; z>K;}UZ>S>#GSDeVl@Ln>)5f&R)c1Uy++Kau-T9Hc1Lh~0&}LrA&ck5KU?BHJMtLhAv8_J zt{##NH>w1j#ARm|StVxZki>3nD(qP(S>|<~>r1+G7EopRxM- z56W#S#pHIOLMdeoYB`~<5)DfnBs%#F3y%E5>-%ee@3Pbxh@m4yj%u9h81C@;Q5Rjn z!I3Qmi4s%e@XwxumHZun!b_+Qq1FUm>W8m(=J8r$ncogDNN2Z_$sFq>@z%ysn4G|g zg}RgS`GX)-n0n2A?+DDXJ@%iL*UfgbX6bmtK-F1wcKQL0s7jcAuO%b`6z9J?YpwbikS-285lIXnIna z$wYQ*(m%2W$y_xM_}iCo#NrVv(j_ZW?qRSVeVzMZ7n-Blzcz(swJ}s45L5*jPP**d zq|;)dVy3FSlE5b3qBD!(?=%mTv~v31MhVsgKTY3x=8Nn^G*TxL`4IhFfL#;3S3WII zmOiVOT=;=nAxtW^vU`NLUS}Qv4wjwE`!8qyJJ-TE}kV+3R008N9y*i7c4>?#T=f3j+`POZRL^dci(j$Tv*oSk5_|4 zy~6E-9=i`-X(=69weKejRaE7lwPLHg5wHs*us|%ZPSm{Qcpi0603OR2pIkWXYSPzw z6>>rc*BDBeGX6NVnDg7soEg;wj=CRRLC;g?_=d`ZkR!I}WI%U1$RCYBwZxH93qPpa1BqXuvAx!7S(b9+AN9>;EbC4En0v zc}cgi!%fetjX@*`C=8DZqinC1)nA|tu^h=*3lVT@{r)C0Ln2bWfC>Hi8m?_iXH3cx z`mH}gdTtiBJEY)GAua088w8X+A9`zwj{l#_>5F9i7u8p^nar~ zhQ$U1{iBgsYpB&R)sz!@n$4J`kBw>Q=qtGIVc}#G*1@OW4!6A7@{_6toS&&O+lpU< zh5KL{q#rFa`>?-}3r3w?zS900F~7|fuXyn${p5--yScZ`%MC~cI0{9%jZt#{6+3s* z>-F`lyi!QIl5-TpH2$br*qb~`sG|-)&GG9r-M<@!Zd zd-zYZw_MXO(3(#g9$pNtap{a{KlKc?zoeyoZP71zG!tW|ofbGkPZd*kBhp1!R9aW7 zD$oM92Qk91IZ|$GS=V5MBsx39`uX`Y*-2#ONY1SBNN>E?Wkwem^HDDyEd%ZDLAj%` zS+z3#%b^HWTsmxbz6bW#Whjild8~o5;c>g`T$>O-%JP#AbG>ts@*F{1X zKVo|Hxb7r5YswnE$XI&W|8sQK# z+?iw$DY~5A6s5T!DDCj5Kv?>p+->HJkgaDI*=(8BfBi<5c<;l|w zIVT&-pqMOITGG3ORQroZ?dN6Qe3N`DJ3F)6t9h*o?65dIkp#*J4!XsyO9C%b zOB4ztS=Z#sXGpvjCbTs>O%LRyabCU-*!J%*#OK+H8hQZ|7KV`nJKW^=^DTeF3tEgv zkwEP?3!9OVv0y)bb_OlS3yNDz(T~cGc|CL*ntCifZf4BF!69u=TeDf&*zua^1ID!W zw#(Tg#-ueHS%Xc zn2E>Il+2ez0qYH*Q3#@t*5U8Ve@}g=0M0HrmHTB%d^iH0UJrm*D2&s z4O4wSPKhFC!KRS~6^QCX1C97)?2n`7>r{%Eg!r~|%ft4*5XBr(RCx<--Lf1B>W^QS z!*u%BF890FkAG*oxQ^CmfQW7P;!FN~4R2*bO8j=kF=6aoY^{Gwk2hbtqJGr%z{c8K#DWivPW_$fI;qHuVT2Eq);1d3 zsAEUW$XGwagQDj}Hahv8-4Bg`;w3|VNblexf$&(<(dhLbQst~|nXOZsjzT_xfu)Sj zXIkrDl9he??%Vf|k+G*UybO$jaW8(4bBl}b&qDz!BFEQr4!>|x@oC1H`ggC4m~o`e zQ~eiA<_B_vC+sZmdl<}IkEBIB%i`>S#LeAAwx{di=J>vu=J~Toh$$fP#^pxtUP3do zM!itL_8wi2O4^?XeHc2DM1$j7n#)a<4Dw_QRBfpS1-8CJoisN;< znQVW7^YJ(>dQW&m#N$j*6f%%L+gK~W7V7B=rl2hnEzn@+^>9wh?u^)2>m6eyl zBA^sF1(1Gwgvu6rcp)Ec(y73Sl^7j;^K;DlJ);5=IsG}bCRjco<7>h%{*1D9>j@W+ zDCE3R*KHi#i*9NjV2(_bm-W3=j&L1VpS_*^nF{Bp3X2ynE)!;*OPCkSF0b24&Yb0& zb6cNAhm}#?>dC_m!}YPL^Jm<6{tMj=pW}{#)c82-7Vd-FZ`CYLf4{U7F*R^BgszC{ zo~Jy>D=?1GN>}K1#Br1_I9(HR5i57D8&l5_jaCu1>6VQQ-~NhDxB{*;ijTYO*N$xSpES*yD+UClMzm#< z)NGBEEiR2vPz{KQsd-uP=Qw>mghU9P^@ZQ%kGrf0N6EK@t|+8!yy1aH-R--M;$$uX zcE>%MJD!< zIeHcbuk?2z2Ru-X$R|3K)e zc%iYRZ^SN(isuLUZ>BWEbXz-@pG;Y^JRRayM6tmt^iRES&jT;m5$C!k{s;c#vvPp*{3(x)m82IS!jYqCtF`ye%i13Ci~G za;82bW+L^sVFby9b-pY|=g#dhdBdb7j>NGlyiMhfM-d`a_32S1bnw7vJbnbCZ_h}^Rk?IpK$8A zcevXoy{YG*mNyk*VKY_UTq(UTVYA=uD4)v_`X^aE5xXq=zPI+*m$RPDuW#Mgk0Vnn zlJOZvvNZYx(tDaGMV2N3emEa80#a!CjLHKe-it>VlU>u*0nRn=d;3#HPGKs1ETkg# z)_*JJ>$n6AT)rEIE%y~^r!^9&=JE4fff2*nO7lt*9p%OPukTtN9@F=$(1>$9=d+BB#x8FM?w_)hbSd6f?$HcS43`;?C)3s8 zx`h@5{8kn+&{IafEvFri$^B<-9k0-8u)IxF9wEUO#5UO}CAVS)fc0o~l!xJ2nwP9K zmHtVMhWeMS4m|mnhsN$zE3fOh)#LeO5$Ou@0=9}$N`cI$|ASfU@Nq`Pq4yx(`^T0C zzqf@&?DB6xqA-8jHY2MA^_#p2wL5-C#6?<+^irDLj_2!YG%2XI5E-(KB;o>PTGQC+ z*s3z(7aP}wWrk)XZ^X!m>|?Uv0>#z)*Q1B`%aDr5OjN+TvMr`tLxT}B2sICNYU->b_SoNf9WKqsV&UBs2#&-5GDaYp z5eWJ}8Hw%Pur6|H zVjQ~|b87S5#OYlY&_%>X4*;W%Hm@RArH(%3e=@`g4$Qx8ODi#m(r}bsi z8Du0|fZm?9+NNIL6Ht93!1n|uo_+1eSh_D+sx$_L>hy9e<;W6ykoTniLGGw_Wb}&O z@blSrZ_{qH!tH8(CWS^Mbm~Pgad%i90dfsK^L4)U*zfbiB(!Au#E^j8?JJ4}{>KFX zF0EY#`y*U!_@--Usgffra+|CbM zHR$_zzod6uUqxGI7?LIQ(I55GnCkxP)_2P$wanZ9;3%l5Yb+NHqTr(+mfv5px0gRL zm)+BRlxrXZ-zV|TmmOJum(A+s)~|G+=ev{LFt}vg*#N|Nfd?GH>gvA1?X2JSH*y4W z^&QcIu>W=LgBWQvYc%?Mm+dV!qCZ^jk4tuN3F9&)`T7G#+ z0D*_CIU5(<sfd`dsI(?M=In_7eGUQG<8S9x z83V%yUY9rC@TlMLXX)NBhbX*xo9|xOui-Z^M$>J?m%Z(WUiY&ekDl8z3(@wxnKLUQ z&SM_TH2Wfcu>Y~ILVac!m~Tmh0fIc{tJ0BY--<$z=kI!igsl7=ShH|gO<-AS^_z`u zptOSNapWcV4VZ8coArrA;-+hhblssfvXBBF_B_`ZJ;I|yRuA(_snY7x4MJgTJvjl8 zZA8Vw8^d~aFuBxpWchsjStLFg*5;f_F+FD5s{i;J9SyffwCf#9;OWL_CB_gP9WQv9 zK&-9~*F_2S_7Did6vBifCaNzQ9xYl>9yjqg)>1m8UMS(Q2*&sy z6`cm-k_-|lCYJ>Dj#f*@{fnDlyBv%b@0)fw>(%AZUYtqubrdRkUQ@@Odsx6_sR3 z6*Fks=?vcAfbp*cp{)-ZbHH35EuOQGxFJR+uJaD~3wSP8KP-1Nu^dSz1F4}Nuj|^^ zLk_$cLU*C)a+l@ou3%E!H0HAB2jmW>|C;e*deRjqNKAWb1psiUkfm4nwdnD=}2JKrI2-Rm-g~Q zdsXrOvwi=oxGXHR5E2m@Vho#MxBCskb1iq_etn_}xhsAZUa+8$DsOsOlZE>fM&|6l z0%>!ZW16?}ArPHm0!AB&x{WzHmg3FfgJfQ*A04(TJOlM&D`7?(ur`=J)vxZV_coE-Q5LmN$e+Z&Haphjz ze^VjZ15s_R-3pCrkCE=0JuV5s`D>^GmA-%nDtdEBvV;xl`K zAfQn|BrH6a5%+_Nc$*G%mDB2?UVbd7Bpkfap%+zz-kv;wN4N+ljP$C%mef?A&}p1K z1_Ji*H-kBS>EgS4OGn=M)8g07ww>0o7T_H}%h>jfwyU|QsFK6A8|_@+`fB#H(SOti zVM)I|GLW>pv?B6GktpsL#0Hzxf1G)e@BpI&7Yk2T&59nz7J;U8azH5{Fyaq4S#TST zv;B_+Z3T5x+MvL^hYQRkayDjM*BxOXM<72U`sjN5E$KY)*t(?Ews}HW>pvyn&8qfT zLqMe%ChImrPs@y@1oOFMT7r$?0A~{Xl4++v4`hcjSE&yP~RP zITHy|#1~8DdV>qFez28JYD*itA%DX%#2_M=NVtjSVX|iCtdsBgPhpjay!-t(WbGY= z$*J@l*P@b2TVC*JH5@P~K!~Io#|v6EQx{W&sGbtfDGzHcmRakxAQNp(z+FtU^2rV} z!2tTQW=|Bz#fm#dQDxUlI?Z7mK0+iw^W9kvJ966^QkMXJ#(K+jQB^N%Dk!Rhz13DK z{%qhukShsmQBt%v^8d_4D*Ps=HHg~|4S1Oi+!o|-lN7mq^Huc-B&ov+X9xxop`HUJ z@q0|}j#ze1P1Q}kkfGI>b!=%BGrX_HBY0r|U1*OW0TZZL%y==LH-^uW80?sIrlRt1 zLv_fdU==AD$zq2Sw4nZBs&S<#>m(~mpZeovmP^Ns8#z6R-^de{887`8$NQc)c6|qy zb|Y(tAe5$+WXyMkWy)MGpV~upP9b&s;2OBuzpn;3d1YC-F7CR{&-}INHe*LaLl?Jk z#b)_=*_x#Gv6clkV~_v_G^nP;mCr}Esg}o)2biQV#);+kB}LX!qgVZ0i&I)vlNJYN zA-Ce+7e8T`H74PujFgVUnGM|z*l0Mq{6{@U{0hghdL}1d`Kv`63R{@ycNKjeG z1Gr$tfsvgssaA+c4b(Ryw(u_{#Lo0z>Y5@g6fqd5es&p9Q-#2VGh~p|m49QUF7LG(IOrJCvFcXZtTMT4zknMTLZ%P)IIG$4NnS z@4Eq0HCaCwB>4$9HIDCpPON(^kb5lPdTa#0Kd``fEcrZo`Y~p9DCp%<>1|MDuFJFg zpqv-vD3#}=|M5I&bUM+9E%^Z55-MKyxW9k6!wU5w>u!=gkAeg{RJ)!biwZ9V?wrlE3JQP}t^X{FfNCMV@%W9IP%z&HZfJw;f_pMk`{ zX`{KI|E!$s5b}EY^RNwaakM}>V|bVgUqxd}=FsyY4#Q>a)TLW+LQ)R zW+GQ2ID`OFSBH@w4jGI#)-$_$m3i610*wu#z^kw5ENp zWZ+Z+Ttr$pLSQGy4*%iKKfQE4p2-T0z)T{WsmZYC1^vg`_p%obGQyp7DYhGj$%`K$ z`~f{=6Hzl(W26m5j;+Rwt$*p5`UXt+cU{1Y*fUvhq+*$(iAzRvlwsA%Zu;7<6|Jj1qMSjB=*B5wOdZyPTT~AMMbnEWJAX6I7fJi z!iy0x+D$Tv7b?N1T&G9%u_y71XxGQ7QKQbdQIsqlGQ#2|ZHM9kXIJ zWld+nmB&G{7?)t9O2#edaV>p402od?w?3CJ?GG=4zF7&%hyfjXT|BIT zAYs0t+aTHc_46b-X^{g+NC9XGRu@yFu5uQIhnjE-pvD43v*PCF^ua+1s6wRWQ+IT9 zbSXJGvzx!u@KP`u`ug&wrsNJy_-SKq{hOxpd<*>Ht1;NoQ04R9y?yxe&Dh0rO4N(p>t`JWMgrcTEdD;n<%0Ysm6;*fXEW|jLH*E!0i+$pT(J&oGhxQ_QClA zNShTJ>)CA#^NRo=>&eN>BdM#an^{<}dR`bMB`0GMBqm$mWCX`G8}3}PH~&MqEwvsz zyx+P6gre`+?!fO4FilXJ7QcNkO|G~2Tv=j9tOo4>A_=o8r*=(xFf6MMbH+F%Zl%_Q zhTI?tuok-mRFO*eU^(G3;J-FG?UuR`nA*GZ#iNHuN68o%VnahA0h$qJHm91N-uS^p z*2vfxIW={7BnGwfVU7o@>t7|P5~TTs1r=pwVPM{gg@r}!>;KTO?l9!gl;_HNpmk2@ zz?Lg#@>gpXAU*=@Lx5qInVybgVq&83&&$)Z`LjMC;FW_Wf5{Ec=wId!oPf*q9JyYN zQ0FBiC-;>q7XYlc82^ff-DGIPfL9L3j$7=EjEt9ya3KnAZml3R9;6eE@G~r$D+WMR za(RL|9~8_#q9`mb2XZQ^s#xjnRscDdUavU;pe81bF}B4l*I8mu*t;zZN z^3&4N78VvJWM+EzZvre25fKsB3m{w$TbHm5h=~Q}=aX&t-Rpbb{u_Wm;SU@!Q&C!} zy|{1+Lna&rIAvN5Hdp{-lXX$g1t~Hz5*|p%vN^Lj?RNkg+|Ix9YAPWi!w#?2mbp2# zvyOWMhptz5BA*i$z_WXV-Y!u93T@$*FN~L$*U5TYnt;z8Kr-A|khHd@1t{Z^6f6KQ zdh>~&l=NoPGbQbR-I z_=EpeQ9(a5JL^^h1pi?V$2J;BGUqBfM#c{&;^B-elX-U_7~n!C0AKfECpt1FX0Kt< zU>8_6K;)DT0x3FSU;}OBw|F#m zt>qLE!0bL+tR{Yax-D?r?5v#Pb58o`w@eaIdW!93AGq=Y_V(rlgdBs-SDxW!(5*@`_)Dkqi#?b3h`u( zaUTw+9nN~In<^?$+U(KDTtp1>oF*#@{sj1uGH0&f5YUJ}T3a&}1s_ADlc@k0CA-Rz z2Mib>mg|hpmO7UStGF}Q5SZke0smH<7oLboaI8^Wina>G~n!0o$C;p;o;%G=!Sropl0#Du>#okxX1+DU!0wPgMWm0JAkWAZ_u6& z!~&>-keql0Ks{BC|EJy|zgE4pT= z?|CwqfV3S(3$D~p_m39pJFgeE*Nq71y6>yD1(Umuhqb_+oNFVsoCo!LT0uc5@061- zoJ}3KZ3&2w6>t+?7U+QtTkSRrKsY=lAE_sO>ad`YZ^XTq4P5q?MHLi+QSVVxPj^Cm z<^E;Fz-=->dxury*UEtzESOxp;9bz>PgL686>{MQn}Qo?&gEhr20?7f*-@PFxyCm0 zQ;L#~pFbK@-mq?Ch5GG>8b%ftY_Q}Rg@xOJ7OrrZqd`4N>3PNh?+{2K^bN%Of2{bv z3OaLwHuM<=koK`?;WJR7DSLPbD=8^~pp=C;PR_}R5B@-+0TqkF7-Y|mo*r5r9@WNW z0|=s>U0tt-vQ^1FbRmczb?aUbe!FtEu@3ya^|3`9`3Peq+|&_}!HfS~0jJ&F;Fhoo>w! zT$$*ltdn3 zI7Tjvk{x! zUf#iCBSnwH>gmEay(AWO$BSVa5VMXI|NQxbY>ln@OJPU21u~YWw-g0ML0X=bl_hv_ zG*`1ftU2L%d5-KuM1HD!zN(f%_z8R*s1H2OoGy;qMdGcd<{}&+F_v#O52QT>OM&6p z(Ke{|Ib9FTV-*-ibX<|t%y7H>bgMpLbo3<|Uc1bel)3r+!wFk_NC*p%>kS~v($dmC zfTRuWpgjo)h69~n!K%bh1Xw6x0H1CJ{vRd?t8n~a2Y&&fH~c^r4pLk*y;Ho?A8ce{ z!2B>;mKw4H-VAciP0$(3FvZ0s_f1d>*b;Htb+^@0_Qr=+L5NNE}48}48I-ckI zh@I!hj~~wiT4&$l;^NW?2%PxsKIG;mE3OF*4ITc}0T+4%4xX&<-wognYFW4525In{lo&WN*0=`Czjqo8a&;rCjAPpv^+cRB+qK)%& zL9$5ahQr!oXWZ8z(^i1vp!Kwog@cK8?b>rHfvkdp0xl2T@WHnmWfk zQS^I~Pi++3q>(HUt_P(F4Hh$mbG{Ax-{Tby0(glV@^pO8pDCtML)zjy}+jH%< z2&%N466_PXJR8($i_-PLZh$m#WqG`m<*M%$uW#Q-P`bLiLp1sfI7@{?f`VG164`gb zMn^^R&EFYOFg^K%v0eUs2$Bs1WIB_ASHyO)CkaXcI5Bu$D}xzmtcTaLb93o#V39d$ zPdhl(-Qrhrp4RD~P1*&gmps*th7AW>crQ5Y4$9W22g31qO9`IBU|E^#d$ctVE`d46 z`qMaJ=&4eZ$3ph}@5e?5xW?2gZRj33tj|PhTJY;HKqmIhh<6Eq8+fC5tOo#;BBV?d zMUivv5WyWRSkEo&5hO4H3_6A*{PWvK5<#cGGPtFY;EMnkQs4REbU!RWG#paNltO#b z&AL;Ii$l-LD9B~oert$HZFwk%$g=L3{*7(7^xlUs7Kj_+QBk(P-|FDV)5fYF*2xejC9q zkA*mO|78IRxcFLOk>ImmznZR?pdce7vsN^nRs$;*yxT95&`#+|7Sr1Xx8||9I2!mx zX2I2g)Cq9K9{Ck3O5Cfvo5R+B{p}C-}qxNz;0~>*le7j88|0^c48AQqsZh2w}sfr3ATM z?UU~csp#c0WVi9)+-_hLtd^sg#2fi*wHiVU&@7}$eD?W7vNgjsXk@|hE zH5G_y4bE@u_DMMyTi_$YC*FarXbpLF#TQc1z(0pYobpJA1zBdFq3)OhPPUDV|7!XZ zIItc37SK{2_ACxmgpWMQ+f5wL@xq^i-z;4rt_$%o!YOcG&B_25%eaz%yzb@6$k{Bu zCm%~^9M?wWQvBRPl&u$>B#T8SIt*p2L$WaL4&igD}v=wueAv`2?7c6h4w=K zoh@?YmjNdAo`+v(s+DwfeFi5VTa2;MxgcoY8c!3wnX|1Z#{jhInCf+FwuCBlc>k(~7^5YKPfKgCtuW4nSUjADPH08%CtZBsGU;p_5%(SU!0Py-`c=}{BCvqO!*<8I| zQKNtYUWF^D>ny)P_Q*z}Ee~pW9A$>#b(7ci!b=;Ak9ev1G`w%DWG2j}%f8ss{*^V3 zY2UXhe#sJhw7uJzhjD-U9B*Mi!p@pDdtf1uf8rBnVtV@3g#LC|(P%(h`t8AnGY!RI z#_RvpJ!Zvx=olE*aAcOfjHRyPk#&IQ(S0ImN#Kj9?^OT?T;`8B)B%F4DOl96iC&8<5k7f>ivFZ(kD4`{ zHuaYD*7^8Wh;NuQ>J=J4gQ@(HS{qFZBL|0rqVnmuyGb%Pu23X(7AlQ>5;K0yEo;`5 zBb)Ur>IwlZ0k&kAC}AMg1pNUC!}cT#mLpScSKiOfn3Pf$=QMS~h@~q81_Vq3;t_ny zL0UF8oCN;!!As2}BT?bugphwxY#UN4Du{Dmu;6{MYHw+48vrOabtV6v^+un7T~;^~SH>Wq<CP#-O zbpu`W#<$Er0jPMi781DyVm{%K7H{uPUEC~T)>Ptas%H}tLbwrqOUn=yW;#K^SYRIr z9336I1%S1I8ga8Muz4^PDexdgj+{D#knuN#-V;Z$waNwWC;;d}&r1)W9a@AACw%ks z*sSka&l+373u4q%F-H@c4#b8zZa8l{7j3 zxHj*2*3C5SVhZXC8sr7?6W%S;g)hcuHb!HYuCmTIS`0q1lB#%nhg~P|)2C~-u7~t+ z>EQNNxweVY6T=(AZ@UO`MhWlpUcj(&U_`XCwtlrfS~x#HkFuCJ3MICGb@iizg98M) zLMq%{jIk_&i$~5e(iT#{!`>grQDX<-FS#{U3srtPMDthy`v8FAuenK9hI2{#`uYGuQ-yV+ zFfuYyad3QQ)2`w^vB~}Zofhskd|S{hu`+-Ax0l`_dkMMJe?Lh+A{KlwqY_Y1D43d> zhK(+PDfG%au~*JOU8rbYtmW5p0&4&U-}lN{NKP~8{l){;I2?-RzPLx$4i4#1i3LfD zgHu1(gjJ*DBOteE2trBE7(=@koSd9ctWNe!V7>dpnVyrlADTmb0hQ-q*;`HFiz9vO zKiL0viY&U*|6P>vp6tLw<=DMqMy%O9#26_iE{=_d_XbKE`PZKI0&xqs@7`5^>ntgG zRajU!(nL*74MGm^VaN^dpb44T*yv3O5q6oJ!D}d=_IL^&c?7BKuMT-t#z5%uh$$#| z0GOif?0A>d-kDvqEO2H<559?djZ-1tEOHsMZ1n%)3|t!AV;6dN{wN1|YD4Y*7`(k$ zVRsV$C$CMk6JO+jA^e)_!Ftw+U{ys0Ra7_Y%F*fR?(tH>bmR^;KE4s~CMefQAATR+ z2Xp5#yciD;5267V)JNS;92trUi-==-#0?T3Sj}S$;sA26f!Q5N%?Q&9r;Oh9qN=(& zEHd&3t>>s}-z(1(BfyDCT2DX>InfW7?rmb6U$S2b#eEMl(QU<$wVe4T27x;0<0~ za9Y`S36!LPHOL%VrPs6smvt}vgYk5o5bQ9dFpW%n@|@FVUfSb$fhd?#Bv>ck2tEYx zLO59}vOtM!Zf<6(FvEveFSpPxwaraVMkOUB1wP?riSf;}v@|jymvC^2BM|_0(C5#e z;nd-{y1D{Rg`-)5&PM7Br7DDFxtA}Ap@drcktFWt=l9X`IQ`f8mO!v!TaHr5Fo&Xsm61i)BB;L0Bl`@2=M8*B(<&`-p- zU1Bo$9!Tv7;G__{fY0QV|{f1v4>V?!jvq z-*9wvg!rQ`4(l(i0l8cKX~BkbWitHzu4(D`js_UowRJ7vBJ|;40cC|@X=w>0*II2v z9C8A%93!;|z2W8tDXGa#WrZj`!qi{jK*?&7BnqI?zFuy*ycV!pXb2p~j zOzXnc`DAsUmLSiR)pl;5Hfl+?mf~wDmBg#L4|#ld#Z|A+YjY4e%C%e!C^V!goGQJ1 z*};(D=2KkE#m2^a(F42*f-WyEE?|#Y0TFYPoV@pBe+{X!IXE~*$Hr7o0~IpnfMi1W zzr@5uQitaU5MhcPHZI3iwv((y8XQZqbSpTB-JHo?73Ol)i-S^`A$pSiih!YmKmLtsX&mw(&?qN^G7s~@2;fMg2D z5!{wju?e0R(Fl7Dg$WQt>ynNaFV)qzp)A@)-Wp!`z-;)w9Q~~jp#x&%)(;Ks=S}3Z z%+36w6%m=a#q>z^>aJS8QPtUT&IpTwj`(Jw^H({6ryhYP zHs)?pvp*J1j%p7`dtvm4F*ixWg!@Z?7ddMAlJsGdRtaG9e|2_#E+Z#552FCgf0yBA zsdT|egm$2jfFu$j7Ix!90neRun)05Dkb;7O8_Zp>TOa)l$6tpx$m9IvXT7H**`de$=`;3OH_FZ-CIi?|N__ zMdW<%79f(21se+I`I~Si2Q&NcL10A^DeS>fXyqVXI$(BRLzf7FJ20DQgy}CMHwAEV z-?ghFfsZV*T~a`h19WAczI^$Wk?h~f&;NICI=l2yocR|S6mxL&nfe8oQHA86y*lGm z!g9QuCXYgLD4a}%o^&&;>z8zdgT2nB<-Iu4eD*9uckKB%jX)Jc#j&(FFTz|$zRmNx zCwbQOvks*itgWr~Yp4fXxmUjNm|cAg42(cr-Z<4?*|ehZmy}S8r@*c*kG z5P1a%6+n+YvHW2`-mJd=oq0`HR~M#c(4YXH=LBpjl(DYRO#WV`18)W=Wf9i)d!$rY z=M(4+DGF|*E3fDZy$>Pb$!>G6)PV26x|NSU3_S~;=A^?RWZ5gBsIGnE=qQz#hkAy3+ z=l3qwt~I??RwWKe64WMad7E0`(3;8K{7l{EnE34W@|6h2MEZtt8WqAO?NsU|zCn5#Y0kSvAXQ z(zx>+>X}_xSG>Ws_*0UI-oItb1oik+Y z-(qN-w5yAx{UiqXQJ3bknbk(!joiy+7uG(tlV|8 z@&nXUH*VaZ!jb(~f83n8>Gxa4WG~ryg1uc6tG*i>Rprl z#5g-00n9N}4SCM?n-kHH3{I6FOF310zT*RudG|J9;iL;qn0qMr>RMdn*h%ALx1}q91PX1J`bb84`}*>D zaQ&Y&!5&txu$txR22xn(Z52dSGGVu)^qoq`uNu2CWiSM&rtR%KWYm~C<;{MLp9MQlkVNh{#g*7xhMp|uf{i1MrAX(}#;Dp{zu&-}3E~c{% zG(Vt=l&qTb0_mj3DHy5WAtmjGS`T4ppvO(dZ{r7Lw~{CZ5`{C>fEr;(+A45Q058EC z>1=7wJbWXY_64}@pShalrn_NZzT6l6SW&?T5%w`KOmL}CUC*tpeF_N)S=fp=gm5U& z#s}-$3KBEsiGap@_bJebkglz4ZFBD2C*^pJ?(OYOtw)cnUXuv*KiWn>`5kU> z<6tN=$uRyY{2w?bC?M1UddByj_+eWuT4=kHJ}BS8#>OtRyE&MlNEr-+q9#%L0a|?S zGyupvz7q`^sBRk~BBF`OUVSofl?BAck}2{3w=9mZfnGz)IGJiSy1rfns)Fkjf)(Ru zMMa$OfwD0;fSfYGHV4iM$OqtF+Q!E2GB9M2OkcWduvrq9GXQ!7T$2KM$W}Bp2S~{&NKihN)in# z%xTQRb)jgo)Tx{aI6G8SncMx z%iQA`bo=Yx!qDQY?*(#b(gvofHn`Hgp80Z5=SgTi6EX@U(h0R6;sAph1T>s65+RQUvHS04_FQ3QjKs~I_8M%@#$}iLnYUH@MTqByikV5^#;tN9OlkXP4$B- z(m+!JiW9)u%C`m2db~S86Zyp;Blw`541$ZudbJDQ6}u`k9kqT;D7+X6al&QO7S4zA zSuR;NHZ}?YDx3`&b0_~L^}b3n!=d+`x$UK@pQu`(l3HL^HgQVbsGzp0aa|#bv>}e| zGf8SG>IiQY?F-rIWKv>M#b0><1QwKs^p1g zmx!kqh%%RpCYOk27jP)Dy#37l7KKB)k_w9#`3TbBtrQtm#Z$eWqq{KH}!D z5-3XbD`7s6`fQ>#=%wgU`Ple4;6$^#&4p}$2AEh`b8R1_r`w~Lo15p6-l)>~(J?+w zf{BS~jRHr?&oi~ACKk|*h7Lr&$ivFYNg?=LY&xKR>&{}bIv?>g#R z;_7!KYw@C$->F#ms=NwP$&+9%mP|T$k~TyYp?NRN4>wLKX={k_^$OiXEIc?l4hjh-e3i)veF;~NmWo|5cs3Rr-kbH z^l+=)m>Zm&gCKuE<^gKt-pNu4(8SJsVpv=#6dw5OJ>LZ`cGr2L|~;u0cmfFR+{zwtj$-1oOf6RTdJGskdk&oHH_e zL?jHSnD!RN7{3dBHWLgrn|NkC5t^m-jNeXl(}Nu+g2pC|MmZWs?($+kLP__19W$l2 zA=^o|;9dm(vaO<$$19eTfctw3cbB`_@2T=9IhclY-6M|Be_+~vz)0@Hiob~^rcGx= zxP6g5XJ@`5XH1lTm1voXo!tm(_wO)25CoG*UlG)FK<@lO+J`{zzk*bFsd0kz*`Y_8 z^>C}>GYv0U$krBg{E?SMsOe-`A4BIFnds@e68zMd4}i@RD+x$C6)b>CfwIV{g%!Ln z8Vfjs1dSFLSBRp=-x32fa_eYLt?hp-$<9Fi@d0*?4Rmb)#=c~IW(YsVGLR*_apT#B zy?s7M(}wNuyzC&=cgx+y55kRJWp+H)jr6ZeMyVX9sBF6(-Gv?GjyccfAZ!Yd9P#cM@6nq@3F*_HMshbT6?HPj`??x0cAWmSC=;yXof{ zfnA{~fMIKIp9T|A5lz_W=;)6WDg5>I^&>#^SRgy0qk9L`8zC^CK;~lM;YsF?jPOzR zoTquh6h=X4(%bimLze33?w*4Z7mbRKZ`4K{>P=zbW8Z-^F!`sk@$mQP;~XXWIVj1D zCadfre|tl(gyysK6Gw9&E7BF&f%{itv(KKZ%*Us4UJ^2Y(EEk=_SyK=KQkgXRW)@9 zWif5n7Dzq3r{dRGvLKA&}?sS zL;XEOFn{9OkO9CBD4D|XP!zHA(-Bm`wro_pR;FdyFA)3mIA7d*UQMOOpHg7@zAcZO z^PLb6rcI!u;VapNVaA2w#O<0@djBiFd06hM!Y5sV*#UDLD)UsInU##)l}3+}ewp2fI?k|M&&%;#vq^NaNdVk@Wi2U})^=hX}owOqqpx#mU7* zVbrw_T^QajGwA5$( zDe%+&DCf3!r*UGoU_`(d1LjYCVF?$c5g10FnazJx?6-EMP`=nae>QsbNtQ;%RuS4) zdA%7WVk2;KVb7lJ4JrckCia4a!wE_iq%8m%A%0*RK#2^}CG-a(Z&&{OX@Z2ceaJhq z3z+NybfMzib~-h?#NoyOer_5cKlx?|TmmrHpMhW0)7NhXb`u_`=7F>lmZ7cy{F<`h z-wTLqu`jM0XkuhoCnyA{85ut=bVm&W>x^_S`{RY2_kK#TP6i-w2+)EFLac+NpX`xC zATW})uz`>b0mTc@>GV`oUVvnu{{8dDMc(9oUZBtjgj}=8yVu{FvVMa&^b)WzytEl8 z>|pXo1Aw{&9M+NloD=l>{u$Rk$;{6PT4mK6imI>3==JGv%(l84V;?RKv(qjoW2u_+i3eH+u1i(#$AK{fU_N4JhBSbnw~rLK_Z!LK*7F;5+(6hK zP(L6oTev^pUl#tUT7mct0QiZiDYK%`zDlVfsOM=J7>ccC#Q@$p9gG=4Q>0DRknJ7| z%cp2ABhJ??SP;IYp-;R#QOSjjSO#hm`t~zROPCGt-M%7X6NoeHwR;3eF#S%hO(}v>Ty@sjfLSX1;l(I7 zX`q&cR4GayPh%Xt&Ps$sN4SIDEiA7(P9kk*0Yf5>_GjuJ2lD7-KR7UMph~>LZelGM z$+jx_`Rt{#sE##1zfrffZ9y{J{t}Yy5@Ywuo%wfESo=A&_GqpCIgB!&Bu$7umbMEy zIk*y)w!tH`mbTyNJGI62;f zq=9_nSu0cHxYz`8UMty~XuX!bxHV}Mr0XszWTk`gIBxry;2ADN6 zJ)!DMw_h6`a!E#F1SjVgfW^qPec)7<2QxzGMv;n6g*k$;=5y|?=>O9K2vnq@gw)-S z>#8AUzV^C@^*Nj4HR=e)V>2zX6voLI{u|5;^UMs~2OAu#PqUbxrko8}$PNsr6j^@g zDkR?_-BV)6;^|~#%t%Z%nM4WK@)%aj4S$ZMvf48(g+X_FT}VB^Hy0;v>Z2IjRZp`X zW@cPkBf_DA7K1FNp+y~`&5!ez-DY>gT2yw^O)0521$@Pa!u{q2VzRBh=kqtDSK;Xn zIceWbWweynIBkCnwd&9?FWQG2QKs`*-o+*@>qSmgJtM>Nk6aBR- zqG!uR2~AXGS)Lk>^VY8YX-c>rTqQnYHa51mKDL`K%w<0M0B9gaR#roR8ADaZwbVcf z!$k6Tkhr&jO)7Rhv>+oVH=CG(t{CfnvprnK@xBB7grp&?C zG%{8B3Zk)f1{M-B^*uhmuK;NVpi|NysH6AhO?u}1zj%IThDR=d2)IYV_yQfMLUeo` zr&$c7UuypLt;D@aQK*MOG1kDTt)gOp-B5dRvKFa-=gyrr;9Vp}E=R1NUy09dvV~P^ zdl~&{Jdf33DkZe@`|;Y<(3RlLp2dw*#`|oq&fE`m9BZH6Rlk2~LUZnFm+Baza4D-3 z9Lv`nsg3EZXFxn`x-Xx`5TTh;hAZ}#)GvuSA^Qt$z%5U)YzN7?0o*k0(9BA)xZB|> zU({57Qne*jY6I}UdP`*mmywWj@9Hg=6#p+aLMYA>5h|*yN*xkWZ-b&64U%ibJbOJE zWLRH?Jx%+bJTZ;V1=CtlDwMgw^x~Bx`0`ns(YpRcR zUSW7){r#0pYe;@<6qU#l*gWh>HdR|MnPzv)lBr)+jNdDGIsRICkn82{LepBFGK%{3u2P`)AkoM|~o5NN^C70n`2aC4su+6clV4hgxY0SK_;BZiO3dN>D2$ zJ6xAE97MgY7Ei^)^EFPUzk@nIF|+Y@QPA+WP_{-VUfcSW{;qI5V>0p|d=BYFwB9>U zs~Mk82e;MoGPmO;U%h7k$2f<+p}Veg zL9wM83T7fwN;hyH3t}YSFnvZ`A6xT$>t2NB><>58GVN(h?XiXKocDtSCmsG=v5yia zX1e+Zd*6*13CbjF@=nXA%C3dLPupE7rkcG+mF-j1ryV(bWu7;yy)Hj?jY-ETbkY52 zr!aEG6?Z-1$&9Rl(1<+gg7>@<8v5H{QX8mtv_wj7^-bV+n~2s;&ut3B?9H!m0fWRc#H!)FM$^fVyH$& zMxfQWIH|uu*$>J9i8R80f*eZ3i2~9i^YIdY@c-NdlO~86pvSKjq~D0;h!3p|aOoi} zG;p@fgFXg%VZZQcAjtF7QH4N2**Y{-Dibwik0w}^yc@1PjzPdQym_v~7<+|=*sg^k zb?1~4lZlzBxv}p(5F}2{RmIMy!WV)5hU5Bk1wT#49FNc+9bR^d>%Z6Ijy`&|VY#<5 z<(>M=&PU_Knx4%+wgz=`W5ib*Gh};x4*!b>)2HPP*Unz{rpDoKv%V)kdzvHWOFo?y z9Pn15ms4-NrsqGFIC84mZs_nfpDGOLiFHE}KG~6qk2~|^ojCUSLr`}ztG0s^fMvSU zUQjS4ZCIo+h!hQY?25b%Ey1-?d^S5|FPQ13dIj&V5JrU; zZ7nkq+T0b^p}4PkSHi*KiqNC-xtZ<3j#TCMQ@6yPc~$1Oi+i>eoX&8R44ZzdthQd& zLRCCBx{i0i`piT#k)`^v`tU2}q7c1>pOo+3KD8dc)--J}AMyM}Qbth)K^D5!My~Nl z6Ly3cJ?Ibp9%b(}y|D@IMe`>d!OPdnefxIPMP5yEudKG_?0|tbRVz_GQG~LNKTJn^ zeD}=k)A7tF%8I{6+`SXp&Xy~OJ!jLH>*|NMU246r=qDIVt!IoC9%9j89xg>KZ?wcd z)%)q0pnuWc&3D*Nf=4ORT%txqV9VzHg4Ip^q>sgJZS=kN>7_x#D1-AwC-%CCOTbrK z?1{l@7M7^KrFSDl#Y;b|QBcJsZ`E6F;2yH`2>I5f(BFy)ZTbq^?riuzA&ztIN{k%6 z&bLF3>GPV;P00k~=nt2|oQs#o=!l{7v9{&jH?Ux4bKN1 zj&Pg$^lzk9e(2yY_Vck#n44Hp{a*Y2W7l{`$-ZN9ZvAuLp5NdUJ%WQ~abkrtC!F;`|e-B)DT zjS?!GhB#OeR|4|D2Ou&E0E%^20R`mu{(XQf(?4>Y6<8DG@eZ${=_&}1#zBl&TXm-j zB{wWu0NY~W;QRr3Kt@5q4}xFN&09hYQBWTtNKL-T+|FP%6>R+go9`+9g<&uaMcMM?%EYfeL7-&uI{l%7HNrf&uR zBcNVe19Tsz-!iu_8&K@a+DXJ_eP&1Y%H4HlUhjh( zz5akN&1!ha^CbdnN87e>+2$-;>{x%rDvJ}N*I|4%f9`wqPGIA%h>2Qb|NMQ3YW2rX z@HC`tW@Yusv!|X4?Q}Z4Z)+PLyS--K@YQ&xnx@}8EQFGpW>oNY>t-z3y7BCqyxe-} zZ>5*cuaF6T9ML6_NVsoiyFdig|CMg|HpA&Fw~V;6@q4>H-6W z6hkX7`Pa`WTguxBzUOLav<=B9RCg@5ze!eRa#~Bv=;-Ow|CJi8@Pqs`9 zB~6E7w|&XQUXS;AEVqg5Hhz3Ny?SUgmc51_`XxrUW0CyyE8iQevC3mX z9#>(M)8JTx@tiG!Ujrec=PrL2@JGsI3mjI1Ee{o~{*s6;PMH|2yIc>elT*=}E&IE@ zodi9hSUzi1FYwm_1S~L{x{S-nU;uF~v`2@T$U$@f-ET*EE6fH^fG;l_0}}WM58MG= zTG{>XzP`5JUR(KuyVd|j zH)zd54dp12R?`i?D#XYF(wN4^MsN7<9H1S$fo;J4e ztZ#9OP@#WTc$C^Nrk{&b@qwiLSYGEJ6u~b2mD>ZoPXVtb_EE@`UZUBDhv=nyt$Gg% z+_#ke+#xht-&RXYtG56H|nI{NxCX$hmgdLB`J;{Wi3`qjioZxA}$?Ci)$ z*S<6xC-C?4*KbzJQ8idv2>TZQPA6mTXoU}8*dgv_NQy7HI=^#j>WCmpmh5k`h%$aU ze#{P$Q|w`#=4ay=AB(kacm-eSGgh%tx&eY%EV?YxPJsvHX8qpW_@8{bUjK+v(=_UB z+fZ4ts}ZL0NqSX_4QZ<_*R`XU{rhtgaWV0irN792I9=}EhL^1CoMPmnovBw^T&p~O zSHr>O^V#=QDQ$3j!gE@G@SxVo`K#r)q@ZBryL{p9B>jvPj`f=a&)H^-Ek9|bJ)sX9 z=&7~nox0?*Ag1h(X)P1_Kz!6NNSl^kZ2dc4V{mJX|7)*^TVTB+S6`f>Bz=T62Mwv0 zrH4j{*gd16fn(#`Ts}wP=+YR6U*F1wa@xds%->sj4H@TYQtNE~_4k7R9v zuE#MQ=)IEoX8t3So`J&-RHg`M1^yQCP9j~}{QP`IvMVS-lFf*M5x(HrAvh3v|A2ET z6&!0ID~biR!ukg3VZrU8O^+AzWNG)^Nyp##DrHahG{%t--i|_@`D4Hq8+jpIvUiwe zn=Gs|)Se7&M!rYU2{X+1nXl-r#W$Nz+Kv_}c!(y^HRxOF+xlZwy-9n!ql|A zMjh03mKxn@cfNP-F39J^{XTq8?pOAzZ!r;Jq@G!Bp<{c5b9owU-wjtXsG2&;e(`L~9((+&PrGG|^&`8}%?XejB%Lwx zA7YGsFq-@6&Y@9#usEZD%cjMNUodrI6O{`)gP4FsdC4wsv+jDs)Nor-?ytS;DCvFb z9l!Xmv98h5>K33oxv_`bUbZ_XX)&%UU1JfkRD61ZBAK#MwStee(j=vuOY8C*o?h}$ z=atR41ZvD_Vrdy_qGtQU5!}C{<1aM_>}?9_-Q10+nRv*9G$a}p)`l#|e-D$)R5r0L ztILuJSeYz|SJ-)Co+dI#7~Z*11?er!E=c>iwFGtyD+h-=m|Fh=iAEf#?!kBv3snUL zDEjIyFI<6}Wy6uInBCt4DIdZoeZV6J>VN=5=}_xB!88k?3@yS>-&Ue*ZI#5Rwf z1WB?DHre~oKOA24dIH$&;Gm2)U2De8hUA{M0M+NOBUzc5O_J9P4Hrh-bbM0BOZKv5 z%vg9(Zna-;9O*_&X?(0ML1&ugb1f=iu_j)#hDa%6?~p=RM%INMKj^McNEA5Rw$ZNo zR{jv&?sf00 zioU`IDA(CndmtcApF6dir*)xL9-bFPnL1W`aP8z^*-s&ZAwLm|H23z0kc6z}{UMR+ zhAN$tE!Ok+<+rZKb0h34gS9lQE|XHK5pdZ?Qm(-X!6_x*$;?=AGxTp+vbq~db+ItZ zR9a!{vg0en2ImYel~|l_Z_X;5B(Upe_Oxa-cPA@fyUYeI`IGyMfLJXRT5>U(|#QK!mt~}@lxmF>d?)qYFg;YD|2 z+}br9<6wxWr*$-BXI$^?V;rql%~4;F+&+kE9~vvL#|KnCV=T8WZ=$M|C@$*GdbkAKVHvs_6_d^K2gbIW@riW;NFF>;ACR z{d0?6`2|C1V=N6bmc{!=fvQTH#K+6mob0ie+{p8yONL(%65cL09P!p<`?Qwk$<%%J zp!@yw+(q-B%JC;IQdVcLd#-G6xL?#M)1 zzLB+SG*p)RcjW^6I71|f@7PGG@So7(26|FFJm=~r0YMWo^#EWbm=$YaA_EwM&h+Es zm#58q*WXM2>>cYvi*rU9^^hb^#n{$=X9*Js->^bg zP73X5QSW4h1Z?xo=GFe`r0+F8QBx;aio8V0b=rYiZ2AL7pRdEz>A%}t>%xB-@Po)* zo*!E~+EcH_w1$UAZjbI>($KJcuvVO+-L2{Ic#Zx@WvV z`?sLq$Ms6SmaDrsEQ*3YOQD5p*4a375*S4Pv8R461whUr18mIlYukW$d{aReP5(@dJMv_YZNfN*w#Bjk%hC z3@qDMaesI8bQ&#&f5^5kwV^TO|L{Q8(AfPw@2LA^r7Z(uST`nUFB5F8sV6!7U0uIT zgoA?hx5!d?Nm;}Es`FipBXsAPnKvWzYr4;Af-ResN4AoxJQRo9x8ry%r&v87uFYHz zAn<6(9g!M6n%3PFIL)B>oMpXD!Jd~-;+4Q_uKzn;{A@b25&h`&ucu;t)9jp4hfwkP zH|yK^437@D0&VCl+#|V1-QB^zjN$~`(CU(uczb#WQ}#I**HoZqUd^)qLaWW^3bAp6KFa zMl`9ELj1yqQcakNVx0Rc5SP;Gc_TSWsXOTofoEHlIx#`CWNaZ=BsZ7jByI4rme{PB z_%ZQCmPpWqU{CUP7fxOS-L%}WH&Mrk*an3Fm=##2t9E*I0ZTrAO}J z4^^ElvELbJ>dz5f6iU@}t$SG*`QtPLY zgHHwzWV}m-?G*YylO?3{uKTz~g|e6nex|lm;iaNgW>OU5+|28#eqq+@*@g>~%;8#; z7zxWu$g{LQHFe!}x5mLarLu0rkq;K5YoF|ouIWLAS-dhqw-KfP>dK$as=L9B?9XB= zzGXMPEW)dM$@=5@XLn+j!z&$h*^>6|bYU|52d9(AXg$E0O?#aAF~{M>DTI^`x*c>Z!NED;s;=@m^`lt&3)upD~qm(`DXQY10no26&Jkx0#Z zxZ|jBS2FDLsAc3$SSMM#t0g*9e+>RxtxN_`Tp_}HWDFBL`W0sHu)uOzt#51`?{u@n zqzqhy1Azf|daz`S5nWdk94qU_Rj`bO^?nLtKB1=6+M{@)(ugksoRbTB z_|mBaw95W`(msFjZ!bik{?haU4~RH5`(w2)Zj<}p=Z{f%wYFTkI33PYYQF6)qLdAk z(Wy!-u{Kipt9UD^`N+LuVV0&z&+m}Twl?`Hk{HClxGSSBqWDBM&~*18b-$!GfQ)wF zv35Wso7nziFb7q zWZuuk;3(S^kUo8QrJ{;YSw*?2O1`?{YlN?CQlh7{kw7Vzqh+M-vyQ51htJW^y(H80 zp4C&7;F(V)cK1G0^@?!SCB%D6YH$&(eV4ZS)Qf%_!`krg-}IK@pCtWv@*MA{8wAy=~=#J`|?r5Ln z)4r9reCY4KxETvMl$GD9aXsEp{QAHJ3$ldGtnwWM!FY=(&Kg^GPb@KTnVdT8S@w(l9u~plJeApjQWnc8?@QXraO-`;#JwOH?;Y3Ny6zZ0)H z3>@98s2;x5D_eL+jYx-OjO?m8{PLKL#~bA=zo8V zzG|UQE!ZrdbaJV9Z8Z3xyEl_vR4vkXV*F`rgjiT=&abe~vA%NmFtA4-nQdDxz0+bM zVZ-tH+rRvDu=7zVu`O@8a>>+e#o;MIWg9t4bX!nSkI*tpQD_dSL+JLh<@8{Zyk4#4 zA@l{VWAlUjW% zZW2j|w)&txy>^u;ATj(|suYIFy;_tN`;)Vak39rv9|J-gPMzbO-`Fhn)h^W>PF33-0WRq>KBo=nmj0?`K7#gCaC=IyVS;tw{lWLzC5W$F!_f*6)7JY zzZ+s$)^Rmp2Sb_&;Dr7Gih1mhnGs0y7QhHH(MwuE;SHEmd5Yp?-5(P!{&`;hu(O9oaN z(oemzzccSZW4~z?b8f>VF|opLV8BMUo24ROo6xj0pq~5f6LLzLF@7S`O_BU}?HorB z#gif$=UX?J80d(CUIayT`aY_DNRur8mDbVk#)!m4h-KpNNb9pLop0B>Y4^NwH|O!Z zWS2f<9di*HSX9uBSHEd~_{||8$)cO$ItiEm#9339E$*iX28KTB0(*A3-YU)`%dpG` znqT=Z(GDn1yxS8J+BVVr0Wxwpv{03h;A#t$-J`C#!n86r9}9Cmg+4{Kg^1-3a?UqW zlzcRAN!s$vE-Yk}))tSGY*upS2`5jAls$hfBw$G?*ZXa7p_Xo9f8bKaMhfem-;F;4 z@K|*kdiwXEvX zyuZKC_y7Iek4N2gm)_p*>pHLVe2wFHzT$N3wH=K2GHw(JEofa=luBz@{#BqXOTqPy z`Ao^KJ-cmsu58g7%l3Ljp|f#jP|CIL;3Mjx$0-$$r|G5yUOMb&*+GAej@s2{GWyXg zc{X;=TQ5)U3VcDk>)Po>?aTnf>m0%lIt#-`+a?xb8^6>UFk`pB7$+QK2G5XtWJFe@o(PBC)gJ3We~kwksZ!& z_L=w0Gp3}ahpiU(Mx2)>8V1?MS8WB|4ZIn4(CoS|6%(Zqn=5ep%mK@9!rWmjk3`)* zT`#(k8l@7?rSVQx^ZVF3iPk{NXJ59TSAecTneFM9O3oNm<(%e!&bBvwF!COWs5WAM zd(?2#mpaC{r-wdl+JYs(_uxCr!=f7L@|A9#mdZ3^Q;~7U>--@bM>~A`h6~krcmSqx71K!3>jBBkoe;s=aIHP4p&S1P1Bl z+&p+)j+%Pc*^BNQVyi0trr15d%|WN*&$lOWHld2XC6ht+vFpXiFIFRsYGbz;*Kn{1 z6$(|Z94Y&4H{S6v{y`zf?U&QXYZkV+TCjgyv9Hi(!6wvxL0i}L{hr7}%S8_2V@rI3 zUU8mf4J<*@}II3*QRu|LzlMcF&>cby>XLO^kRRvWTTPr{uF~~{gOTZ zT!|h!*mEwyQ-r^e%|!FSu9N?pAC zsxUWlAthtHcczu+i_c!ABmP3)>u-{moEX1<=;PxNGrXM(+q;^LxeJnFpZ)1L{UV}G zdw7WHTC?xWJDah>=`Eg?f?AD}lQ)LiFE%C)mj&lXPLGCs{^<2rI=wdNMPS40)#Lkp zDyP}g)jxM6satZh?!NDFdbOnA;?J|J*+O3K?5mFELPm>UdfH5dokv$TY>6>#{O1~o zYuX$I{&2h?cT($hr0^XYckxe9j}fc7 zL0Yg?ukoe14&@c;rp2G$T&4&0vwtc$I@>4x|$^eL^OVue8Djoq(x< z(k*W1m1@YHX0O&nI(XTX8LQfFpcbhM&XW0QIn%;AVz=q)Kta`gQ7t_Bzjp7U+1vG4 zHnH!fA{#cmBIC4dF_VmI6WosS+PVgvQF5&8DP47QVyVtmR5`Y{&etpm?{T3otNfhC zwXiq!TGF+5Dq%GtR?fG_T7+v>XO5j4?bq`R*(~L4`ZaTnoSdAemlyMn%s9w*o?ePx zPi|M1tmyL0RbWPoV8v_KM*#>(X;4GVrNUtclD&4VWxH0ts?I(4prGbR?r~yVUtKI* zO-yeq2SBzJ($SNdqbb1f!4UTzX8us^Amd<)B)Oxv)rGf8?cTu3p1LbCVfVS&q~7y| zV{;#jm-pPD<3vsIp|gnKn!1?t3_jt)RSaH1sb=P-Ba4qsYHBfj+Nz@DqS-n?5M z*6881CCPo-SxK-_02StS=$vba4GGtR}znDTcqkr{xj7GhU&tfe_ww5y5I5k zU{RdQl_R>V3g2CpHfq?7M1Sg7-aGZ{rool{(wVYmlETiOXk>_wjkt=AFwXUQrPy~g zo}tq>?-}{?DQg#1F;ly5>H@9xK#dtt$}dq0rYt?l2L3NJjFkUGQwLy^APz_bxEjpC zX`pt_9iW3$CJOpEs4#z|o0LH#z6QE-L;@TAE8JizBDh@GxhRM)y)j862zVPesE?I3 z#?Z9`6W~Hhb3>Mu9uaQO-Gv7IEuckTL(qnpC2Z8$^p1!KnZxj+y?TH zNT(^u06Q>0tO!_P$BrU&0#lcldb1(^od$qlO_z1{%hQHb-t@f1Wo3_l|NdPSk^95+ z3=sueTAp%tb|x^{W?PA-fbVogaL!A>-VTRM54;Cfg_(L~RPb+d=1r_UAY@lsRpo`$ z4hE8cM8=md6TdU6&J_3(cqsc}V9;xMuSby^wULu@+maN& zPmZZjw6}41-fg>>T_r(vFYd=cs2gurU!j<`Ucp(jzQGp*2i649>eVgZS{ge$_G4#H z=H%2=)cg1H*kssFoOrR`H_mF8G4eW)^soAiU(<>iSzuwh9hs};xRPPkl-ne_dbZgo>jTyIm$O#` zbA8(zm>yP1=I0vpwEohSPtY&PuZDLFmcYXgvMw^Su+Z+`f8qfN0+L;UQ079NI0rzC zm?e-&ZX(Wy$oCZ1hI*!XHK|Afl(P?DF7Ofa{thJ)s#5&b*c+K`qy`7!uZ{gx6;RHR z$t6@n2o{QkxpVjKi&&S0sz5MJF3ZC@7&J#T6v{cQr$eg=stMsPG3^4lT?>gQA$Q{D zK};4B8|fTk)bN)0Zwru>7+2W~hJ%)60~`raze0cN;q84f`rE1h;iR(2MZ5tVcN;y= z6VhG6LqN!Y)3A8-3=d1gJU0j}`zC6}o3Ix2*` z`Io9jtH60Uz^Lf(%TMATYA-6bcc6V=SemX)yz-xhC2$ZAs}1yUxuCg&p}>tjxi&E= z1#aAFKwrM0K?3?B!L_28+mBZmtL21OybN$$=K^@@iTngjFMfxKg8)OA{w(Ma8HI?~ z``fLXIEKNlCmOM}YuC;<7p{E9jzIvTD1{NubfHOGo?@6vvLR$jC-5`ES6=y(S?CuYUX2qR0LtrlS%Rf)3M6LIMq1EL%iys9JO{?m>qC4m3 zFI=w>5?8A+-&J}3cfQ7}X^$5csi8%RPFrlcximS1Hm+v;9?Do3BenKO>G+O4doF>6 zjH?Hi^5wJUhwwXie1A@8d~nZFiI`pNQY)ms7%ST2)H8fsd0a1n$yM%_7-fx&d|0-} z!$w~I(cSZBn7rh?tX_SWyl#FKUfDiq*1;^Vf3JIG^mAqBwv*0p8E z=>(#INVf(ihxR_l{0Q*Tb^vP&^bt6z;7H?SY^RKXuDwVkU;K3!A{iF=9ng{{bcA(T zxlJK3yko-!>(e)YUG;fzu$tL|gwOtNi17%w1IPr50Id)AV2J>iG8CIvJz!n0tn>CK zsUX+WfYVzSl1$;Hi4suC|Ec2Q@dJeA3VNR{fZ5<%9fII)!}Zc9JIVb5@5CEESYXyP zPmTeja5i3vKqqy1=qLaDIdf z6!Z8`oKB%AxT)I$+;%I>@yS)m=nS&xC z2VxW}unQn{1rK2#=(k}6szQze!ko5bMeCsTZy?F zpS{F9lOW{?j}4G2qCQO5uMQUqf`EmX{B3P#WLlY01`Ry~3x&QdbaM391YzwB6{;*hIn@SBls>>nZt*BSL!;)GZxG*n8Y-Knvh`}1z5azv^&tQGe zvRK|7b!^(hX@6vS8LLQc$iv?8XZC;Z<(+rz-QBn~T=fWLU1YhUb>Q=nle-Mf#q~_x zbgBlp&d_h6cU>=02PrfRZwug9b9~DB%yD6M{HM-Z!LA;znO_nklT z7l0A+4?wrGhk5Hux24ix!C26ALH%DTIXM=XbU?$%ZF8{_po=Y>?>#OiR>=N+H45UO zoXl{YFPT_vh$eFM{@m4Mm8HvV%FU9|%)2|(bD%TGr_X6Jc?C`rC8KFh)&ME(JAJze zezk!{xG-La(=5EOi*|uu+xtuA`7ocU~lehQAY7W&;+QS#Irrmylpk;7y zp)Xznef9AZCkWuhn}JUy)K~r9f=ML7+u$DRgQtoIy&lfPxx3K$zQV)W-1zAJeTt9j zC+%_%1XW$c@Cn$?$9^@&R29BFD&RE#K6eC6T||L&*fT(5`Tad9bTJ=TK)>MN3IvHb zOJNG|$7@hvXu*T3zT!S>KTJc>)NHr#yoWRv>A)CQ3>~NTR{((>TmK;Ltj>Rj0R$kp zr@U-mNT1zJPhSZpcZWUy0bz&tQl`$;oMo%o9~lduS^z1!u&~f9JT68Pn>aZ)x2X$T z8wK24Bc2UZ$cPcHk>MRz|5W_sweKH~)Szet@%U-yZKDv6Qc#ou#xo;Qr_l&CZ<)F--Cb zxn@5L!of)vvpsyUwED*8TXJV(-Ffx}x>|&~C@MHUdf_G^*)h$Z9V=F(Ipe>6kdK>g z`NG&B^=14aYcAvKsENG=Cs)t;KW^Ck`|qJg8>uhbXGVo!p^(!7SBtD1BIJbYtUg&w zi1HD_pvg_Z^gIQ?LJQMga6bHlZbFLzOiRLhAkaftqljt_7^;eznzxX-Veg+p=a%An zTC4MIpov;3$R3JD3n9hN8M+9p)HD$1o`4ommf-h%T}| zv7sX;*|=@*MB?o;^xgou8~(0)5j(bwx(I{{{cj_ zAHpt-i}}hfo2VEMHS4v2+%)r}eN5pGzBg{ui+(+y5%E;wvRv4f4a@><6>@){){mrc z(J_|j)&yA;>R7&<#{WbgT{M~U7mYqTpb^GDu{nq7r;v7O%gw#&h2O2eoqHmthKe3P zR9^u)H=g_$1Ws$em~$BDERv@#BpGgFI4keVd*SKv(!$X~tAt%Q4}^aSHoI3YxWw%q zpNIt3@9gr!nE7oRSQ9IRm$(fxW{(a37PGohvRY$wVVjVI{5a>SOFqv~=1p-#Wat6i zBvkk>t~XkfLm2AbJa}1Xw*6DKoduZq;4%WRc;Z1*y zQ7Htyj1ZRFZsZz0uW>05<{h^S!9qBU*avJ6F2LT1w~rK9NNA3TQEQam4YUib9NSNQ z)&%PG%KF4BvToqdB%?^kr~(i?EediSFbaeq?%)Xn2-}6Q^01jC%J5-S3gL=DOhRUR zV9v;VN<_1^*}d(I!o(8^mKyWXqi%4EE_@j0yH!W#F?A0Q zlXec!l)u0hTs*HetZfpO{1$C_@=Y<;2j_elszS+v%eapg>JKF*(VEO%dAd*N6y>~p8M;1**3+dAzz+xV}o z=KJM)n`I0Pj$s$>0~XJ6E{WAR2-MhVK=`0-EjJPTw1dx1tg!Rv`R3kvT<&-3`)oA6 z?W;`7P>e|T_iWGSH`D)}M;|?H{IDjG(s6wA$1lf@n@=)5$qJ)-7h`yeF7k__^_OM& z1mVfJHpcTs`3`RFzHeox+mcP%2t$9VpJQ|K&4Kvs6t+HjqIyBU7?a;cx`ZY+TTB=1 zqWEjOId{lbGEsGHokMxuFk=U-iJX*Odj zgx18Q?7YN}CiJskK3RQ6P9a^r4eKNO_13%(cypsd#Ep6Gc%Qq+FBZ-+MW-Q`iik*B zF~O8$x3xY`{MqIw%q+<2CApY#PO!c=Ab@^ClCfgOWx|fH~y?(L%q9z?SNPR>^ z!hc%ypc$B~MFHSL;m|H#-_JL6vBD8K`8|7fu;KuDqUrN7Wr--I$h0MbM+RJ9Npc3c zFA|$$4-(ulZ$r7(?MDqNJ`LnI+6$TaQ|Tq<=i?Ql>ldTGH(%_feemhXjsS^M$9bnt z9=@=h4tWh|kpw$Q;6r$G(KviaCT3|2@77^N!k>`Q;v~I}uiLwg`)p3u@~u4js7d1| zT*6OK{?G|qZi$2DeRy`8iu{XGg}Ev-gJ7oNWqN`G^dS5$_Fq8c4K zpXCUd>9?Gudmmh@$2V{zQ?p1n`EO>2^_rM3Zk>(0!sWIKi{I@XUZqiA&6RI|<>=Yg zhQp;A`Drk})nWMQp$TG4nT55Nt@WGzGZ!Z2ARs3X@NU?TPhJ4r=C0Sky! zg@AwT|5f1+e|oA^lmv}%dXQ914_O4rRgVSoTzX;5 z`QlMd9Iv;$QNDulJ$d7MXX67bwjMI(a{Wa1cZ6R=HHko}3%n(Ok*cbsozw67tDV?` zVkQX{#l#|!tq>V3$jQw7;+o>Gm7){d7_~b7C|7Dxo&HmAYZ_zJB7OROkbc+k+NivV z&3`=ioAwE`R1d77V@s#o5T;C-|TPfUsoFA*) z$rk`ZIg%S)*wyl;YlKLogf|LvALW)U#cgdG4{d45q@D0^Lbw7OBMP7_%t&Y;p%nUX zPw4gVumGStAs0ONnd4nb?97ZU1ptm1O!UuGGtdUGDy1GuJYmP&mFT#*-;X#m4eX?n z<)a%HqVVHS&eTngyBjzp1UMdV4-;e256h_By3MDuP)n8}%QP#@&Qj31VB$5dm#et9 zc>JZ;by4!mVHAqD6yiPxNFIuzcbD=NH_MtW+d?Crg}5@uerugKijbluG^rXkxURtZB!TtT3nt@JX-?=rZPRl;do^q;E!PEGlO81iy z=O)7qvbp<$8m6Wf0;potsij1u0vO$Ytc&>}e}^Mx>TLYvh1d1bO2Z1bWa4I=`Nqsm zk&`0u%=X_17X%Aj^(YkssLRaHhtYXE>^pAL!Bml1-4cOiZybqA!3U5^)Nj8tu75*m zSQBQ&au-br)L-ixJa(uO3>o-Sx6cQuB}#-V$88U&pgZI??|=F5xy@F&3WLk%zHHgm zlW^4U;6Jqzo0SO@*O=9v%_g0oTO1|~Tad9RKolowtv1GU$wmlcfRK~*)t*d<6A9Rl zhL*PDHVK4WY>JIgFDBE%P}OCZwShSV3_TBZt=alJco}dAzm6xkM2gm9wWto zDL~?PFfiQx{PzS#fgtyu_^x50Wfy^D#ydC?Bu_X?ey#!l7F_|K> zqG4c=Mj_Fpqd-MT>4N_;859hPw`-YWiQy>8>mChQ;UI-|l6(KtL_ZURM2Nv6?;Kzj zfS#ck0RUVn2zN%`qTKI3^#3r@#N7H)(ETkvF*!c~>85HOwHukvh}fy}zAT4VWEPCVgEd z#$8rJ5oGrc4ocz_A(N!Yi}sB7DR-TNLxQ?dQidrX7rqzYp1G-T?})59HZ(U4^U5 zoRD6w-?))Psb39j(j5y?r{Xbge1gi`X-p&2gsKfo9+~j0-6*_tRk>_ zke)|;>Wxifgy9TIG3~Xrz8Dxh7Y3BL~`4#3Djb!t4q4#GLS7r#Qp&SM`yy(8pN zWI?0{nuVfLj4#NzFI>4vtX({jgvUUEM6nA2Dj3%LusV7^dnGmwpsv)zv^u|u zz{toP1nA-L=)JGx(a13ECID%az6q@zdrEd&F8*sgx#5YgZ!98TRWrIG0(wD}h#%A# z;#maxaS1Shr%YlI$SIcjWadnUtpVsKNi8l54ILd}%(MbRi5uIEszMJ;%3Vlevbz^+ z@Oa^lpg1qc=hXVViyY(s`?yXfl2Wr_Jee#yh=luB`?d!#Gv#3A|T-Pw_6ELZ{NS);eF|9pOsZu7z}YFZ-`b&1c2x$ z?j;3zBv9$CL!A{h6^zXy!RMHeK0z(pKODflCN*UYa>E;~f^BXd6+Iut_@gkcQ&Ur8 zhu&}&;7+9H;)zY*AFQ&?=3R?KHQ?JjwbQ7;lTI~`@^{?T_!M8jXvL_u&*)d-mB=6_ z3RHk_IOg1Na!Jxc%Pksf5#wdPk@O45M|7%j?U{Lbn?xc_g2$S__hC2)o>5X`L#vHE zw5aZrB0d)H1{_U@StI$J3jbfeIWN=7(lnJ$3gG{HQG1$+FadH*eckdW%OfMO$QU z5gQFIx^X1ve#ICJHadBt99dOB%Y({?;y$`+65zlSBfr3%siWWokeO)c zmt*iL=D&V4X|7pTOH%P_7+imljjdA4Is2vI&6}2G2kf&}&GGptuu8{1ASNKh8njsw zKF6S}g<)r^q2o9R>WtH|Hs$s6QGOo!o^-c0N4v@vV^&nPg1{_F*yDxVn@sYuU*Pn= z<8lT$1?npEKyO)8in7{I{O=Va*J@swluWSNPiSO}JUUT}fr*F~KcJ_|)`xKyWP}@v ztEMpGxa~&uI_dfG2bDK#IFq#VL*N$<#Od=M15iNBnlwr9MIMimOkSR_y_&2n z6$P3AW0O`K-@gG|NXsA??t?{*o1z?ZHv?iLc7}cu2-e~wBEcuiYeq#4`6I#Je?V)Jf>ezOh%xmZJ0`C(c zXd?t1Iftrp0aYaqZrlePZ5Wzli20<~a%@@UgI`@kkq6iM7fSx5?BD%!b;UmYXju$l zilc)L(RD21VBzJN25dHuaq6!L(3{u`q?Iq($kFq7{_^Ez#C*V~9AabJf_^-)x51eX zM8Nt`>v}61td_w&R`QsMIv1=!gl6h**?o2tdhzis%Sq9H&=(b3)@QqW~VJ|X8)RX2CY3CNu{eA&S5kw zML|!!kBwc2i2TH;wpit7B#POz<*BvZgEj_d8 z?-{H8`l-EG4e>|q%}+y%N80B0W9?$h+0z>TjyEg_I*U{b(A67ZtnIU_16>>#-h&K9 zW~NZr5o{9X?~S}|zWC)|hh^wV&8!{y+Adc&1=IChqDRjcElLC!-=F;b_jeipfIg44 zwKW-1!@RdA@K28yCuv6Dt{PtnKlRgz}T?7spxE{tz%m4m9q_K4ryiD-+ z5b~8Gt~-8iXZjEPdKuv@QobV`98}J#X;(WC}|LoHiFH7`%l!3&^!S& z)&tddBo`Wb!|{R2%>Q?<>v7x%3p*yP5LzRd`V90o{hc}29fe9NDqm2IB+w!<<`<)` zd2>Bg%1AvY@x-G z2Pe{5H2Q*ZB|%vt`e*>XDShI&knWN{#KW%JUF@EIIMv3l{a?33&Suh_5#2z<@bL2Z z;G1qnTy;oTcs~O&J$QNQSKn=BP3IR)<1{zgllmW&&0BObfX=h;tvI`=WAZOda00Hfzgf4-9VV<3Vs>A<{5H5I= zxP;`XRx3cP!^w&{A|xxvo{e}-dF@dSb|?_=F|0A;kjrV_5?>?WvLbAeKf4DHK%Rcv z$$z~!UQf&thPa3vdaPq zaRhS(U&(aZ_OE*%^#!pI15P&5cS3HF3i$}mX9Op|NG^s<4KI5EdBW=QxC;r25zgUA znnpZ-6?ixRPDq+=k?8QRE#yMdDTsg3AGnPC4`CuO?fYF^ToAl`MzdeQs>f~p;2t8o z>938HLm!4@mN@wd7ab8C{vF1r|2AV_NH=BtubtGGbS4Qniu{B^i##1j@4rThVZ}2M z%0FI=Jmrr0+G|z3AUOq6mJ~Aag=mI9L2Hg1bBG}R*=j2ozJAc~Uu#*xWYAU+trTRr z>nO;WXdHz%@Uq0aKzNbZcQ74B0{hLxpFfzUaS%BM{_ed=GY7s=`|vxA)FN{m5cx|! zOFl~@{9o_hd>@Y3XoykJ`rGdHxkr|f6p2ZGfruWj?FRlQR1=4Vg*6}At%H~<4MWyU z&oBU6j%P53))G%hH1;p+pc>xi>;HSd(ReN!8;#06&e#quyGdC;oZfYaG;opN&>bs7 zHB%B-irJz06NdT-p(#V zXw4*GGp8{@7C;b^o*K1&U`E!i%*YlX_0WM5p)iNeG_2+X>arR94et3MDp(L%Z< zFaK=)sG#4!-h7)1BA9dM&Oysmrlo?s1z{h7jzWxRfR5JKug{#cqG*60gD4X9HMB}C zD)#pE_dgE^xCnX}Q8Lg7!cdM-rS6R+Eg8x{lu4eRFm6|D{KN9Ei?!JbaF7dN8V({q z3b2lCP-9LdloGVe#$}x`tuEJJ1fdheS4xsAsC!@M4u+c(zj@U>Y$3Jy)!;Oy03d+P zj^vc-fmA3*$53A%8)dh-1WJ?;M7_c?7&{sS$GLa^vA8Bm#@rH*j_%@a+ivUZ_d;R( z;a!%3>{Vd_;{st_wgQ&?Y+|vBFwcm`tcMw0JpOEq(kn$a1-5fZic#{Y4WU=MNhPJ$$$pK9Tq8 zN!LyUvegE$=eF}u0B4P?OEwl`mij6Ywn3oh^KRRrvb6$xHd`s9LxYJ(DkG$>3uQaJBjOHx6BCqN%KzaH!C zgcHp-xx0}9qMHop7@W2RQc;!HPnB1uJTU&{@|}b3Ws=?3Gn@8E_ocP=6y2~<3e;fd z6sEY<#P&i;{`iYHC8-x%=&dwPEsY2nncWfu@D4c}TUp{qodaCXud|OP+WRh#> z)V|yE4ny+szt&4PZUa`FbRbYG*p7i&G!Vq$5kcNW6BdeK$qRd`AEsmCK^y#8C`JsJ z*joHifu?g=6BZOCVQxOAtfRBkc8dq2C{qOX*<{aAph1w#%4M7Vp}t-b#bQiODf#)6 z$;D;W#BsE@_XxX|&jy$H#x1BDv}6SmTq&M{y|^QLz&o zX+80(w3^MA-xsocT8VI*S1kapZSsiuQ)pVCH!jEWe#x!B1!}=q+zgtR^v7{>&(AxM z3=f$uVaYk!>!HTX2|aQAxM;Cr2tg@ECW;W|b<#ys@Ao!Y8}UCP?J zZ(n6SEbifU<`1pSa2>okpq#<=CfV_-9S4HynZt)7wyK#EMXM-uP>Xz{9Jhx8Ke{|S4+c-T9SDyA6KO32f zaC&fyqm>gU|1ACdyn&A6s|v&JJq&%jRXBF-zN(^oKFLk6)6pq^cK*(A43i^?FP9SX z4g-3;RkHF#&y`DuR6_k7og>yaP9EhiDm~zL=w+TTXJ~n9bNw_swJRgFYs53hRR-Em zeYOfpDzeTB`{=e*@kgkaFD!A}(ldLXce+Jm93>e?DP|!#|K#U5x)CIe!MMO6mIw#& zwTfPt$c0MOMVv(0s5@XJ(km3}Xc&c<;&mBIL@;Cci_;R8UGoHMJ^@Y zW8J*=qdMBC4oyOW$oCSDRw1=40_&TVjg1%#FefDhWvFbO=KiC>`?tE`$Bv#a*~x0| z?T1fiZ|Do-JW_%zI31ZtF5 zBzE02UPGV$kivh{%5C9^IX|y|io0>P+)4L)EAH%E{u z&YF~wOsqV`2NhMc{y{9>;;X9KN{X_w=3ElBzi11GPcRDdx=_x=T+CvUVJLsq+Vi7t zU|_mM&$nVjzWP{C4jDRw_&<=t(K!%p9fX4f9*wZ654w@DH{vLk6FoX)GGA(ItJrn>bKfYt_Zm(nL%P?7t z=j^oi4Q#EPrzwZ zS3aB0k;UQnDVc0|ZPmVp)BH|D!e!5=DdY4GMip>U+ZjE|OvTHb5hzS3E~{F{#7Q0U zNYyUUUqfE1e_?G8?ehwD!5W?7dq%YT&Q@Kr{-&te0gVmHqkdZ*Gw)-SJVf$9wzlWY z(&klr!$j|eV1-Pgu>T%FdkRF}XYsK}DUS>yl8RA06Bt^G9>)I+0OGR`ZW#Q9M^g_M z1$DjYdTGuzqznOhE@qR7+^T=$v0lz+gE)R{o?N66z8JIT!*pdu<;jxsDR0dW$cYaH z%d;wvIk#Cn&b3Kqq0Zk!oga8sjOm@7(8U-7S;IY(y{&nXi{Ivo%8oDR5nE$sLSxts zs>qz8ZvTPFX|9Q&OSg?&B+fU|AE=3}O&PIvo(-LE=IYTYyFC1MmNn^=zn@ll&|<^2 z?9p9jAsg$Cec;%>E}vOG)33v@;ON&v)f!&12p^)RXW|%RcS4yf^j~N}GpmI?aelY#MV*DFumC&yHrbX5gv{smw$_^t+ z@hu*r$pnE)76okx=xMTsFZ*n;K7kvmZqqrTaZFT4{?mgw@Ty8QLu|p0D%Or>-{(ZBAr*qPSf6OV-S4>2dVazr*WHm#y!4Cj@LK!(0TKl79++XdbQ>#(uoq+@J zBOG?U^-~=9Uf}w=5td}@x82HYBLX!*x{o6)A>u(?K4K8VyhW0PLitp9s3IKYnU`qd ztaNYfr3TS`V~O|pHv+3PM7f989F)NJmk1cAC(D@pBO+=@g`nmAA?O032nZ$CGSrs! zGTZcH3#ooxJ6Hydblk~g)=&OcuU}|+1c%j}h%!HL#4O}7P1mridQALn$#7}4uYF;) zHE%xtT5Zjpo_LwO`k;6G>vMhX);STs&jp|N#JIKG@QQgIKGrm+;ggi^jT(IrEQ==tEyL)=y zz||C?zTNsq``T|-We3b{pCJYT!uRxA_j-Qa+TPTqYeyr?M!>x0=!ys?{59f?6Ohq@DYv=R-;?K zJEcF1<(C%6N~%!avIQug`$QHiT$T3%v1#PMk7dB^(tl5K@{+NMAA z81I*CdN}zZU}s)$Y{K*l_MnLm0h85qk!!p3+4YuwA99-dbn|V&Ed4;SEcuhBph&J8 zm*t$VE$-gk*LPxRUPO?`K1ybtiRiK=+mD}-BY3IF{t4$Rj6(Y@PvKt?;jpBAznh=_sqWz4=T|wPQQ{$0zH|31 zr&3?cuYjA)<%PwbQd`*Bm~u4L^hNap7O1t7FH2nX^BH1_)rpUP6JsNBRFFoh(Y?LK zBcHvF2s@B1Lg~6wZ0You&!0D7&@HKX4rIol5CefS83&Jqp8(>yxFDX}0U4cZK!9@6 z!0Y$#p8-F=!N$hsYjrikTwTAs`o!TI)WN%U>5 zj}H}m!laS%skC%G2&Pfd;|Fx35t$=X(zCGeb$8!zf60aFKUx5P7P(7_P2BclnzpvK zWK=E%sv!`jV6x%YP5rAV57>^i?>m3~Jcbpae!NjVDG=Q1N%Zsl0s`DYOQpc%nzFL8 zO)-j+=ymhEtT@d&lCgN`)^c%kM`4lyI*{w?Vx;LX2?I96b=&EA;%0xAR91SD$}{Xi z5U+@eijs;D-mc2KYv&-UE(8E3&``;pdVnW1I2CkRwVJD8|^98vs+Hspy z?xjCtH0fL5GBmHd>yec9c6!z2PHa8BUB4dYM{oUkFW)U)hqKRx)&NSHnja}aH}p(u z<1*i_wG`%YTXB8-E#@xMpRx9@Q=ggAW`>!reXu^#(CHjb*)UMovDz(HFh<0Us>!og@mwAAM=OiclkL;7)~!FuIbuPe1^ zQE90gsn^#CjZZ-PVKvcp4orQB?^z%(bi%k6qJ$@NcwnbOtu65f3~Ho;4YffZ(T0GE zdIPmY`I5B=kpq z;Q0dnt#RL+CYOGHfb~gH25H(2o!j@brqn5_E&QaZkdlkeio1WTTBD)9ZBwSBwq}9D z#&q>%-vZ8n%ars&`zQsGm#*#l_3M$#>RAeBA-m1@)@`WP$T+vPv@`2V(-W_zHH=qJ zZ*`pA=eBYC&wJ@^OL?Y8e_y{9xBjfo>$4mU_il;K%ZUGaC^b1j(uiTX*x43`TwnQS!`+v63KCU9h(`qilKQ7gXZe@SS09UL>* z75y{h3xkF1E9p5=r$PgP&lgumShd!z+rYxXj4>|!bSh0YIah-soKoKoz5Nm8YuNQm z(O1>=%j=8MA43*Bu)6mkuFlGO0j;Mv?S@X@!;BNHPxo2VyV25Ve@b;{|M=>9Ox zg%PiDiY(ieU9UIIDXOVe_?-N??tNEPdP}R2?yFP3mMbi*e+Oy3)KC%$kMIxo$d1{a zcxLQUlH%(o<8R*c$<9iUuOVe+MYc&T+xIRX2h)?! zH8ryPKSn5E?8NOqZ#xkSso}u^*02kUt}#Vt)uTT)F3y<83+@Ke$UqCl{q^fZTin-P zz1on_o9ns`rCrQSxM5)MNQn(iF7~FMi|5fRm`5Cof#Nrj8nq)IikKmi1k@cI7DqF| zkyt_%{2c@!WVsFwR-ksYr3kLt_vz{Pey<-ww*{@m=Lmy|+YtgN4}X8!{{H^o!^1}c zq^vA0uOn2$adH~R)!(^s;s(J;K2)j63|k6JWAaW)ItjUnF0$A+ZndML((HJ3VR1Q}*f0 z(<#r8eG~-~a}3-2_XJYB3<>ESZf1}ubNSxU^rdrW#p>2aEdqk7g(?Aouh>p@m)&M> z{bX`6_sB4Ug0RaY_#@% zQj!S8h7Ai@*>@Fdqt^rv#=9}Llq5&;(au zubC#LGmKg1eC=j$wS8n{9tsgCl*+xzTjrgss?2#4Cz|NejP#F;@fqKOpHb=5G!-5B zSM%BmCI+g#UmP`O>FoI&$YEnB86G^FQ_G@3Mc_l=&+bfzkWQU5aTdUJopWSd}ugHr-_XI8H z&rY~djV&oZ-ZPe0*Y3Uj5Fh_-US*|Uh8JG5`JT?C^4EAy`TL-MrP09m01xNLZ%Lo7 zdrm9wWnl1n=y+)#14DE69bGaR5513U>%J{y3I{r(a>7~b;09k08!coR+tEjgL75!= z)eieslp|oPltA7taC@jxByyE&Tc8r#=h9y*qmoDjaPN!1ecOrgi4eqKNVc&*u>~Xa zz-l0y{r&s*A7^X=>aqwdc4&*9p@GGP!ERGiQ)8hVMMC3wuF=s)AYWLU(7*3*ZyHjB z-rv7Ta-1lZm@}^X_X2K_a-s9R@5x%y$V60=HD9BqFt>ctjSb5>>f{cy2N;nYu5eG; zWmr};mGutK^v83$*Y9U+WSQetQks2HQBkw@)j_c!|1xU7kmpJV`j4|;T_dlkZXJ20 z^RD&VBMZ|a*_zZQ40pfCzN~1WJiTwSup;k_qcF`%_cQucOO4Z~SNGG3o)+1C-~i>{ zjhOMOhdYM46~#f3q#;R)nADv};XfKT`@Kr_pBUbK|8***-%h&ns>IgRj%x2+NY4&& z2>52ba8gM7Clq0|oEN8g%yE>fy^u9(|DPNz9qC`!$)&7xSKL&( zd0}>VSheI^Lqplub{Y*Ki4SSqm*tWiY5p3QZlEw7Jy2d%jnlQW?`yhJpiAa%``V38 zbF(zhX?l!j<`M^PeY&44BjCW{ael!6g1hs^uv)bk%&i}7hAU?xA{(M7cig1O zKEA&@p5V`Mf)gbJcBd$~>f~fPA^nC7p$`(lcbeHW_i-@(Y@m7(7)U1mA>x$)_70-5 zl|rf7A3s7M?TNx}Y@7}u(X;2zA1blwBXg%9(zAE(POM$aC@dTYmv2*30E!_y_wB2I zAdM&hppMIr-JX__v9SxmIW!H8#=KBqkvJDewC(NNU}>Ml6kDjW)z#@a^WK7U=Xo{9S;?=Pp zY1U!%so^M31~NbDJF+CeGEGk@>hqR#n0mdriEhH{Y@ z-`X|Sc|Wea%Cv3fK&+gbqJp;1mBSY$BsPiMTc+nUJbzD%KCAWFGnLEgvhi^p(J=(Nw-MSKb9hcs>C#~#m8xDNmzLaIoeEOJA&tj9#D<1AI-zs+Bznxgn z<>hWO|I1asFT;<$1Wlv#d+$~Go)LD zAOXIFM}EEt0m{nrmWHOKokpBSDi>I6qLx}nvfxavM@bPfxw@vNe3n(HD)$T8K7l*) zwGvw}Xzm)B<}uL4@e2wPg+IbfEJ2R8L-n*2aw(TSj*m#_o?|qWWjv>Q>oUIMD<%5gj<+Ha+e3EH z(SG(gatNL0hIB)hZ8Ii@H_nS>Z{ypvHM!J4F)CpP??0gXi2K+toCR%N3l8MhN!gk( zZx7b2;bXAtRx8{o-CuiHWR%LQ@W*}Cl4Fe)jV}}|WSBYmLi2_AP9L0TlF(jt8?@QW z?X>G>vSx9RSAYF#Om~w_pYUbGag(FpL!%2<#OK{lQ)?9%{ycY-<#U?N@J7ek17E*p zOH=%AvOi_B=iR{tyTe<>oT=GO7`~fz`lcs|94V90El-RVcyBMnbcI3MNRm>zaAD2W zv>(CjWi9fN$z~!8gI(LXZKN-3NGTC?n28E@_1!$OSuPzK1k8u!1qcEhe`mJoEXP@6 z!g;`Wg|85+7@_@$C}v&4LoTTBx`5@lC@1F&y$t#|Um;s0^XDkgqW68#32P})Q`VXgOC7N!pR$D zv|w_(2}&6jy-!v5@L6xNl~#e?<$RJ#s(I6ZL!-r&%!uXT3lSEv1BaTv)xU{YxEfl9 zO>+<#K5G(e)n_MtR@g%WJ!PI@{QRQBI}}+|5pfYT(fnq2*|hPr)gJN zpR_%dS?t@Jov$=dDHqqaSOy_18PW#*+W@4aIW7!oCUnpn^&=FX`|5veDIdnW(@^!I z!d{9=(H9;FuZ0i}#c_gUh3CYHz$@Q?g7Ou&w#3TG4f{8{3W(EY$0k`>Yb-cU;?~>l zU)!%Sg{#wtBykvZMxCtI_?SO#NH4=oC7b;6<;(BEqu&A~xm1Sywd5ZqWj}};{O6;d zzY^d$e@BRh(O=S0n=)6fv}5;goQ0(gpLTgD&1F+hY@>Gc>ON=DF_-2!WsR8E%{9#= zyp=IVoLa(!*8CVPfK@d`TOVor%McZAc*Roo@dw&mlDmrZTxZoM98Z8)PaZgJi^R(yXD^)IR)2hcZH*}56ejJEm zR1Q=&OW_%qG`H|bSZi}cB=yMFhZ7h2cEu$;HeO7r)K})SSgHEEvUg=rr{O_+6gP#G z^6pz7)$I;=>Cbua=Y?J2I<4^Jbt|JC4O>t{+W0Gcr>jRcJg#B3?wJ~;*NBac9z6f} z@ZG={Zy1jZ*OvrZtvNWX*yCE8qU2Y|Y2O=Zcy?>wXXQej7(wcf0XM^f#lN%;zUa%i zSo_Ye<(#|vv_$Qi`w)a;(P}k;&|!kOHn5s0%2`eqQ0l(e|t!G*g^a4aTL9{bTp2biwQS04oThQ zR-nSoF80?;aI$m#8u)hO&Ax!=8rL3C9rXJx|Nn9I9^hF2Z~M5Wq$yjJ%*ZAoltS4n zBr{}|9U;<|kR*hJgk=DV%DiJcXW&O{0-|zGMp5uQUeLmG4_kDZculMV9UFUTU zZA0JJ`g>C5PH^*Hic3p2Vi{McJF)fSrr2?b+YKG6%7)JVl4>-S+N2)Ntd7}KRk3%a ze}a|vrKRQ8;EKJ217OySzdN(^c@Y$LAYS9R7wZpS-++MXo}N|TUq1lq{8ioZx+CRC zO4J`%^PD`nn0h-SUpIS)%;&jgC$BeJ|+hR%m^n+xc-3OF~&vfDf;1cR8Hi*j&%) zy1IgGyTj+!KLh)t{u+5GPKYxp9ug%_t+t5UHd@CjoN94#dNFl~GI4ofZBmcBS$Vwd z*Uu%6V?o+`Gm_Kn&Wzt=TrsQT!ke}}UDD1?oq4@geAdaye#!b{Lz=(I$7h`+1guK$ z|8V18^lP$|{YQ4OyREXL5YN%>h}O}SDWj3Jn!F@*E}Lh-Yo$P(i8E^Tjq}vpmto4^ z+euE894SuwRdap)b^!rD;O>fbo>ElTXxH4NNZK0jWOU-n=d+uOCmp_cRTmT%#LVyzPH}m@I`@9>? z=iffETm_D{(Ymw>;v|Ty8!e?6hYzey`Ss-b=6=6rNxq?c^iSC$FAlcEy_vl-RKK4n zIGg7P?MJmEv`%`-U>-AZ`ypd~jzFeQWk#O^Z0K(-PzZ<~8|(AlrQLCI=$BcRUFS9D zg?alW%QI&Uc|+(wJIz(R=jN*8(=d6LO_B4juCZ1#RHu{YWiv(2PwY1T-V?MPDN@xB zFIDu@A0O&143<~FNT(n>Id3?NI;CBDV$0Fv%mMq~Z3H$;y=tOK_I}^uoV%VKV06>Y zd?oLSRo7dwKMpNVJxuu(SWF97NbM#5P=g@b{MpV(OQU-7si*$+s&pQgOR^5czR%n) zvV)Z~YAs`Oo>6ey74=gxDT)^_n!x%9K*zD53!tWsVA@^LvDo}KK_dxna?MVn`QXlcIT*38p$vc9UPY@R;q`+F=rR_rJo|TVDN)VP>tYdefqH zb$V2xxpZ65#o>v8IibJ1caS*Te;b_x27gm%8yjMy1K;G)GwF+`EuY!m7M7t{>t{x zaUJ#Il0^qdxlQ-Xzm0uKc<{^Y6?gx0Qf{YXX0njrqVBMVvTJcd+AMrgT3#aM%|C9t?P*na^8FbHfZHk-Z z=~HF5VgF45yAIZX!@Y`^!=KQIuVgGI?;Ray;5V69Ydmp6%+d15?@Yn|S8GyMNyjG! z)`j+|@Se~w-A5Gsb^|1v8$Pz{KdzWLily!JH|>49wBAHiN=Hwf zq76}y1rmfH1I#jFO3wj?bD zbXY)#2zazv_KrLp5}^SDcbjifmN4T_yvLfFTisj7%bIrK(zq`b<*$P-l3Se=ZG`pq zuHLkZH)*AQ>h3}RSucAy)Zoe&OD(A#ONfyd&{2|IZKHCn-|jpqRk#iq(@@r61{ z_;kvbR4DQVvI-7T{BgK6zN;93ECk&4)>|5Vi ztfbV|u6KN-_!yN{_k;W{T3>ozqNWqEHMZC<#n|JMu|;{BY-%mW$;pFPc7XY~NM6TW z@bk#psY&TU^)luVDym{e;jpvk22lDqKMbU;={b8ZiIZ=n^I4xhnRHD|I_FKM(-jZx zLW2*`oHM*}($1f@GE!B?{@Ce*67m-P5&RT)Xo}{I$M+A+uH4=4>-*$9l%+-9N7Dj4 zBUB7LX8(@5(w@9}f~8u?Z1Z(=f&0qovcrMjYgcriANolqc|bp^8PJoMC;O|Fh7Nx3 zMao7VtmP^8j@-qG{zcOT$C2j9@15xkwq#OG&C;pEqiJO%{8o+J+2h|8b%z)Y85Z{0 zk(Qh{IV)wOed3tZ$yb$gW+QMrM-B#Zg%>lH^HZf>w%qw&gw=rDti2%VN;WK|z+u>5sH)>Gl6`LKv|rJS__ zMY7HbvxO%QY&X29EQOsH$7QwU==HLNtvYs-QP7{f5un7&A-TQ}`y$GW$CB94 zzBE+Vm(0vpa(e57Qf5$P!3JRT)fJZZ7>fd6id*lvV=Au z0J5vQdy73#4@e#x@tx5t{StT?j5`VYWsLs+=ueswyDXOYpfL-!mD7jJNOFJeq)dML z_=##wYxnMR>#rDY4yHNHtXz0KAHV)N065CY+_o%{yRf_!BSgk>DI+s;xdxN{`|>6GQ=JDj`|O1 zd$R{!XxSPc&xY=G!`wr;PDwR6Ba>G<$@gM?WmEkw8k-0IgM{YHq_Ya8-S3l69UO=` zsQpWXhIVvf#7L5~*+|x?>`6&QpXl4ek&$&5ip~W}ZKD(PWSv%~y@<+j-H5*FX&`mb zE60d&9lqAirRIYDr;F(|H1zMseBCvj%lEx+aR&)+)PB>Jn(603Hy`aVN-g1L40->e zyS18v&Vh_Z)b+{ksnUXLSFN>g8?pu|2nZzoT@B=Tw`n{*s=xlNE}p3-@bJ+E6+y6Y zirX3z{t6is90q7{O-?+ZDYboCLcHi86`i`Nc~rP&GN8ID!;n{03BHcqufZoo|#KD}I`5e>_`#*!Sr%#_|qV3&6 z&_Yn3x_NkHUGF&w3iw00I1{MdAexEqo&!%U>gPVec_v9X zHZk#z+~;DepRK+)-1bfMG^KP|?%5mCHkTM^6zD}_nN9yyQl_nCSQqm^k!_pW`q^F`z*ioqKeKc|dUBuV2FyRj4BouM4< z|3TfX&4%}aMaeHCsICS^SS@31CqfpkVmvTY?bP z6IPwKjSmc6zGh?708PdF&8DU%xwsbNYuBnlWk}D+U_N=0T2fMy@ZgEIS&{*9vJ?@oeo{Fs(*1DrUXyn zl4B2b7p%9rwi2;&GEpv_AN-q6D(JcCIY@|v-fxT4E87wy+pth;pKa+|>OhrKxCg_v z8*&Cezwk+5Zg$2b@q8>xOsu|tauEmGskiUgHItHtCdN$fNA211G1<#B;K9RZQBl4- zdDz&h^vTNZ_(jOOyb7TTA;Bo=s<9=aXxT(X{qE;m3WtOQ7Vkx2ao)gC?yS1hL7L{l zsqO=sPUOgp(_!I#bN1X?3hkn8&#uw$KiZ!;B?QE3hpOvpow0S+@_%72W4+HesQ?4I zPZeiJoMhCVh}L0T$Qh z#p#W3*P6hiER*}FwNHW-r4`S%d~;fP)W?|U0&W$&qEa0BQ+4-!!mZWqdrbO2_*Pcy zqriO@65gcBp#A4+C{w%Dd+%wosL%-ikQ|=ELifrVS*PVQ{KHFhTuUa}d`4#+)R|p1 zo_8(x={PSPxnm>Ahw)Z-ro&!>8X-{}-D&juA&6;`t9u5M*^X#x>7LQE7R1T)At>{- zmq0-9k3W0nQ&g8a7HccXUV^!C1~tto*Qvu0P*;FhPgO8NOS%+FUrSjn3$QJzX(A7<%t;N76YuLIDA+MPXK>j zQ-Ihgtf(|KHKF%{p6Fa$%W0uu8rU|1qXS_OVfYpa@ge_^qnmy4s4$3(+*M#Ep;A1cngB;-}U`--sQCc3~N8^Xw6e z25&E!a?s~r?sOB^2!9$fo;&xW=%?;XOHqD)LDuXlBeA{Aj+^G&FN(UCbZwWEyzRco zcz*M2#j|=d&%Y~qjgi8y(5Ac+wyUxz+h2ClrNgt-pdjqxCPVdPrJIuS=dped5>1QG zq#ui}lfHZEK_%owUajmIon%*1-NeIS`7KlAC;MjmqmTsGB6a8m4vJG7%zK){$Ithwtf5dFQCW6leQdaGu(Zy!90|p zqyXQN+E_Nlrd1DbD$tdy%gcYH3S$VYeCEuVDBe6+N`rAw1Jne`FybhkI4M;(?We@W z1DE>cpe7=LS-J_V2MD7I;9QTl1riICW3(6=c=plWoq6i6v3l!2qZ#k3!#5?R9vOY2NNTgTYVD%4kPuQ2 z_v$RUy{+TM#tsXerJC0_(JGCw1b^9TpjYtaUFnXmHD7EjRu&sbl-!bJ{Xf`&q(%ZP zFF~dA!80K;lI7KWDf@!_>sPke??22{uj+QgYv9u-8NyZ!T~MHQvN=5IVev$1W8=`z zb4E^XCnlukV4;$r#Xm?%d0*rBL&wcz94jz>s=yumegL!iU;d)~Bp-2EvvZ8uo5z<&+PI~|>7PYjKHnR4_<3u5moBGGynNt{J#LG)7Bn#}THnoVoNAN_+V~(@8jn0*0x;3!&Jpz8p#Hz zb8F)Vw<{jFpAZV7IgH#aFh6UT6ehe#ak=SE*&oG>sItCZfwFDRIqj%WFvu<$5Lsho zRm10%pgAH0B-Vb4g^le2YOhO6Ut2mmEiir|=!+ms=?tj-o5mHMSyZKV%+?sRjA!L3 zx_>`=>vN&mbYX$YPi+Styk09fk&mW1mjA;#hp|F^eO(hDGk4yu2c=Kl7puE2b22p? ziYKa)qiwGj{jXaMbiGs*2#wYY=gp3#v+R=TL$UTKI{FAoy>`)M4n&z?GadsY3qJ`M`WlpN zLY${hN8;1icSNcY15)BLK#5O~$xsNWpV^-dTaG<@_d?QT4B}V24^i!%P4r_*YR}72 zGq#C2nwI!k}}!yyLAR}BsUa&Xq5HRG9-dmI1QOg>HsCPVKHxQv1>RL)UON|q~!vs+&4twwNUkgAzJ{Xu~w z#F_oLW+&6B9U#2KPgDNyin&!6e50Fl)Y&h!Zsg&kgq;ZnB?6IpXE@P-N*e8$+dqH)tN?Wo)?$M& zy0{90?Xmp1$8aGphk3L1&+;f(yL>HLD%qb5uf^X!H4~uxw4itJzTF4|(W7t>xiz!~ zzQs!zuEc6_Ik>u7fH<*Pum^4jbF~8yu_sPhE!*YEVnTImF}kR?>lK5s%?&k|gHbvP zaw^9iE{1DaXVcRCHZ@Cplp%BELFuU<%gGcWukKP%J&?V$*}y6u7Qs2=C|FhBc4kjG z`@cn&@r#LCcqyIasG!uN+ACsf?&9?uSjT~$x zcV0Al&JPQoj%u7)a)|Sd5G%Y|N&iED4gq2$SUIP}#0cs#eAG_e{wtiCnyQ~~?*od6 zr0Xr9JU@p+jpS0O_ivX{0XPJAN`6=hzIo44i!j{AjABc#i@87?Bmo$Al zb=w|;cX!~eMw6T{Mu)2pEO0_d;@sH zx1M9yC#Mv-z*Lk_!buh?Gr(YN(qa`CwW>sJ|M5XybBTja; zktUs*r;1C2?p77++hK~3XHD@8$17RQW4X9%zV+U@=|4HMaPw_Jky!38#I_R`{!{d; z{P4NVXwoD8whb?Iimk>>&U&3axawWhRA?~LbzAs3iqP{_3Blo4o@&n>jx@5$Hv2_= zh$_0NZpQ8A5r4DERHrpZ!6&_IS6{UWS*$7YtnerDq%F==_GoT*z0Xw?P%~Tps`dUr zUNeE^JTnS|t9FKU;Yyrf*u6k>|D4QhU zh_nitq4caQ!s`%JHIhpu{LfEMs~r(a6?1_p#c6GhLK z{PD1G7&IyJmB6!R2SJ%ZrM5KmV>+P9I|ToL#*r{s1SON;(Ez`ifdo${P4hodM~4|1 z9h{xbpucIa87Y&vxdcTpS`2_0PeAQ!YD9f7;f#N3=1F1+^$m4gch1TRDc6SSm9xw3J*l;{<;iL?cqSjJUW$&sD0y1Zkh zYIuky`8bz$(CZLYbt|#mx9J}4bmyEOrX3x>n#h-y<+PH>&Bdu5qWNA!GnOkMKl>?I zTMz#VzQ9*e73xO3GPdTFw>ml{NUZR?GnOBe=QD0xYw-JQo6P%#T#NM`O;F@zCB17> zp>}VdVPQW=+R81&_KSV@3FW;R{FmCg3p{r#YMG6MJPXlLQt=`SFObDwjIG{(td{Zh zFJM;IXSB~eSy|mk;v102@o8ZEYrXFm#kz^p)D1!8d1K$c`M!LuE%I8W`L!hB$pn4v z{CMYnP;7}JmZ%!Ry*|I-pM(XEPrs|gLlj>EkY^53_x)FT-mkAg{e;!v^mpD0cp|fsn5t|OemWHsb0gGiy!5f51v~>IaL&Kpx?Z%HL&=hz9_`ioS zQo>sR+Cxc|{}L_B*LTVcAiOwru3{-;UU`6#QCUf854J=W1kA#s2jUYj3d*~?3;u3O z8}@W}$0R4O>W9SWrLe;u0c>P~XRM&`-YW|BbO7#8o;>Mx>(-@B5dDteC(17<@Ksn2 zE0`ZwT`M(?Ei;n8I>V&@m(+NCPR9R(2M{p=_ebZuh4>jB?xDLI5YRNhloq1E)|qBx z0WnDX*$!ei#tGJ+Gldup1`yg|{k?*9P1H@8GqgwJA?X?2wMXEh{umsTxwmugl+}Ls z#R;;H_|}gQ>=r;orjbO6Jqq{!EtDFYi(QO|4?orCEwj;W#{OhK_e+`J_rUROx^$J7 zsK(&IL$J%hd)&Bw85)-tgamVXpczj`7@FY*A&HdsevQ8#g4z3j7Jm)3IscbnlQ$g6 zOih#fZ^>HE`n6M1C)d^TzRf?cd@FvZK>=lf(vwtu{Cb$Ge^-h9oGQC)Dz_~D|2J%> za$1`uXL90OeS?daW!X?aCN_v9HgKzj>S!3M`xX{c6lmR*VV1Xg;}?>&g=vvJjMGIn z@Gwyv9kn2(27o$ps-V@U`b6cmx$=}t>uE1)$R zBmCu@$3>OODJ{|n( z_(Y+dcCTw$H-xy^L)CyaOZXs-j`kY3B3S0BM$&oSP~>Yq(dXqrI*|BBBHHO#a2;_s zT)TFSlB!SgNGEi~wJ2Tq`T0LqRNR9xY6h@VlwK8&53+Fb^0M>r_=BHJm@G%n{&lqy zfrT)(Jwm5W0u=Q=IHyn=kr37i;6V@MeL(b1Mt1fGLtZ|q{0~sPQ&H+o**hh1dG#=Ek^9h{A)Elt}}hRJ?ydRDzLFQ4UT{=VA_2yqDsc|IA}Q z-V>dju1VQ}Bn6$7$}Ot*EPnlIQ{fXX2B0287|m_ficHo)We zFq$M-fy(IUgd(Mr%J;lu=gf7~dn-Mr89_nn3y!#@F^Q10mmsFaC<%c;ZZSsLhw>#? z{G(Hu>C!q}J?W4@!fROkSUWjoV`Dt6tm!{#Tc2((`J;??Ajq5N&IMgyMLRzOdp1XC zP$DBELDwZ>iE;!d01n9*%vCnOQ3@#x^!+HQxF?4qe?rReAUE z?p<6o-iDQqXAcz9kjEYy{v`XBOoKK1&e_8I^heK7Tu{AW7h$`yo{>&LrhHK2_0o7q z=Z$L?&5^gR-Mr@dT5Lp3P3?@V?1Sw?Qkhv<6{u@)G=P)CdQ_$t-T_BzbyT0FZMf3x zJTXK`Uwd5mnU1cUp}N>D+2OYq!y3B!Dqa~ru^QvDTT|rx6;fni38l`hemumot)sNH z-I~oho+3x#!S8w}lDO`tb(YnZf+oTd0`#9@dB*khno_PjIeVOM=57`e_b5h{eT%0g zzWtc63`{Gc){(d9jhu9F`a1Y7uf{O$jCzBU*zwDx+yWch}py zc6=(WywYfKz1?AvdhSx}o!(>HNaD@q8mY-`;+p?dOwGZLySn*ja~>s(0SWUK;y*1d zErgIs!!pzjk(gMViNba$_R@-HcLP5pr09iyy#SChC3TXxHovFqoHDLvCG8d)#pq@6KY*llIbORzI4dBMmmyGGK$?Jl^3CzB!RufZ`4Za@m*wCR zSy;B=ZDeI-UH=AFEZ1kJEYm+ZWUrG`?s%mEq=lqR5ZRP)Jche!>0}N-EFur<%E&t# z14*yV(qfwi!n53Ey2yEq0_Olqv6!#ZXS2HZ+=-5kCPM26pICRRhG~!m=!xK${m=5R z_5RoJONrf2M8GtY{rb~u;0E>P|G*?28|x*263 zg`_hn8gI1pZ>LtO#J!l3x}SIsjxb_~l*I0lUsUw-_wOgc!NGg_-J+?esh_`krC?~t zgs3r$A_#w2?52pG=xqv>%Gqis%F};C?|U^(>~2N>7cc0JC-a*KUgi{im6({Wdqs#L zrFG9RJ69w1Q@KNO!3&Ra_2T7Hv}3fnQnM?y-@wBx@r9+ZLN+}WSBT52CY1-lDlDQk zB+Ndk6!*FEC2SlV)@+L0W}VxE(3jqb*|MW!$g-eiEujG^60s}9x7qKfol;^Kq9erYG?%3^H|MV|KY&?WB{NPaW7 z5HBnll{sNcc}FH*=I7i=XHg$pfnzNhX~gJeS@@t zP@PNRowHEk^Yf=`xZ0teh(XtdUi$2F2{_J8+O5CRza^1FA(3;q?ZE+8d1T5#B#*+C z2>XN)dXV*PQA2~5(b3IN60P7U*hNMb1EMf|h{&EEaPkuMtMHENVh-R zYMjLFdhHwWgJpA}i`x$L9v{se$hz4nrYAiA-R+Y(<((3}i@GeTe{b%)x{=W0U8n-h z{2ScyM7-+KfH&dvi0i3a;23}1mf=ojrr<~MYcha3u?Z34N^%-rt>2C#+EBPPA`P4% zoF^qEfsGe}e(Vs?DVVY>f4{dMI}e=IHpUA3EidD{P5T$R4*m}p07n=RQ9(3H0Ixy$ zW9m8j!_^wfC&C2=aX#N6-^A&9X{6dY$q&V_wSi-Nq5XcFvopcx*ba1_%5q~iyxtRZ zYx%(LGZ2U96x|f|a^&=&@mx))2g9X?P!ixyLgMYz%bM|IgQ&iz*qjJ~HT2np8i8n6 z3E6U|p~vTw&67-iCB?)Z5LGJBDc^(5famC#1nUOg*Id z*ft3-hi_9ATPE>jNyYsNoQjw^X8~`s8!Uje~MTG$AVe;^xY<<#>1O!Sy zpjiYqO&G;uXkgXxfes#c7HF_@%M0vk@Zs}Ed?wuQQ?7_2AHkMk8g7uZzzU#ybglTK zJoPqJR8Jegn{K-C76dsE!O^&$8OZyPK3oQbk?2P;TTlS#GYaFjfPjF^ZRE^TPckDL zSa0a6PK{}DQtdw7lN&!iGG{4iLJ{Dzu;ILdS?&B(9|J%>Cb#cCJ>rG~0fbGCFFL_?E=h|}89;#&fcqT^s%z-ma&Jr! z#$s{;pzQnIKij(>qd$^M{mQxwA@8nq>Wp~Ub&5)Li+BAfncB*};K@$1QQqI~)q~D5 z6Ow(V+wA6Osud3dR%aH^Ab2SKH;ABv1Q$Vk?EiqFf_1oxL zJrzmbZHvF(3`S1ThMv7GZSioy^2ywEp--~^pYd-w+(ae`_QDSWE>Z~MA_NmC#*zDt z+>S?Zw}<6@uBX)fWxv2+m-6r`@{2tsBjUu4R950jsOE z5AOD75fO@5qk)o(VcXBc0WvBVn>`U=gHhH4RKn^mI!RifM4metOBm(Bn(C-2yrzGD zfbk!&pK&EoAD6T6mcy+LcK}6xd`N9p=sS<0DMqfM;az-7ClSSqNtrn!I{qa9io7Q5 zkX<@3^cusJBwSS06%kYL-$57~5fzFjdOQw%AuutK6TyExzJzn}f4@;1{WW%r;4^K4 z_>DzM$`Ce5|K48WSLk#cTwKh7QNZTSh(Z!iWqpF~p8PI#4mNi7!KtYLKR>_iaW5g) zD+l0(#{EAf>c3ZPJAh?{&k#}RvhgFXrr+8j(!0>_y?GlJs6fBh{*I>s!*~Q&tX*(- z!J%(%N?h85|1NDXk$oZkPj7Jn>Ggjo?RTm1Bd>jW+aWDXRx z#A`kOzaH1;qln!S$rKj>p|EAZKs~lP`2U*VCJGT;jkClK%3Vu)8b)DBr*4sp)kwcP zJ^f<)IpX6WiM(9=Y?MYmsC1f!$QEr=$C|GMml0LY#eXZ!jc_w=QxK0P70`L18M$_7 zC86x)`F}pami)#?%?k=5FVFL=CKR&~%O~-kq4&BA>?+-m%QV)O6wK<5>)2-b?@5~O zMO2eTxn3brdU*Ira2#t3;rZU?py#@ue(}hzGwRlY7NIBpJ$IYHmMvR~k!DE(HQ7Va zez$Y~ZVqjhDml!mQgX{ zu*NGTW54b&<}k^Z&dBRD6{K8$IdRsfN{jbj+MM;Nb1M7dFNb@NmWUe}DYUj8Z)lR+ z!l}ijM4z(#5^lqEEOP{9Dw~-NUH?1)1|Wb43&lme@)JKlwr7K>MXy+&Z&&S8)6-M1 zwthd!2cFI18XVG)tZ_-<7boSD@#lPcDU0vOB9fc85azCmYim->u#mWEKtYz6t)!!) z1BMy&3u*H-2M*jRD=TBY|Nb~!(;Wi43hv)gtd%rMtqyY?KK5|D#NdX*uaIH)fxIvp z4!iQE_$|XL7fCoN6($Vswyem<@}4>_5l<{m^3mdAGB3x`>&@QR{>T)6%Vn9HVWzzE zt%)h^=A`A?klG^evi4RktbcuMg8=AD#!h3IzJ*rTwkv%L3HmcwS2SZ=x{Ug5d&Wz0 zSUJp@mfP zp+-vRcjAt6(YoAZP9ge1esc7VM$E@JWd^-sVQLQ@Q6g`y?I2zs6L?ZwMhqtjTPc(| z<(-{6cd>`C0wzNKEj&pHS~3Q?*mhr|PSjSgC0ye{Exs~a(b}3N_aT}%aArN+7q)sYBMUQ-u!(xv2@xI{Ie^FVP4dY~BOwfSI zfVq0Tjyy!+(#X{zOr5~jKnq?tB@$exl_cAW6LJ}a`zhF^ZftCzwwyyy84>X5=5`8G z+052Hw*PD`0X~6)w9ARx|D8xDmE}(>wjOLI_Vw6(5g47|0=zu4OTDJ5vT_E)oH>kv z5U!vIemBn+0rd97d>^q~ygr4>nC%eST8I_K4RHizu{BAp3?0Jz#?H)v_f2}l^BLj+ z|Luxv_lS@3-`Vk>|HWzx((VB)-Su2tKtO;Pk`PIPpFSatmKSa(FV3vX0-Qpak~xs% zTq{Dx5G@^zj68xs2|6XFo9S#GnDnLN82H||^Z%D5kSMb6@TrfeBM9e5yg=?yIRSt{ zcMP%e%cFhrcnxA&lDmo3YfF|7eqU$qXTt9h;w{*L-rGL8^Z);jtMQK4kgkeZQ#g@m z3p|=2ZlZvMbvlS^WEvvBASWiC0L3W@rh^3RPDND(Yj$~LH)H)}tX~{|J;2HKpR14Z z93?D*Y%UzNPQoEL?_NUu!^l=K8a(3L*r-H=ULb0^Wqg5%u@b)i?FEVlOv;+Ds>fR5 z9--zrnxd@;&(1LP3`jKLKxhCy6r_F_;p`+}bYf;FB$U-uqwv30_FKSL4u1KP-6t^~ zX9uSG!6>JO^pB2gB|E=257RQjSp=sxVXTVAl|@1#0xwIn4&eW=UdT}*M8KGrpob*9 zY(NfxMpB+Q<}s2$8d+ji#{aX2H!evG4GZJMYhe*%Cky>Qua%8BZA14lHgsRQ`S#2x zK8c$Wx~#dSvQ0)PugEkQahX32AW?^!&rk^f1-`}%Q*KNjh+K!86J6>FgUtWyc27ct zFnBDUz?o0+RFD1mabJx3@EB2miP6*+oVlxh4twvP7WpHHy*h-obRK;Mk~0WXtgC3Q zh>ll-F`;#g7*k?Ez<%;1p(yWn`?>d(u+=BnS)Rx2BPG!1e@lbGC)mESZuE(ho#!Eb z!`{f}b3g{K)wF}+F+E|OK`7cWHF8>#T6g!t?KJ|F zBqDW*FyO~fimN0SM>H}3>Vdo1eajpF8m~Bpx*W-Bq6Ub*$>OK?4|$iQ#nq1n)1$Dd zEbS3O3_w&MRK)M5uatR7q8I~0{j0E(2)#k12^KSvl!tqGAUzTv=QAV#pr1D*rNo}d zMx&)kr0)q`Yy4=;&yQ6A#~SXl2VEb4 z^N)7N6n&8=>LDVbl*pL^5WZ44?j;gJd}M>JKr|uquDY7>Mvc?9wK-Bub8M3V_fpOE z{ZmUw)f*fi_o(PpWUN_z^kVM_-Gi&$NMGc)%*?lh&5mx-+Hm&tr^Y1jxXDcTpvler^&>8 z?CcCh!4JddT_17V5b-)ZJfBYvU`cjkoCw!(5OoNo3&$@pJw{0dDDytv7PhQ%ET_AA zDes^c%PTgu#J+_<1Ps4?P$dzbu&|pM1Q`{%HE1Z@27NiylG{J%W^6?z4T8YEZrgYG zoUwb^BLoD4>|4M@Fa)Wv6rKeH;ee4ShSIn20a*1FF1R#kCuspWehxr281^DSpfG|M zE*N>e4c4LI(8P6ZG&eO}gVY|_#vyoq5Zj(LWXcFJvgL6D`$!kp5|$2KJw0=fyi(B9 z@79fI@CFzH@cBDP^jJffXBL>0w6?Yq#s&yEA=uWU*O`fYyx!xu5-_@x0q6RTephk~ zkr##opaM4m#`>Xm{^t|AAVTOs2o?^&81TO{*WS@AwIPdw4ryGFF?IbY;;vH1SRxIs1nQ^mjX;2SCr&gjdgBxTCD#l` zn$jy_GHGe)#i_n4=9e)tGeh(eAxy#bF%=BIQLqN@)>f=1EVmlG6gD&yP~)C5hz6iY z2JUk`LKO2c01pBfKVcj6fw>b{cs1SK;V2$RVEzOqKQqD01Hep7V!@~we`#|vf=K3r zj}jDu{h6-`KNw$**T&%Pp@~Wd*uv0MgmEo4nv6!u^bc0`a3FKv+znA48A@eIC<)iWfZz zs&cO;&O5PR9S13YPmawa z_&j5mO>DPD+ju<rr9h7Z_H@w2tx9?jgRizTVdS^vuU? z_%kd{5O9bcjT#=II4^3On@K-!c(|5bgO5C;>C$zuG%`<$Oo~09)p=oN7b~dg= zTzT8>75>N8Zg;-+bgs~zvTmmgr8_R78!V}?Bg`(Y&K#?q*nfx#UZKUdQ!c+L@#6v) z-WjDr-D;lh#qInuyN8ddfvbh=(6=g7% zlgxAf<14j-SGMmJ5OReY+XUB`$U8$F+e3TWRc{(RmhtE2v6+}0li(m_$f{FvID5Qm zC7yC5R83z^;o{jbmsXMqmz#-g)>_sNLwTs)k!J6^$8A^v=ddQ7q734w?Y zWJls!o>rNCvJ^Bu`HKH#L`oW+a@bR9B`Uc+<{f6~aasH1X-E$nIG++9x3}MzRG)1~X1-*6V{OQt=NC!-J`K0B0K%`_=SR!2b#nEc;y&*(51i~vk*gh1%%Tn5 zTxs?OIBu7dI(J)j<^}ajb$wkqD-*hS*^ZhgyARQOP|-{5rI!$~#vlCYNl85-^$&lz z$QS}=%zV2Zt^y^_rim6gj>msyp>JpjK%1A)a*9p zpx3Np`;X!GMI#N$BD#G2E2M?}c`njXVfO+fw$T-I+~{so*kL%ePngX4=a-GjE2Yxd zWk*LX+pHH{wpmlt&;X)Cvxs`uo;Xu-IalJan<1A=E?y%jDhmCv#f{|E?18ifjPwX5 zCuU_Qbkpx3!m@W(MF^b_jP8)~1`jbu6z>XYHAuh$*Z?|4H)Ne4(dC<5Mwf!1j4wE5 zu&Aj0cEq(TKl*(;C*-TL_tApF`cMybj_}Xaj$dc615@b&dV6kV*q8FlQJ!- zIP)TuE`=?L&cveo@*y(bUWvGUmhVO$k)sEvRvR z>}mITSbw^5)?@gdX0lMj+p_B5d>9hZuX-$5%o4|tH(|j9q zJIT`B98nAwtpOPuGgo)!GBR(W@h-qk`Y(6!>eU8lIV(a$v&5yRilz{)-)j_z+cnvGD%#y zTYQ7qHgh&A+9!KC+Z7^v4}U2dbGYeLsiL#=H>OPdv)wo>;-WqS`D zjVecE-@>Q?qrLsjk6Jh0x3A`PUyb>Y_%wEnVz-kYXTH9Yq4pMf4-qf_;u*Uke{UAM z$lh^7nghhd$r#gDm#eq;m#*$3nH&fyl6i0-mTN>u?~3hqX|Zg%Hk}x?wWJ7T>)*Hd z5#;D#`|X9IAN3ElG$u*#m2AwV*Q@Srza?Vc7bCk|*unDq2+i<4ha-#0WsUmAydG+D<;5-;O(FL)m*2V=hvQ|=hsgZLpM-l4S?zllCtzmleaouAi|j{H_NejGTV z^lxR|BvzJ|p29}?JeuE938x429@lvuZ56#dWoK zyJ4>jig{x83g}s<=jA?`wS&Nvh#@*cXj|a^4T09pR)NIn9OhLjZipqaA|A#y?my5fR=NN}% z;BAILwJ=Skbv1ALyj0bDzqU}E0B|d#MNadp@$A4`vZMiTyLB%ejZY86oTe1+TGTZ= z?V7dy^wP8=v!Py5cXsaZ#hJ%tl?X-$sVJD$^?b?#ESiPD%mu0R6Ly4T<&q7xy9uYt zUi8j;@+OR!OdCH+eq_kgck_R^0Ed`(eqV`5)~_4u?VuI^RIOt1D5`0n4xhzSDs}}w zg^LBxE)FJ9p7u0wm~$y_k>&8g?OuUqHbvomD)SqDom8074B zx=cscsn4lJVs2&S?SA5QN{x>CjT5FzWA!x5S+lKXCzu>M_a2ctjQ9>HLwU*%)71bx_igLz?_6h7M__I zrxCMWvWNbE8Pp}b3N03hXlidS&dqSq5xnfUtkKt_je#sRUhA5}!gd2;2jd=XNuPa0 zMSM-&@z5Km$~wyTZOTbyPq#d|*>^?V@EWW2AEuL@CBc=!$1_=o)S$uF5`Vtg3^9t` ztuNm)P{YKsywLfF?$iOlmResOqjgR5X5CGChvV{JtPZ>7ub7@b^hZ4CGwIb#+VIk; zOJt?_HYkSyUDKiPP7GQAz###|qQqu+FD?J~+@fjpc$xlLgF{2-f#bgaEUp^H?}Kcm z!I$QYz~IqIWuo{L&uZpF$pMZEp6m+GZ>K9fZkd{MwHF#?k~9W?{k-d)zW?15ZiBn} zR*9yZ+-xjD{;`AAOX+{91qEBbeCxh6?%$7Ww?Ql9_qekgUhVnC4uR*o%)X1_|mmTEfPaQm6Gw`Aa?!r5iW=q)6|gI}II-$QHWofca$;jZW<2ok5NqyKmm_MUxw7@UYz;K)xd%ILH`5Gw zDm=&-RFEt+>A&0jVc`UKa%SYG*ke87x3k=&iWbkC3SKriCTq=LyDuqP%3D0;fxh z!zUg}E{T%#uNd!^w$(j%0}SW@23bE9WwP zmX90fR!612GmA@peHbXc{&=T}*9YBoX_A1~kIlbqF0f=9@UOp~sA@TsK{D@og5r*{ zI)j_d@3#!81QhD?n4jtP+QFV|lje1Q_Um^!kMm@7#2L}N%Cl>%6;KU|2)$x1mNb@B zy!2Ye{y;C z76+)7t>vXm`O+M+?8rSRx$|ZgkLg5Zi}1cQRrQtyo|xMVZY@7r>|bSDRsNB*Sox84 zUH^0xyTp59uC(E3l4bD|+B}!moGn|jiv-!5kBB5~+7^mzrr0)wNMx57Y+YVXnr2%b zRBibDc^F-@**}uY6Z#@1%-#sV2Z-hj(sX}JPWlH1?uX=}!ZLefQ8(9?AX=SGZifcH zF>gRGZFuTi4*3I_^0JKuJ}46EFhS5un!x%O0`VMpDEJsL7*d;=n|B)yKu;F0EdewF z0T|z*_b?5Vl!K`|2}BOLj(~4#Vas)W8uT}UQ$?V92$Uu%{rj66xYk1`1_{O$u%i^m zC{@fWA<_X#!V3L1ph43NU0R`Qdobj}Fy;^ig<}OR0_h3G5{cohVJb`yiKue`Sa09z zdR&C@$Vn7V5Jr&9^m|Mn#8lZZjpNv{yXa5bYuDvs)CgTtzxz0kqm$FLjlp}R8K3|Z zs_agGl;~6Yo3@`^JQt@vV6V@Z(&RJM=f3qzu8YK7hX0SP_kibm@85tmMT0byRVq6X zqU;7jG72Fi8QIF7m6WndBr_2zS=lQ^$cXF}N+j82Wj)uYbME{8KdYRh$ z_xl;|_w~NU5#zCCiHiz(r<2lbw1ur@%(SWR1~AQy#NKHCP**%$Qr)!;)8$qh^RQQ{-i+Oej6hv?^ciOY>7mVWV6xP+eQ?`0YIE9rBVOYtX z^)Y(1*z1O4tA=Xx%iQ(AUodA7HvL%H$l)X5@LX-TKf@9B%&WU7mRzLn_-1Up zxjfCueJD1qE&PSNywdyDP8zWV#vFx)!K}4w7h)Y-A8ijkQBrwj_ta_92K+$r5Ua_u z*SITHh&oBGLawy_n5p&A6#P__EAv0EQ|Nj2Z+5XC`xIGcoNm-<9L>DUw10U_%VD&; zR@3)Kd-u5u=Re-fNT@$}Aoy0v>hd#AHyhrl-JxNA|7M4x#T1MO4`2Sxub`m#L}2h~ za7f5R!`wh+b)Dg0YtJg$_UWzc%1#S+h6qn;{cuR!v|;(W$)ljm4^ZLVMG z^X>ekQ;R3MY+2r>*!^s0Sh=*vL(kQRnP+;=X+{GR0kXE12Rv z3=5M7Ig2|)3hD~XfvO>$Eyt*e*v})vE`22DGeCq5n>S~DD#ox8H@=UL&m~~KAZ9Y( zz?KaM904(lERYj)-EQ&EKLKjc!p#JA>LQwK$b-Y*y^~&^PW5~UiZq1Wl{GbmR#8a6 zaVAoBa2-#enI&m9~@mriU;!}%9taRnxvQwR9x0ApSRhE?8?kGZo#ZYScI!3YLw6>77x5CTI zD+WVnT_h(~Bl>-O=Qkmxa)QYcqKwU_)=xxu2$D-59_1vt3Qy-#oXbr_I20INKyA7 zpIRE*L#!;C^qQiMKW~8;)?LdY=AWRpn<0cqtSKUym~g_~UMuqL@-;d{9QA%5@vXmb z+$QcpXNS|-lr2Z|L?1+jmrgtpTziD(L)ke#6GFp^4VS;K$oAuIDK_Ef?_*J1JcklX zE)@>Cg3_TEtw)iYm;Wv1`lXLC#r26M`fi2p?L{06H~e^bBUW*9b6?2oqht`FHt0&o zx>#FjT%H*?U(8yX-e@}4Iy}3o?X5Xuo^xK|auwrmw>edA?y4~1?@v#y6nd?4XIb;^ z_`r>bq)w%wwj2{Fjn~V2q*mTUxZIrP;^B#N41D`qFNf|%t6unx&_ofr0OlVRpN3A? zolgC|oGX|}>g#99n+%6Hrmjj8Gv???T?)uyKVz_zu*bB$a7SwK zZ1sHTtAo&n>CmVPWP6?P;laACfKS;yU*DwqAzRCh;owRWk}#IuoysdEAhSca0GA0& z^db0x?~gw~oGSv@g$6u{aOfbTy&K?ObqKp-#I=b2G@;8s!~3whmZ-Iy#Sm8iMn zJ}SSzg9k$ru!%9KIjyX00!A#00PJH21Pz~?E!$Ho%w`mORwj26XK0;pf!SZ6R(B~N*YAmki*bJ zm9)0fQ-CgvxuP}0Sdx4?bXib%UBHkTWD7DU>ZG>7bq>b@RPLfW!(&+rRMD^dE(U#X z+^}h)?5z3S^u@rQEK>o7_K7J6aI|df3MB_))Lz;+PEqVF=I_bhe=*O;*1jUmYHszr zj%ghfo0g4JlcTQ(&n> z&+^p^QBxzGsZrt$$B@Vhh4f0Xg!a|tp3tY^R>^YJKawpPwX-%1Bw9w~MqUr=4Z6%g zdAIGY*xRX=%+6PuvsM!Irb3I0)mC_PIIw@a<+d^>>ojJ+&vnX6Tk+9{kR=w*>0A@>*p!sB6>sNrhE&xt$7>|nh=_|#Y=XOSBhF038_wI`0ZIa%D z_u8N9e>}h`^tnT#ZIAeeVS<5xuuwQ%0c6N{Js}@wDji=UE`YH*RA)~bR_HOPbNI( z!o|fT@*n8AIc$o%BNbSz-!FC~>UYZl^&dwZD~+$j$7v+h5882tz(AU>^D=G5tjSs3 ztIX$(B2&aW+B?4u4AsRW94Uye_gC+o?ulBRZ%6Zv((W2o{58L+;n0Ell!#xu`zCU=2tR%Dkd49x(=ba% zLo;N~6S^qfP$^Wqr|9Fit_r7#_QS2bQ^ufQO6+r;oZ>5(H}c#RB`WTd-c5!iaUDJ|IfZ~aT7RXylwkV zAGPTUfmAcGp(lsAu5xXsr&m?G=vQyrXSaAYd$`SF$>vGYsG;PG-5 z=GGT8l67Y@12kjz+Ghn#dX=Y2?_?cZ>{&fIc@5We_6LQT{$ZV#bX%Kqe&y6}uD#hn zWwlzmv0MqN8;ij1s=*A~gSu~@81byQcCFjRr)(WLeJE1VXW%m|n0*6ERIFmOwhif~ zZypjkz$X>xPU&ILS<4v^ee{I)#Ge$+6o*a+)(LU;M_JzIPupzslikntGW1m;>NJ2rOxRr|;S+PW|v-YDw?<+^23EUY|p|2r+X79Xn*A{@m?z}l$Rid6dS0;CA0y`LOciMYx#S)b#3Ox4RFhsBi@v_YQcr~ zd3^jT8<<&0E{>l>-21u<1r={YGBbtH(~&?%a2Vbc@o{iaCTsZWc@9M^G76bWgVsI| zyB{rB{K9LRFpE}}#yr()S84?7DEOgiB;zMIh~3poCCSerE$x@nG0LC>2a{MAIB2Gf z=qqs!PPsd)%F-JC0Cn#2Iz%89VH87HUv|#*$ zp=ZJ9-gp&Gr`J7u7u^<*+4WIS$kEHR{x*I;;LCN0>xch}$jzGJGjHcDwmwq|M|S2eiC;zn z83J=2pC+-hbwW=wrDW!gPWxmjX3OPIU+M^^@o8TWJeN=;k8ASaqv%0MQLEH+Dra$zuzv;XP;gs-!OR!`p4C;&=4VfQ z*$mE0|I5VaR}(`M3x^t(r=G6x0}LUYMA)R&=~x$)5q%bX8X)o6MObC2TFY zzmok>C%JGCK3G4#zW0J&wV>gx045fH8Gb1jD}DLip2idlpnhp-Xm@6+|yIGn=&Z9}I}{DQoQvEcZXr<~UA|+i@V>!;9)S&FgKH6)T7I{pv5g z&rp`~)U2vL`{`u-otU&=jKyea2@$q`_`=5c=p2WvpL>RR7oI*C(NQ$CDVBr^s0-&p zsnlY(e#;(KN#T1w$1SO>)KjaRFMG`G2+@|8P8)My@Yvxvvt6-R=ZsU5uy{ui&Gms# z--gPj<~=5~MYD&_b4XGaQO?F>X5Q9~@XX`sk2)54LpEvOWaXA-hp0rQjDT}ONHG*m z_osPlzO<@ixoft+kK;D2`qAPB(b^M`Sel=5U$NL1%l?$IPVc4bqvDuR{joXv_#I`1 zGe7T6KFd``oLZiB_op|oS^J0rEeyo)lXosk^~qXU5r%lCeKFhZIsc?29&Lgzo2%IhW`+-l8dKs-*dpHys3pX1bGxwv2N?OMH$`$^2f zYRyFhyZFJ9*su35NXw{hQs+NE$h&skAlC!hy&+9uSJ;cC_U%9XE>=;Vy>4MTTyr#1 z=f{_U?y#CKh@7`->mA^Gs**DEoVnnJwGaKyo!riM$&kqLv}r1>nq%Z8%?5)2i-nN1 zZeBAs7w#%MrcU?pn}#l`mW7_vo3@zUQG3}tW_^a$qoew$8MCu}L(j_jYaIPQ4VIV7 zgBfeDr?tN6ePlhh*;EyO=U#O6;;rS^B~rPRd;*No|iBD>w&?}zxyc5fmFk0~uG zg3}vWY#E`)tofI7ir{QkNy)bwu^bW-T}|skX=AftkOD>f*o9jI4q9!;I={?DX>teu z9%&Aglvq%G+4`(yaehyY9*ds%bk4)gqwnaq??^M86}}j$dv#C8w_4^4S=8pPo6DTp zjyjw6GeiA%;tOlGHscA`BLfy@?B1I9+cVhXHDU*@8B6LNx0+oN$@H$e6}IB!E3&-I z4pZv3PO-&7%S`jm=*>OsBDsdak8J}yYux;2448LazpE{`=0dxf&CIm}3pGaJU!G4t zCQ$Gx_v@CQud^;QLTgMu97qMFgh+|#%#fdio-X3Z`yML)0@sC3eM3uUeVwtU<-4W& z3Zp_-P^0?oSt!wM&(=1Sx6)YE&zA3!H}-hF`PbP)9=BmQtAF1sBYEu!AK7ueyRHkz zJUEs;nZEq4UYUuCXHcN7zG3#e-{nO2Vsa5KQ%edj&o9UKojtj; zL)7ol-G0=C9%ogHzBuYcRWl!}NFA8DA-K$2IMlza@p$_=bv>(Jw}3dF zvYfB*c%P?kPIbyqb93|QjnNAu+M11<4GLgdM;QbAGpu9;ui+EMpq&R{vX>o)6DN26 zZ1J{`$$6`8yZ#WmwYK_4k9J;8%6cfh!JynCOW0rXVUm41rCE?fyo^!sMcz0yO>ehi z0c#n}6yb39Pm-=-JOfihmP@ays$X*RhCG76%c=xF1rvNQX#Kyeh-N>W>#+wn^}Rm^ z0$0z)u(w}_ItETBoLpQFy|_N`T6AO%Mi(b|r(Dz@Taz*OefIFK%~@4IZ@!nGxl~`V zakt>`VDXnplYwYvA?p@8z(@BL73XZH)*l+sD{m+Xs{Phw+7bU|95Q z#39z<<%xItR`XM}1=d?7I3NG`q-`_NAfp#08CEJs^ZkW=UzzQrT}(QH!k2$|Z%R1h z>1|lN?1x4t^=!E8%Ez1d0pm5RsYco(jhPpRjFwtP=4S#Tzqfv=d@SuaLg}Au>9t$@ z?*-`J2w%)yLZ+W}-ThaDX%|LZ`a?8PNnHk@NYU2TMx-P}#DY~kkN&j(MmG|MWWasG z)rvL|{hxNGDco5%;(n~q?@qzkU~q8IG)o}3qKiZle|$LWv0=Aw(5-8)3O8SPp*}4t zt^8rj`%nF~9ILM#(%<*4n2Ms)(dvC!ng5gHwpaA?KmM9d8lRmm?e4xg*6JoV_2BUb zi9bh88f(+8R?CWiDN4`DND7^J)xgNf*J3bW$~$%l=UDF+ZeH&F_6t-^EstYVzP6V5 zN-Eoxmv>WB;0Oq9xc-u}*}zDrxFA}0_LHpk?ach|of0kwL-e+~Q#f63*%ZD`#H6yM z?xkfS= z?a}Jq@b^gLf4(j-R~JSl$Q`8tYYGd^nS(m@KU@G35em`6i(>eeRlrk`1DL! zOZns2-Xx&;Y8tAtiCdxw-`AYsR?G2faC)YNcY5cQ;f$=mkksGBMvlqjFFTblTbg*A z#4zq(;k$F(&?PKLj6y@0LEGM3L8F5$qpfE;qNTw^#j!&svo|laJV^h6^&i{Wj-d%4 z@sC?{PwbkVYy`KP-?P4eN%Go*InTnH_rYs|gCCDKJ=l6dTN?-o&&}nVk#(YVAz!L5 zew3`6QZBv$(BpGyAT3jq-_tcu>S($Ioi?lhcU@$u8Ab?;1t z1l<4Ff%iNyJ>8$xs#gkS3+>p$g~wkf#;>zV4R9N2Rx{dBZ1kmWFId5zLtgBK383OH@{gir4BKL4fg-!i%wX>kFP4s=d?JNDqd*_PZSd^LU@|Qi)dHY*m zUyZWVuuS}`t1=#0bKGGAf~JkHEQ|cgLSDNGcoa!TSSj@@5qY!EdO7WJpU%U`4nL&- z_9936b$@JeNl8i6mpZrX1EF1lz@g+MjRc6A-+(QMFAQf8BT~SmM4vGjA4)L?hX_*4 zf~D8{@!@_VWrGdZgb!E zUAHjf_uM&SXTpF?WFF)8ULAkpUb3ZbFAVD|7+`@4f#FmB_?c=4?F!RTH=ePEDMXa?pR#2w1?@G=@36f zufAKzp(Rlj-6iYwr?&Kcd%KjLy^es&_91Ih+rFbB<;Zc%$b~r=fT8eSH+iPjUWDb?jExZs8uGjWu|9sN(~(5Oi(; z8D%kiJ+RC1p|7uE^5_m2=&YK9zX(wG{YYrLLHdt@feHYTFgIZXuieS1X|YxTcEA6! z9Oyn5pdB$HHcPYpS-cdHU$TBG@KlOMcxm1cV~F_En%wHi=#`jRxXHDkr=U75J4N0q zSo6Ge)iDWml5_!G&LfXQPhEOd0dONV&6gcQ(jH$lEHa zpfTTQsi5GzX2QVb4x>m3X4}vfqC)-P-u(R2n(caA20i8HJ7%wXdnqmz9PTUje}Dbh ztbnARWbw*J8wZ(ZDk>Mw`_!9$&1&5?H-CY9+2dx;nNf-wS93|6Z|fzNY003~MTH6W zIkQsQ?;4C0PdiPhFVD=SxzNWYIkPc!Pi|B?xpb8`8IDFLHq_IqE7Dl@*6tRz*aZhm zBivF6EpxrK1;Xo{Mc?dtLe&`zW z@4E2T?U-C(_tVkxkXCl_HM$ej*9J<$nC@?^X1KW5GTG8h_X20?3yOCNhGi*5V(D4g z1~upE#!r3e8J`?~mEjSuR~OoIP{c?kgqkgyC3^ez7Q5s(hOHV60=0+TK7Mow`+}qX zdr6pYuH@HS`aYqB8D!(R#JKnD%=Ap#u^__2%CSG^eREG&bJTETk0|CG1QBi zh6%1PU(~(WK2fTt;Wo+p%(A0ds~GLk6AsF-KknHoTA#DkIdONc9&d?UsmOksoo3to z1K+Q*@}p4?4Oiw*hBG;GozGON;&t&eL;cVe(Ivwp6cs)YXQT zz(U{oi;_=UV^+5xNaHeTtg~U86(~2`Uog9LyJyWZ=XON-1tcf)qG`HS;#M2~w9ItT z{l?2zuec93n{g*`AA9oVY1JzQ96=xQerL?NNJ(pHaaAa@?Em#mPSsopH{z!CYo_Dv zhx(_S`;7X(V^=FbV5E*OOus#6jVnRPtC4Cdu5l1*GP(__e3_#i!Ea9%*iL@d3K)^- ziuuLTKEUcRXUkln%oJCpQubxt*tkvcDpWVr)EjNC+sh?uTt75&P|9llW>r;>j{MMX zQ47lv&Q#6;?C+S@h2+BOuSjMbr0Wjh$qUt5o*pV5v3k?j^a~yqV^=-8 zJnz)5DgC*toi4=N?LDFVohp6)fNXVP_zc6yX6Tcn21#;(FX?nTfyB zt5^3yX@cLqm)gq%hYk@~AP91v>MoCdso)Ab-|@A{^Oow$3*LMOb(cfq{ybWe((SG$;+K(ea!WW6pOaZ$0#Om z-7VmV61DsG?%UGZb?di{OH)K-TU`2lGLTk~^Rd5<$5$Y(7ql-l94Qo|nfvoFIxGOt zZzG=>jY4yAkMynZFU2XM_ooy-7M%C-_d3FxFC=4W#5%^!YW2v=YYn7l!O~A&_V!-J zpoEP!wtIu=pue@v_RhEMbph%NRA%1;mCpsb=#NRSupe0N5j*45uXR6VXMMUmN4JN& zFvYf~u3@Ae6X{9an`ys`PkdHj%=5Q3%dgI-(OoVRRXzH>UXClJL7tupCBG{VYQLd% zb){r4=EoVepG;qk`i<;(Zf6%dQXT|kBW&2VgdwFI`umU)Zc+t%E`&O7X%pSC)e;_>pM-fZg|-gAjE`B zIF7ynR{uG}L>a=3F&$>BCtFpxcL-hmuBd87rDbxBvx=v@y_zawK}dT1x?yzjV4(a+i2vZ7{%vw_oK|6cO$Bv`s`MljrG%~*cR=a-W_?= zsBA}{{=pcAajMC8%@y*Z=XUfezsbo#$g9d~g9Mnc{PjBVaVaZNlj-}Ma%D06(@lS= zN6y^72?jTFoqL{cl;;u)?6T{wb5#yci2Ea@aDGK@=wRb38FS&(cGaZe!L4=SZwqu+ zmPV=ri(h7Vq>dI<9@X%q8_|5T@#ysf{=dxDeS2uRVQ~8mHMV326!EE?+}!)%dWN9~ zFk|au?jw0Hw}P2QPLy9>z4(i~`T+;JlOo(aTwKqdKVJ)}Heo#3+ZQEYP1fL{)NL}S ze(o!5I{-HuUtF4Sx|0DO$F|q;W0tL>l@aW&FksF-n}^KIgU4CEdOf zFIrDk#27;l0v&55jeuZb3>h*?OW#;~vPlsQ^@R1ePpJ#FwpTh+BhRXSZLMMKxugsY z&I9`&bh|m;@SoppTF>Q^EfHbx?6F2YjMD@$RtA(#NG7tfvdP6^VPTL_UNSPWZ+w0l zc)9h_x{_EAw;2s}^)8{U_TNg@1uz{`Gtom17aXAG=I6gbI$T`rnOqDJbX(hLUlrEd z&N!ueqa3>pusD&UN8^2BRFd9b4!0oU?F}$Knk||hvvl{mHf>+h+ui-kkmP1FR(t$G7AW5j08X4AzKyvU6S_PrWfDe6ik z#=+Pzv*FoQF{vhv$s&yntSN|_`407Sq_}es-n_NR9#ibh&Zi-H||9UlY-!=!CJ#sJuapI>VUHUcQW4U+Y)8F3#hrsi%f40zDP2nYx&s^I!%Y0}UqO(}_9^ z`zWwI)&BwQIGH9-Ie6z{aR%{MyG{zI{MPNvV!6GCSA#7#}-A(SUZFN4pT&6MPQ$Y;dD zM@s8~16I<>8sEpp0*i}RltS@9lR^&aK*9pMvF9&d_`ur?ZWmWOvy-ppvvO3PTH4Rc z^Pwx#=GzIN$%N0O_2$aGwWppG!5{Xrkx?1$_#qkhWi>`qvE(BT+WLz+$G^qzyT-RO z$T^lGD}*h3OG}$*TTJ>xzWtteQqCw3HVY`EK8{QMY&c-*TTsk%NKZTO=iU#x5W6ed z*zkjsOZ;@`Xa&vqscX}U<(-^+{}IOcpbDoUO*%{HyPv~`_` zK7D42Kz7qp)nJ{Pkd4k4^B>4*sqV&F%pC0Y1J)7GD9m~)&K`aS5II*vOpVA#8c248 z*>>Qw0%&K2S2gi?Xkp&|Pv8VhpHkJMLqkmzUX6Uodj$7G;!25qMm)7(9r_HT0mxkC zY0LCA{ow;O`U(^mL70*do+AXYJgc@E4~1yzv2t+Sg^7Q2gy>RTu?4e4=24d>KYdlF z_$MXRnt4xbcY8f!U=-WjlHGEl^XlgdiX{Us`PU@+*+i=ptGReyO2?~R9=mc^^MTk| ztC^stt-UPHKcC$t3@^-JVzEf+9;_e6q9mSWg!GBkQ}`~MhPG{H6-7g!(L>vV5lvCW zv8gXg%Fg*_+}(ecMVl$o=;DVV-A{b1D{5QUg;G~mbA3>=yyv*hQS?+cYg&lNV+Q$O z8(0~h!rcLO493|O?Iqx!Q~Yd*->6&QU<7p>H0QhH)jT}A`7nrpAwno<3gK0lo8tKx zLJ)O;jSXD+)K#Bh>4?B$MaZ?G77Y1%uQO5QhFv}T=$jB8O}c+FIDzm!ys;r;+nznd z^IHDw*%Zy`{J7$4%w5B_c1d{|XdBQB-|oFdcPN40KP#WLkDMJBlOBLN-YUiEnPg zWDf)M{V+HD(9xm2dS8u#G|!&Z+Vd1DcJWW960dy(-1ys4>-=C+nqy{JZTn726EP<2 z@ax$!SATTb>`F@Fs^sf8J5HrJrN~*y7oVH9JtUsmQJ;QMXYTVz{gzy(V;_|Sfy*W$ zq7O^pVPs?t#+I-FB2--QKR@FNmu5N}=$@}q;SM2sG~mDCRS->A<7uBhdzSql6*7h= zgK#+qv9P2;t^DD(6JPXOT3Uc(-Xk2nHp9S)c9W+D<~)YJ_wS@;W(I@QtD>v>2{YJV zUG|9u4vcZ-vi=261xGzI98Uy}axH%bdYZ89~n2ji^+}3K$Z;!LjNVK25L~(zkLSAH8MaV|) z?S0#W9EQa;rxem0vrFGs?sPQ~8)i0N7H&#+t5UT8tBJj!VCzApxlw_$manY4eT$r? zYos_c6$-w+QE_U)%Ym%vzT zI|bez!6`5=p6Gj|OvlJ*?sDP6XyWv9>u0;?MU>SSgKxeBz;YT54AoVw4&m-J3W%ilYm zdSezUt{vQ2>mHl2?d0|i7sy)2y|G!MV1J`2|K%3~D)FhY3f3`IDl+liKF9TC)I**n zyl%MBaAHDdpPW}*ghcj?Rhy}$iq^-dxD!o|-QC^9MUpHY!Xkk!%V&_mGqsb~CbEE^ z2!n%d#8e2^^b~$mtY)s~Y!_?C0i>w%qGzl}$FKQfWzE2(x7#F2HP2uBWb!m$ayA+o zB^@`6dtasPpB1%(f$@k&i&li%$+S`QG|GWx6WUk2bIb`r9XX`oDgv8kA zx9(q)$QNMVVdT=pun`;8#xA2GHBZD!@@(#WUQBk7ujYvj={S5y_yO^1fk~l~g~h>@ zKdr?!*RPw?PD{Z%7}L01o=!=4>{M1(63GQAu@GDj`nj>~Fw7R@3LHk@tUgc`!t+`? z>psw>C)gf@?E-qjl}J?sFe9F~?y^;ey7w-Qcsjf>JOg;1CajeaI*J3(1n2+++yVwA zw_SAV7M82qYU>%qAGyb8h#ga15~cCaIf zt3O>`uppn;2?X>IP;ttzfI7AHe)_TExU`4OU~ zeL+@UbvF=Bu9_l+_GZY4s{oF#y5u}!%m60^Z@Tzj`NiDLd!k$2Ru1p-EAHAp)v53G zY-WmkzpUXWB|#VW9n|ltWN|R;5Z{d#h)$Dw7pb4B5L6^(O~X$FJsL+^iv-^Y)2${7SOA z|N9NaY=*c}*PlGnyxvf0b;YF*mxRiS4LbdIxJI3lk(mG#+z7sIMrSL;Z6u5mknz2M0AskgY|i(Vg>w`o4ND*X z(4sT@)A_gdL&T5y4E%Fo(pp|!?TZ6>mCf`obr|6db`^*K3Iy>0&BuFu{bLBf1O>CK zp&fz|ybE?`pfeL+Yd9v8 z^$3{_`^~M>ErgGZRTC&axdCjElgS#b3!)-F-}0K}n?KsP2Ie(#bX2&|$~(^PH(W<; z8@0IT25vJU7NgWA)@SU5v-;XKGfpz!Z`ct z_(I?CuwO_B?9Qn%d_IQ($tS|P5{=pdhZ8uiotc7+0jN+6o*?eP2SGt4DDlH!Bu9au ziYu`9CRIv;hA6OoOlW!s2dQoVZjKWBD77#w7?Z%WQ(0M=6xASNgBJZtJ?9QPu3s3t z!Z4*0mN>9bQE-@Bt(dfdWQB&It;5Qt^KR zt9t;}VxIZ^?uaO&fGqF>2xy=QQylp|_rwchBjVkJdj^h0@%Zv!b1F&-F>Jm1e*Z78 zn`aU5d zH-#zM0X#JFN#G!|K5vhpN$nLhxa0^Vw&Oc@8pG$i?xJ0G+Fa4LAah;rJ(6y@EekD3 z6wz?x_WZK!uU7|JX_mHR=4EX-h5WSoe;KiWB z>;0w2wtFO8grrs$1>xjngzq+KP`}~4=6+tMQ$-EX9lV|E-AGtluwOx#gJ4$l_FgL; zYy&(A(yJgnW)d!ipMm$RFOVYkPJcg~&k$URP%Us&G7IuU2?RD5{6J0l?W2#{?!(?S z#KHxz5;i@t8@VpnAd4U=t~3t40yjS>h`55|jlR~&34r{40&1GoN8}?A#76{eSmg*N zBiu!j@&>AJQ%4IX?oXsVB~i-|ZWnmr2#2$1;hn_{0w!H+$T!5fGihM(!))|)=-R*+ zo7<5%M8|g4B{MFp9Mgs62wR)57i^ zLZk5H7)?8~d6P7f2|z6g!{OO7u$W88FZ?s&DT07Q(K?A)Ch`jx7Tw;7P$LtQ3@ifT zzlhu#CEc&#+pz2YJsgUiSC(dRa=r4)Gn54@gB+KzzAsLleggM8;%kP5VK>;|jpnmO z%NXt+sO*IA_XWJzgSk9j)tLxkrCSE&+o`?LqcYrHwPt-9J}>vsReT(4%o(#=0o=y<^PO2*@5~dH^)jpxeN7`XtK!Y5gfpcP8@() zu(zLS#G0(QaWeS)hYPU0bO9s(d5+QQg;FGy9*PM+ypCGsG}Ecldbr5!Jb2+9Ha@Yj zCw&OcsY}=y&{m$l@nJJ=0)F$BgTzn~H<=7>+g!JK0b;d?w$r$vr$Hv-pErJj0_e(q z_}oKHLv<$%Mn8!dz~V~vN9*15&@u&U701!?;B@U%DH>_ikI;C4;_>LggLeoLIE_hd z-=%vCv4ErhHH|vWUlW}9b?fGbu*OP#`-hwSBEm9+(80Ktm=F?U1OVIUz8^~;xeT5H zv^}@*uiZxLB-uY)3>hVtdYn zwphY~Mdi`(F`U;RR@j$6-P)@s2CpUe)KU;8`lP?C!{_Cv#Fsak=q-bSmhgq){O*q* z5zT%d@+}d}a{5-&X+X0R&6@g$0klKLqgCW`1okZnF)=rA7an=lw*_Rhf6lnu6knl< zMdFzJ-kRXh&{k%paSGV@N5JiVDLd5jA8L$%J-vyc;Ys+t6Vqr^vDn2a_005$0tB3_ z!s#(4rI6Gd6cOS3A2LiwapnjjbP0u%Sk0gTae@~MF-t^D07+}WHd|u@>+)!iKUb08 z25-Ot;E_NvQdF7m;w7Y;*6+hsJ+Nmd=7M9|Ls4jG31UeOGeT5FL_q0{Rcm&^t>{yP zNT_t!Lu^3wzw2Rz{tjDJslpj`LvBHV$gj53|2@%ffCdc%LpxL?Un z@$4=ODBr7*H%E10jT-#da7z%mC8MxK44_P0#^~JEVyAeaBHX(qn{NvHx_{p3=$ro! zStJW|mVb_c&2jads}{TnN<~L^D zSFZ(yr4Q+Rq%ugs>4hftpkCnvZ3PxE>cee5`?&f;IZ-R^ zT)$}-Ikx*(ms=AQDx*%a8jdE!_88X=>0?OIfHH{GV5G@HBoQiH+@FWRn}O})dlG{KlkpO+f=#>lZzxO7uZ8txM$Z7O-xC56`$ZQXWRCBq$H@keOOzW1x2+Ml4Yy zwi?Bv_le{1WyFb(75*4MJ<0dgVRwvScRsJKE`!<+OVk=3v7C6Pp5Ve06KpV99|3pn zc>TQy%@B#UKnF&Wi3`6mY#fYN^3jGr+;NDK&(!hh6`CqYyWx%|?*$|ZbnbF!zp1ut zNtw=VnLO77At%hc@>{+GHTwZv5tu*(oyjA1B|NzryX)R_J@WrKr0O|u&rq}4S5P^y zG5`3Otxq-7b%IVJwmTd(13CHOOo#>z_m(tXNSvQH`URjx{1SE5)i8yH&B_NPnof+5 ze?{W~2^g_cFg?RXX--4)`1kq985NIp*ltS(g#zs#pnF5)Pm0-so zLryR`Y48>%Wz7$4r$#OE!4rjBSW%}*sPfm_D-T(8JFC}HM zW@=uqO)yr&JVC--4Y>-xvd}bSklq`j0ARFp=JNP+=LfILiJ%|jUd%eC+M zqhw8oRphzJxYw_1f`=z&X38rn5;Z2};Bo)+rw_ikcJfXho}`60o-pe`>WA9-^H=`3 zy3=v+@Kg&$K{$;6U6q0<@P;j0(0Dck_X&iqL~Qo|Z-XTg;yxolDYB%-H{?*ZkK(Ix zv$E=Dm?Xa>EftK1}bS`}qEJWsw7lJ0iCySy0d) z-9fY)sUb0%Ll{i|%2M%)9DISuPy#3sd;*(XK9N%h<>Pwh99-a2@S2LC6T{^9FV=9} z@I0Yjv#^eChZpSW(;t73nv-A*H{ovQHU)rfdc<4x4#^QwRqyY!D_C0QMbMs?!(+~dlMEhoL zWVDY)w3J2176$bMNyMmdscN6r|J6G)jiLyPy*r~dBR&1wbgRAz&RI8bSc$p{OP!b; zqZmXXWBtIk@LGSB(!h@G+n*!=+^K;$1vCL1cR1(tk}R-;rIlLE0jwlU;k zI4LCwWS<&<4Huvdqd>i8jFTVgy2^;`t&a|M+|JE;otz94-F=*#KeHdh$Tszn8w9C2 zXWA}Cyq#hG7I^Qe6#H!<2BoM2K?f{qy#CLp>M3Dd+1Wjv?O`Opk>cl^%221C$!z%c zMV&tnY{ip)P(F;OUU@8eTdL{Kyl;1im(>px|0L{$@wX(vG-3kAem2t7>={W>`WLT; zjSJ);mG7-ikpyqp4_<(q1F69=h(b-&n5r)YO!kBj1upgrIy&D62f5zUdWQe^hw?vh zRdqLLw=vn-YrR(&@6`M494jb1qd~`1zZWfCAc9I&)zyvi->pEpP8`<$ofe_pdL$k8 z3>Ss4b@v%S6+k~ZU>|?jusjV((FYIqsRh1J`WrqoAGGr4-;zL<)qX+#^~h_Rsq2qF z1n{Tsnc2CM__~r`~;sqlaXh_;A6KU?75v0k|g__842i zvc?d+iv-(Uw{su7{7Q*8gKC{Q&v z(fuUHo9emb3n*zRzV!>z zFkp2`!6fG32V`|x+4?(Z7{n*zAKElQpNkQqw6fh7#`-}(4ps)IBO@aTlM2~ksBkLf z!RdE=a)Olvj@`~9F){xi? z3#R`GsC}?uz>TOPRXw;7sC!}x3m5rXhhUn645x&%d1n&~cx+$1dR1a7R3*=On|6iZ zE4OKXDE>DEWP%Tf$&7iG?CH*JZOhHItI5+-{>8Q;OjC{$MeCxJthT0+kYe=#0 zT;$m8d>1E&04{3?0YIp@jD{JXCOk++B&iV(lo%e8^jH=a7EA-KgHz=(_l*+Bbsh0e zh5opr7=~MVt|Ld_P2vO?0Hi)*=7UiibOg>LS*<8(bNoi2gE4J*PIdhFaT33g;QI(( zbYw`3I~I4~j$>4R5xG-w|J!eKzL+K5yMMnIA{*flgzMagw)z1`oe(j@RJ0hHkkxn~ zs3cys{83j|M+--yUa`}h5zcbY-#;Ft1E3Qj|Ef!E@G5bVDe*c|z}B2F?+N?}QZ8wN zP-CJVScQP~eSj9uM&(#`mSb9>ktmMP5;U=0Z_ZMX2tH(;pzTosOa(M#u%}px%+=sj zBu=tGD2UwhR{wL}{SC?ZyC{1-$1!aWr~8|Xw12-BN%KL0iQWvI9%fz>SQRAi1g*Ey zP(nh28VC@Ab>d!d^8f<@#gYvWiMPvt%yBZyVgh38=x72CJV+PQ3DcM-$6?I@+gp?C zd<$aW%_tfotOhjfSCe;-5QK`Vs{4Q}fZ1B-lAw|XT(rxBz@Z)L)k% z=oLvWMJv4vN)yc9NL2ubYyv(vE@I;%^^1?=>EC^3+H~;1Kfyb_;ji8ZK+wkj^Y<FmCerxmdIt4ri2}bdl~cuU+v@{i}O=BKRyFRY!xe{)YX4dPuBMj zoO`H0rK$NqKk0Ss-aYFs85sI1SkAjPl$X%Od#_W-VhAz%lvx#P{I=oEkD=%3Z(gx) zJ^!-wg3&t_b?=FswJP@NJML74U-dextnR$K`9{biL5TIh^?Z^R{+US=Djhj_xfLlq}NQ8kn;DH=8k< zpI6xN#cLyldWZ{mHP{x9WBGVa>T934+Hq|1+_}&CMfX!)(CQv%-8tiMbdK`Uz(8Qs zQ>iV>M?81rm>${tVTtUqNf<1sz#asM#EtOB5(LRKEcbhcmYPfvK>tbyP}J!1?Af#P znwn((DeKQrMh;;3-2;?&TPdHFmerj*p`X}~@tj0>Q<+{^O<<}I&9 zzi(Z#ohQa5h_V6+whSwG5N`n|WzZwkWy`#mnwe^$RM$}4CrQ3C~s!JP80&Y?s;-uUM+ zH{L9|O>P<9FL8AT8-4A{<6)|IwRNe+o=c1A*X%^D-VDge)TH4owvA2KCgfJjRDT?~WTQ=@6n>PU`RSgwBVw1n_ib=-kFvMs$va2$ z617rxR#|)N?5z7?1}+}%*aLh|8-^_=)wY}qit?`NU`X7_Yim|dJ@A+}-C_2@BiS#4 zPUE7$8Mn1u)qy!mNq)6ZGWCX;ht2&g<5#lU6cM zFz3CE(;RD&q&11?>Oq+_@@PHTi_!mf4XT0tOK!m{b=~fF<+S46nO4p!MQlHvc;M9P z4 zT%Im3Z}oceU#z6jU(HlL|sGng4dlUNT)S?pRM)2 z)0@?)-1Ti!C9}REKLgb(Rj(L^BYV?5nkO4>t-dc1XnT2Nb~tKD^2a;reL7jJvFhd} z5l1u)>7EWuyC9Bo0M#2|2T;Ro@Vtk^2??iDr`$s5#DSad3k};AAsjTlWOmk~`_v^1 z-hB)r&nhi*wryv+rl1_z7$l~d8rb)ebZsM33=7yNbW)(IJfaeQx|i|eUpN7#lIj$BFB zQj)e4s^`@S`aI8YP-h6UCQF?XH7+}YH?YMyIV4MdGH~8P+dOi zRWbd?UTn51sg<%o$_A?O*+kvOgfk3Fd;N#>?Nw7&^q+c^d(}zQm9(zZPIGb54~u)e z7rq=J#Fj08PT~6XkL|@zE%}u9r#Ue9S{2@Vkv-D1OXk$64;;HUF~lmJ`k=}6em|b& zH7ceBhjoJC#(fQ^hQK|MUYbmb^zj%%F+h=JQKBgle(W3oY zcEYGZ>muKHj<&nN%<*qq*Lus*_M}K?y>vY~UU_lG{Wt6MpP59B(4nTIw_NR4{Bo$2MWwY7ii_XY_6D^+|@B;%)T#au3O;T=S|;U^XGt!$v{l2hRKM)+TEU7&e?TyK|>^+9hmpMyznEGV#=H?}rWh z=7U<~&ZzCb9K`VOsqF(lHs52DPgC>EzFyj=oq67H2Yy~u4P3muW&aOdUmaFew7h)~ z5fucLMnVNaX;4Di0Hj5_k?u|@1qEqokW!Ftq&uV$q+1%KQ$p&SZQS3ze|+b8K+geo zti9H(nR(xLX3A2lWK{aVIYrN4>F=Jqzv!o*!hXn>dqJ4y!j=KUoY)#-}A zw|aiep2u0gTKpuaB5iO+IPogprb3uz&*4&Eruwy)q82p`Q!~v*qlFi!%*ku_ry5ZE zn}Xb^)2Qt$LEmjSui3B6_T%zXS1T~Ct&GR;;|9`juzB3U75H-PG`^jDrs?xZ()~~5 zye)526Q&|^)JrYC3DVU3#GyL*g`IG`N-*zI7PavGfR@v4?eVtPrRbCIhmk_ZeQ$F` z0`^~!NlWT=)qGEB>X(GXGQWhIn{nmMn>8{3oAvDEug=0OXe0q}+aFIBlt0solHOik89j3aDQAP;zFmLjAp(=t5zIwas&U#cwPXUrQ8U4%=~Kz~rsbd7_edAV=T!71-YXT2PsW%} zrw8waYRWxcHRp>u{d%#!p}vKlVKz5uE!82?#EL7<-*r*1TII7ByJ|6N;|rz8Wju;b zuT`Gty`O_*?Va<-Z?K^Mk_(sJ#o}7QXT7*=?v1|fDLILuP;N*}d!miN<+LTi=-zbD z<6`3^VTPO5AY3N_LIL6}`TP6Jo>0JlK=ca~ov!!zM*SK6B!kgkBbx{Dm?D?6e9{1s z%>!qkcK~XkLE`6;ni?4tD+bzB!WJhmV4&P7J4Kmo*eKW$<-aRkP$c5myKs2D*YSsX z-&_ALvT82M;TE%#b^c_$QHedzIM%;^^}DNIpw%d*?{b21f!2Ayu(JFLiv8ikG{sCp z<@@)^I@``nPNg$%ZS)ak20Bc(1ZUWhdw;iUE5jkX|F9`v=ib|(2Kz0)oB>HvO@#~b z3Dovgfw3w@!v4ePt)-*!8cJB?71y8WAB3=^c=i$Ol22Ab=b!#jYknGEBY~ zvVZbbMj2F}hb16v13<6l1*Lbx1AYDZJ3cw!iL(H&f(6+_Kyqj9^w=Q zKH!iT4&@;+m9eSy6bbh2c32THe^-QH&w_hr@TrSX<{{gZf=l10h{v9I8k zRHWZg{Y}#cua2DBcdFV?b?;sw-Gy#wE`{Vop-tG; zs|H#{D!}og<>xDnqwS$Z%_4YfmCO29MiF)n2Lm0K|kRDFx^}2Z? zG?WKr_Ws`d=bEbe?b9P7n@9$X$)#V4n_H#%g|I2Vp|8Q1gf<>gd;Np4EnN$(0)dme z@qDbr*e<`?Y$=@Q2-e*7Z(f?7*`Ezxyl3+5rT!&S7S|)L6MknLn@FbQN7gnPBmxuy znc?2+<)KN#!weclzI~pUWveMMj_!3H?dAN(4fRi!hW*qnj?h(I_&l^t(u4h;6y-at zYeX<>b|U3&0PI5p&=(yt$4FUmm>oLzND0!!si8S9bT;UQ97Kj5MUXdSwLinSAvqRk zNP{CNCU$YW+z#^m6hPLYbKJ@#VVUf|Y;Ew4cG zvX3)m&dJoYw^)A$drPZ+Pd2+Y@HN`C$(5q?m;=6wdm{$VUzpPD;FhGcRzXJ`leM7QDodF{Sy;x1vmi?a~e>4Ib)LBhdogHH)= zvn$lx@_peUhYq+XWZZ$MkrA;9@^Og33rvUE5R}@K;~GHoA0W$&h@kx%6Kf%Hq2`lt z4gbvV$Jwl`*6}en;__(LfnLH`@I;D2rUKcC{{7BrZH%P%zBS3X1P2G7I^Wm*qNSuV z8Q;6;yMH#ay%CBe5ks*sXn=~e(Cf=o41&f-NCiHClo~~P<^x|4kBp4e7~Q% zWI;K1kY}{Cv~2ir=V;dO!|%`nUuYWg-hhO9Lx);~od!(?k>f(9q+!l_@xqPNZe+y& zGx^diPx*~G%sm=0z3L2mKe19uItPPekfDuMGkLjwdgjhhm26#F$`MqH|5kyEy44)` zZui7lZ0AW)vCDzA7Y?}?r0bwJ;Rj$yA^QYSz1aWF1Q7#pdK(!k)J{0 zpA9s!NGnqaVu0VG_zv;

AaV8zV0rpM6;EhGoK!D!gkXqNi))a_KdfmF~v!-JQ^D zj>*-Gm@`q8L96B58*>us^Uka!vk^ocE_^-y$wTttCTEHDX%8E(25vf}z2OqWxWWUW;E7WAzayke zSn&|KA)F6@yO7qC_G@FJP?z7L>L(#Y&e_GAzW)BRAcmNMFQgALBwUeUgNKV;4NS8e zTwF@bC`FcWPm#x89MUntfq472#bVN)i{N$p>-*PHr*AhViYx>ruu%l}@5{~3KMjub zJJj`%m>onaL;&Bn(r^K|G&6ALw`gd*z=p8`+bZMn8|GUMC}0n?0$&~M^E|Xlof&tS z$X0<&{uiJNBeb*xw_kUVcpjoRWGtZE+}5{8xN+85Fe;GC7KDu*ilDQCiWS%mp-_() zKp0`@j0rIuG+OSW)h2?HLQpLTRu>kMR|IAN6=Y@*E&_lJd{((ne|y{Br?k(`!;^p9 zneaiSs8yq6mvi;*vfn}FeFvsP9CDfreMw>L%5ahOlLia!rrpAOC;K~hvrY{=@0ZZu zW}4qr)X-a8Vt1_4c+Y9t(u?b#C>h#Bbc=s=ow&ZEHPlG$Gz05JeCo*wuKBVPo+KV# z*RoanmbDSDDVNNkZ5hMpgft%>LdW7G>ALx|D*AD;`J>&G0AkeV{-72PvnOP>*Gwkj zKB5jvp>VW(`$9AHB&`J=1wsaegwV}9cUn`I7mG*DbpYQ4i1rEzNh>sRhAbr&%94u= zQKPRo8^kVw0KJY~G1m6?G%m$eXTzrG88V5t3weaATCCUc~xAK|+i15RPjS8oTh z%jSP_in{4CJRp59$@FN#{ge+tOC3lrA~YMM1^PlLk6?e5r}03RC~%`eteK+%73!LR zuy^StbXU%;+9icG12yq~`8SV1k6jdC7APcxiQ?U#^aM1_+ndsj_$3VGp($@@NQfh3 znvuGtfGVUyA`7q;Vd*^jw`iWy*pv)6Z>GxrakY61&SK&@%t-34jU1nv$0#a&v4QYH zq*vpUSuf4La(1CnPn3~P^Tv2e8}lcHlMVD$bIOO07fg)CQYo<%-LT|#hsvg^51rul zO3jC=Qprl{rzT&uc3p8ezVujgG@Pd?Aa%?fQ>!769J_k++_bh1D`~*kP&!q^;U3kD z5>0c#XCtfS>n9suLXlseM>p4Nb;!&NJRDE?T3F!<%~vN{;)3`dd}qFT+v3QXDZqTO zp}%BDuYN)!ll0u|C?!Xa@i(od-O^XyDb+7~=Q2hXKI^p`4Y;F^DE5V0kx`Grm7_w~K9|y^$K1*ij|A)Aswq=>hYA#Y7!tf|FN~YKhF0CCjga zJ6|;2sgQ*d%S?1y!^#_~6T>N+szZCEt<(Q4Gu{6U)&|yvTUp)xwoVJ`Dgq}&NACm>dEc^4Gp2j!V(&@_g2#%|!#0Qn5X`djg;L-03f(YbVE7mK|1Ri-v8$U7z2znmJfb z3;yI@^m^mlQ~PxRRP8G&k^SD;g{b>Z)^p`~EEI9O&-&S2j*nHUUAFCtUA9;g+>R;v zkGt47+_zYh%qs#G*K6E6xA_m6uM}E*_jl*t#=gTC;&c+{9ugkf5HExkwLOi+dr&gC z|9qj-rfH*QE;ZH0v{!g(%rTVIkv+n8kEOhtN8E?JY$br?t{1QX^8mwvFvY%6{S<&c z81bv%uQsmQZ+i>GIt}#zZxIDg`U^Y}F3U-j)I$26C^T$`wh#x@pbSO&GR>#NnAhun zW(9^O(m@y;sWjPC9IyZt+S5Ex;0QqxfarmU3gRslQGa%|zsZ((jK+b)R&?Bua$8mc zTIb~0);eg}>hqRsAzz_mpU7d{T3o&>vVJ-w!%o5P4fw5ieg}P{bi1nq0lB9KI8)D` z<3~nJudj>9h|am?@^S>$1ePZ>PPmHrsbY4!)MmTnX+7^3IHpMot_dXdX*5j{5yQ+e z8}~}i9L%$vD=9SZi3(&?fe49&Zx$yaOGDDih{T4Fc|P9FHJzMX$nxoRcQQwM@Wk~R zy(kSwt_Qn~mp|u-c3k;Bbr$0+Di31QU-lJ&9Fn9uMM{qIuYz5wk76>ccUH!txx2f+ zJbwHw>-nR#wNcE_?iNXiU2fmSn#@`_wy>#I>qv5#kbIdy`Ez+7d9Y}3YtcO-?ygsj zoXpeOcxIv=!yj?4?-^&EW4cMyhis?7!36B?1{2eoum1zc1xEv?5=d*4P}Y{)#A5;a zmLvnPi};VQfgtQn$ixo=NBGX@H~^eb>wXicB~Z`@D$Sz-l8!W2fN&mB?|^%ln?~H+ z*q9F~Zh(~S2BucOINbi7x9Pa}3h_M-h{pNf6m&=we?5Lnb9_$AFA$oA!;IIRn~g25 zEUb(TB4nOgt9Df?HYe}Z@2uD6=w+$?erL4t@nfxf@h8r47o9P1CENnP3YQ|IsHWm`L;^p*y0V;LI?au%``=6b3G-tBY(asnU z8p!fNYhlhH+ht^+E;Wv8HKg8}&ErYYR9heJJQUZ+jntu)VlnQ~^>0dOrdjMQTE4Hd z9~uH<_j8!GZ*j;+g>y%)fiQSt6-Iatiu_GONjV)5^B9cHZ+8h8072e#qWU;CSF$=o zF;`>Z=<2W3!yiYVfYAdrx#s*wi%kXtfypBO)j(HQPEtfjNPawKL2MohdWGB)H~e0C zA1M(Go7*5>zoOG`|D0d!Peg=8{c!@tfcDBXW*beE&-u!xCTElRaN3nck)Q%vzBu6v z7v$R`b5*;r);m8y4#>%{4GRf>1Fl}>vOeO9TRS>X?5L4YI_kM=Q7I(%)zZG}^b7=l zhY4}#Yd>~Kj9^#C>Co5InX)}+jVb&2i(+N0B66L>B1QGkewK*vnTm!+fA9QLeH!qd ztjg7PR_)0xj`Yr;m`Y*-cpR?aU3p;p)zS-^>a6n7do#DwGf>mhMi%;e>XPv&$me)W zYxe|^pfJRFwNo@Lxdn$S2geBV0yrNDD3X|~cCLaO#mCrv7c5SSM6|UK zjl*mYK=!SrKNo-@EA?-2{EjJ;`CoQ2#1$zf0X(PH2z?5$tAjBjP=bD0NuD+=siPHjIpjlY|l_cH3O zd0{tmB6Ih^pji`W$DZ-;dV$qMu9tV zk{3*Hjl=R$GyV&W-e?Hr^}um}zmIo5B#(ESxrF*xVzbTrj^!39dz z3>KL*2NqT_{IVy2pt^)V-g{v-60530t^LTN`njqxDLf5>?~bAT>J=v`%;liw^!O~;x1lmTkA*pnaqQQyVB^ECP5S{JhoAt4&#z#0Ijs{@~|0 zq7Ne8IR5*~cU|tSV$hsA-NTi3edSeUUZ>4*7Y?Y_TTU?A+atv@zX_^KrO)s4GM7TP z#^e}eWQ=PS->DQC8x7G=MnGL42${N;Srv2C4r2E1yX>=|0N^SeH%Hb0c>blp2kLS@ zcPY@vXi%49 z&Z|MquG-~X0keaaI#227Q~jozjFcH|9Z~hd$y2`dsEX6ts0w$APV=TuKB;ECmCqY8 zi03J}YU|iDH>Z=QK8(IyvL-+GnV(M6$hbeFu}%}4{C4#%KE5~@w78O)BBS1UhxHhc zgG2q2j1WHPngKww_(;POY9L7gBrCsc0+goZ)19#$`E%HgG7uqrAzG|aKyo&Iw-fc~ zZ>khe|KMyN5;(Q-&#XyOXpi`E&m?D3?M$=7+T@RUNk=lA>GHh~Qn~!ZM@RTk^m0HV zgn~O%z+r(@3&t03;M3#*FuDD!{RD_Mz~IcCDC~mW0%`80TxfU&1u9ZRX@qnKgM-fwELljt?mdfgtLzl`mp6U^@Lln?h}If2SP9KiHR0 z*!~(_R%5qh8Ft>wU;E0*Rl1}KKw+t_Ud9#Dwh0RNu?5(Tr_W+4y0({do;(;>qZIuy z91|9)k-YZuf!Nx4$O`BKv*P0GplDD!!n^8EdeA}sHd1K;sGd-T6vF04kR>7&)IfQdU1L7_!>)YMi2qyN)?k`5hB< zVmP#GS~#6?H@1^thjeA@+)cb0Xg1Okf&1OyutuPM^^N{sz^B#O1)s7hVSh9K~ zC_M$1bOIvihGIGJ6zBmwLcy(DLXkh9tv!OCaPZtdRaV9VkqF5wgYVr04;i{m>qARA zrECR+4+s1oE(oX~E+XS~eAi6rP6kT9bC*aT!!!Y1R4>65#h~T}I3*||3rM4xWr^U~ zCM4e&0aN^#3H{@x(DP* z3mw`mj4aF;myCiK19wo}fgFCU_-On2{}{fG$3^Rca?mV%*7WFAY=FSVOyZl;w)P8| zcp^$_>JO)<^Mr)&DAhc*z8M2T$lF}DQ63E>QOCzVhGVbKd74utN~&U?oLme!qC?VQ zK*#ON)l2}sD*g5TArL4c3l}LSP;_T|;`GD;jPoO4O+yC=LcqQFHKl=W^BitNejEC$ zAZovy_otA(K_q;T1jNvSv=QQy0~el6s}_ZbhaeLKojXCe3u#5i0h=mBs0AFninVe` zGzPO(eI0~y&uKD6BSxS5nEB!q`g;8XWwG-=}nABEUw z>8ByCu|0UhVeu^~)I8Th6DZkp#HbS`uaV+h6Mj1G$g(_>b7T)sXcmOIsgUkOiEYWr zLMm7bk^_*D@q!txkXZoPtT>qF-5`U}aQ!I{Q+>YIjvW>e#fu*wKj(C{wQ=9-2H^sf zrMS+_j9W7L)pc*Y84`+5BqVqZtT87c*$tU%MA8B{QZpzHV2L4FNuad^fS&a(n7@R; zJxJy{LDP8>VC%tT3e#YKMUcUI+)NMt$TP{aUj`DTOc|HPZ1187hKKQ2C&V{jq2p8V zcT7=oJbl6Ihm1i|(goh=qkJKuDWa>-7;}d;s?J<`EtQGNRh_QBQf!OV0J*Z zxmmqx$&LMt$7hxYFp|t!?<|Ob3;T-enL>`w@=vTC<)%U%i+u1iOYy^8aMadTTT8^>*jkG$J%t1 zP%MzVLFSpS<`WhLRTkh<9Cw3YV{V9ud*h?K^cE zYA#zAS9YhblHF>APgyX|T_(Hcm#si~UW4A$Ddf*b|wuUo|J9*lGwJVz*2!AuN(F<7(#EH4WbE|~ zo0%k1f^yVuS7f4&j{E6Fn9^Z2Z-GfK0J7S5$C*nYk9h(+6x2{aIG68?M|e6FL4yq? zEnA^15BNn%;0htCLhwKi`t103hjfsZr?3LLp@s?+l52;&1kzA|K&I;w>AgwVXl5am zP9-3a0J>kr@g#%#*B4;J4}*2p4cIe?C~6@Oya>5>&M`}Li1KhDXQ2a+YYb8wNbwLL zdn3Xwu!v0viP6aD4uE$2bFrE(n;0-tvIneGA(%q!6L>8MyBu;{SJEh-s6{8>+93-f z!On@sam-w;v60Kq*OG{6hJmR`UCn=awn16xEuc-PUTIB+D9P|v63;71-6$G77p7BHj&?@5F(~i2j zC{IsT3{0JaMT;lr=O?we4lultJj+~@VbN8kOpaGY#tAk&2G4JFhTI&}BXEqB;+4Xr zs33O`!Z1&*Vl$F`-n?8mW6!-AdxRFytroq*8kJ3)O(=2V7RBHel||^UAmD$3M$AYk zp@5|yb4lFt{JBhd0;+yt*gi5s&OxX!3vdreM*!qZoK$-V3^(W;Sb4|WiIvJ=(CM0OG^Eqy40gKjUgagPBi0(C& z!5IwP%eIe$Ak9%MashsN>Z&`4@qYCYO(0GlXk9@VbcO}8gWuf_%}hCBz&aTs?123Y z@fg_l^9&4Rt&X??vlv#IgLJw&n`Uga3shJ!&T4Ia)-H}>CAp-uF>PS^96RIa=WRWl zjiEYpF6O5sl9Q~&8>D2V^u8OVbQ}1y(_0VI+XF@yYt^S}S8cTml{Wl*>zTPpO(d{S zy1VyEWaN*Ism&Z!SzO`7CBIRaNq$&{7l z$OHnbK76o#5(u-vP2cntVSQr#hf-AA%2Q+S9&t+Qq(LkK90`Iz8{r&#bfE8Qg@oJiI`sslXm6FXgBp`!KhY85Yaw+l!9j&< ziG#98bWiyWL8gvi-Fod2o8XJ|z+E71|3DhS8e>G9q6A@csH9@EyHt zp{@;=?1S#QhFEWp<>>0Z$m$HNO7`#C8~YptXy^Pv~9#p3zwk1F^N26W&L1+*<-0F_G2$&uWW!CYw= zI0WZM;dm#}rRTXG+9To#gcAc^E}(tT_aJWxNEVMDKJ@U|=RxRKP?c3hMWvq#B6g5$ zXM7rAA5?2dIN70v7$RRK`{H}JH$GU{x1@3ywIAh0B`8PbfoA@YaLoKQ0d zNKfO|?Tm0oPcPgpyWRI2vp>!_D-Ao>tm`SCa4n&7=zI1v8!MwpKh)0>Rw{{!=b;e@ zmCZ7!OLPuu%6=9ndKeN)aQ)Bl-CqZ=7tQtpD)uRMPlscg z%u8l0xul{`*5Mu9~|5zSc~#=HD0A_xE?w0Ci4pHEj( z`!0yyj3}k_Mbz@G$zQAlvTA&mLspdh)*8@q&hgJ^R@7iVZRz|1vjphOa79 z65|*zb!J|WEe||ri2*Mq=y;jgin6_4Etg+7<`PQ0SGV%b0T+iwTC7DMzIZ!_0Ij10 zjhI1=A7{;ZnqqHc5B zzui&Pyp>_031&G>-tV_Tep2)-N%+z&#m7wezw=X{r9?OI%}2iY%(eR%_MEpFF&|^< zauWD>r?gEp*@L$5hmWhu!N z1sx7uk@&f!9A9{fwGckcFZRgA~a zWgn@GAcwsiEa#?aYhGoM{6a&&R2E8ETSf*mZmrXFln5l;ziYblf+4;<^IgehlbDtZ%Z~o%WA7cV`RQk6fBeFX> zQe>e1&FjISnvGU+RArd!CTskP#8K{gK-pCPkfK|F&2sUCEq?RTx~2K(YfbOYeY+(u zlLdRa2nOEmreymzA{UQ3!`fVRkyrt90p_`MrE2`a95W?VyV|kq7n*;ubCtyL+RKo{ z<0)(1n;xlHNR&?-KL7C?ZZsCrbVs`^7SZ29EAs%3r4X{_G<7>QYvR8(De8!g+iiBL zs7W29ZcC}IbaF|w7A|DYlTWz$&5T-P&bRYN{qzgq8;U%}JS;ekwU6B@vyqDC6n_0& zDlN$MXG!U9vi7PYBkFs?)$0cIUELkBZ8MB?e0mfWF}{tOXEftC*~YzbwEg|-oUY*U zqE3X*TRXQLcPV}uv-egh`{T3x{vO0iWI8UEea=c?qM`}Y$r`I}rtUOFwYCqJt}Q=T z#p}>;9)l+}-HorqN3=AE{MEBVp_=*YRAd5{?^?F3B_LC~_;279um4E}cf4X{wcL1T zp_x4B=X$`l(jKY!J#GHx7%uIHy=+G@U#qPBUm^1V)@bwi>XW#~`0N+OwE=SV+ncwY)rtBn^s^~>vMv(_WP{}FxrX5!$G z-wQLx(QvMWMfQt`^0X(JvSeSFZC6+GH@I@YqrgF4kidms$M%RKD6vjA(|b6rp}%Z z8E#I8b_DhmEV*J3;uU*SX0E)k-I{9Ud3C(pSQ?~vyw)&s!s`{nd1~MN;z;d06LX*8 zK-f1zMyB?y@Pwl?)7Jlewx#bjL8LzWpT_*Li>zP}?g#w7%$N>>H*ZQM!}mSwLyq9vj6YIIy$)~PDS6h0MH^TvIaZ+m4ZPEe1nr6=nas#AT`%B7@@c1=`n z>DA=ZYXj#3`r1Gx^Y7*2pD%p48-^eGY-%%{o=r>A{0)yQrDG-WLywJ`d}abHfseBR ziXSVnPboOjw9LoO+h{)$GpLeW^e+LEtz|y&X~g?OJ$kand6QlhMzz0(oxKQcpYA=5 zf!qz7itzyTd;~wfcD;N+C~vWMlaBL_m8lLz^T-J)*|H+Kmif?m#SwGfW}CX1WbJ;= zs8CY$a~%QiCx*31`el?=DGOO?6#U;6h{Gk7hYH zyg_(U*{Le`vW`&AjJ|jA6)*0P>8rjUy_(so|87NWL1+&FyJh6lW8cT|;JJNepM7yD zOmTT?q_Q+ff4Y;`x6GXPd(Tz>;%^CxhtX*0L*tHO;w-OUA5}7OowX4CSxF>QhH1@v zS%o$t>N!=dw)`^T-=|wvZ}gVq%9RN_G0nJd&^CB+FhN@azckZgPg2$tKV^v9vEZ}i zs$^rVEql{jQZ1HAhp%>}yK87*OWnVWVb{< zwAiR0z1cd+fFn#&(q@NDX;s;+k)8J99y;Eq)9EgrI2KTuD!2ObqVdY-sU~5do#=G<_+@P zI%1OK$$y7vxle+9?iL~u3_B<>B^#^et6LqFwfb=xV*1A1|?Qc)LXQzBG+3nMNKuFidOTX#rxDUt}D>dh^+X zKdvV@pQk=`AJ)KRSGT$FZKyekY-5D*5>)G*~U6`A(a$=onG(}~8-1StdC6)$tcAF|jsFZocpfl(pJvmEK*_K}#)j#|Kk89y7CSeswSV zwd+-=!X{OUHl@>oG>?C2&C)SP`ZlY`$Qiqejq*xIaso#(`${HG4e7a< zXmEqHI6&vXs*+87=7=?_gIJOV+s!S?!=n~5=^Q#2vFqhN)0|U%tMYGkzm=muhh6QC zXA1F2SeXh@wLVuLwj$%d!G9b3M)A+$m$?BO^`F*E>ZfdBW`VRzuC|93NjWpq#2ZlnM2 z@OogP+KA9_|J)G@CFpbGKf@XEvB+rzg_`@X0g&iEhnoA(_@PiAzCF zrG_Oj`7r*R{+9Re#}(i9l2)_jPP{K&gjzRL!*Xftm1zu-$)=(5O~nhLj_D8UH)iy@ zN7(T0d4A3tPQpz8QJpXeKY1^`Rcow+tbzjwDPk{%T*SDe*m5VKoldcZUbAHa$J<(L zfsIYK#mphSelfCnF?@7Q{>@Amb5JjBNdvv#^JI}f^JsEW=G%x4Oc}iepL4tzb4A24 zy$@{_#PdlQg$>}1EL&*ssCi_=T1c;L%RMtT$xH^q^u+pine|DPreX^-ZA2GC3Q9DW zYbvTMski6CBSx9GtNna$!Kvvov2Q_1z1GK%xAQ9t%Cgvo{X-T%U5)mS<%r4PQ=kV?D-f zIZt>~jHN#i|B`bqP8<0wM3I{C{mkETKAy#_^p-&Pb`S)t3? zOS)L5VF_7P4>Sxpq$8&5oo|PB+MJuW}Q8ALpwBC{DO7?xJ&e8C+{BpN0S60mD zNPNkhHuI7G%ZBo<@|mRQj9cYrc7*>tcTzVYHD$SDo)vMX zT`W=kIHHn#@k(Rw^IP}|H)-#bIQhoj$r4iuHw`fgrQ`FG7{>4VYNBPWVvs`~Ic}R# zr0=cbF-njzBGz^G_u*?f^@+VMegZ=fQEgRwx7<>aQ~!{iTOjKt{Rd9tXs~Q33&v`@HcTWe6lI`Fq?g}DBHe7#giN#>(5mOy*5Nf zhzf((CRp@R*H2(d)VSolEIwPDmQ*G`)fZM@cI_;8P%X=L8~x2lY3q5(Z2g6Po+HfT z#WstgDz}o6l9d5Mcd9pM{#+*dUF=8GB*Rhh zd2!&Q`6Mn?Qbffq5eu(o&~dg6eVxeCygT3QR0{nwt)1&s?~xnNG$fb4O)=I5W*?bt@(O7dL{>UrvUd@df6Th5J*Tly(8R!8MkrT?>f|o|7 zjpUPZAJM13nJ(b_IU&nNq)3zSYveeF-ob>8?b8!$DIO1zKD9ED5L=d=M;PN@%efuI zg8LG2URUSRDIS*}*ZbVR^*Pfxdqn{b6S5=m!#g7n(^hZyQ^Yjhh=QGbY%CBk2+^kA`RTgSJ%=^oHS+o7Q-T2=7_2xpN*rQB!Da}@kZbqejL-QR8znI_7tt@sN(PhP!FTZw=oV;2`sy8BIJmeFW?E2#T zv=B@o#$Ihj&zhO)!K3TgcW=2D6_O?N2)J&!o0v{<^O63!Ng-ZO#442E8Of1|9gLpB z?eDJ?$4Xy*uj#rkbAu^HF~s-dH)HO^>O}#ukfo~88vE1aFMZ^i_r*7TF!@i#tffN2 zT9b?3c6Qe-eN@xUWLWXd*VN8$CI!kXz6K{` zEPB>PU)x_yiTvXNG&dDC_GZvIcxHK}!(?|DXxOM3qBvs#L)Mc+~-ut;t z>RjQh-O*M}n!%x_q2iD0d{9{cc_BN!UKa6&8W~^mt5%zl;jxdyU;0J(wb&}?M7Ovz zZi$*#D5}!q8q&Q`FDKWDQb-L`41mUCkIP-SXXLKaR$E3rVd+ACmY00RvPO@Ki^M{cd#13aH_mG}B{czpvJ@5R7!~?G z`p7OrCXN@)tXGHAjyf5wqY1=x6$wiD7}a>MRjsoNFnISS(q-E2HhKG|D(tKjNB$W9 zbNz_3DH~$msop)OYS7=`lkW2)+`_ij(pn*NF;9igfj(YcCdtCvV@((=5J6W~K*(aw zDHbEGexE{-Lj&{e*>yQya)nxT=GJff)-_ib)9QUliWKZj*x^I@RI~oBA3YtIDjIR+ z4ps~}%8V(z#V~J)wBFbdA7qKwM#`nu~+CfE>(b%+1(SP79GgkCsQaJQ;w_JtkxJlCan59 znxVgU*XoXHpROW@WqX3F(x=S7&;tbCO(@$8+6@wR8ndx|A+O4=*X!TtkmQ?)ez(ok z#rI~5-Ms!rqjtVNv6doz2b{gqBZKaz|*qW<^>@>e(;lx7ilOJYljJi8I_)2*c>^S|} z9(8pI(}p1DCgSlqu?dyR4)hEclG3Rrv=s{(gof<&72~4Bl<%Jgj=weG8QMJ)cUI4+ zfLVePM*Qd)3l;O4M7l|LJ4~a2$HTktS(&1Jrg-;`hcFSd5wEpSNMYt~n)#bt!&^m; z&2AHB2R`OZ8s8*LKdo4pb0~gW`$l2MvEocO%4uV^N_jngU>8mB4*kMJ{xvJJT*@PX zAJn(S6Hd+j`Eii@jCoylIl$1bH>{r_u9ZvmjC0?QiF9d;V`2JMC#RKg?y)T|wu3^L z=@+?{@0kQXN&k7MjQt3l6oRhD?I%t11sKUa82uRU7w3MD8hi^Qv9T~rn4eAxDN|t! z$gv(Y;pfPJi5h}0$-KNY)@(gewUl)bm@yW>{cRuJm1C2~?rcK8#7@dcW zPZ7@ai8V%dWB*ms+x|C_MBTnSzZTK(qNGGxqh{7pNj$OpbN&@_!=qQ$ZANS^^4)!j zG*pAW%bDXhE-}V-KXX|{YcrESw0i-Dx>trB!#21@P~_tBmf_+l1;d z1DW{9!duKg&AF&5$d_%gco=u8pLM{AxwdBArlrY zh05{2yqFtPeW`3S#(s{dJ4i_NW@3e|kLR1+bY3@D%c7q5UB`M;N!@C+efuEU^=h<| z=vap-O>W~{tnnFsSBFu}o{Ikrrfehig5a_Z_mI7upSaVl(6ZF>?p*t$gbdq$LIF67 zo!u@T2K_^a@#?3gdo7s3>)$+lfCB7(1+KFC6+W3!iTH z$gVu5CR1_mM9D|~QSg)9bhDkux=)>#PakTCgky{1WU9h*VJEtFu>FQ)o{G}_#aub5 z3%T{EYk~5rarTm1hJ`kDh`jEt+|`eSt`-ZUx2`<-ciAsR97HbmkgoKd?y6M;YMxlU zSB{Fvd}v*fB@K>Ohg;U}?bZ?uvBaUQi_zn3o(uDFDqM!x*fH?xoik+Sl#XkHWi6Z}=eBOmIyC^>+)}JbS zHN8KMK1ivbdJ@ivI`Mju1*TH{xbvjEdLuoD+2zIH&q1QD#b49+MW3zj|9Y3|urk=V zS3`N!wLDP8xuZ!f$}dvn5@<|L`74+1$%yP}2;mH#^jAsoWNTmH!FZy=yL}(2RNZe^ z^b7sBf40u6pUoa;oW0mr`$gH6V=F(g+ked5Z_M08ndsJgm1hr}s`7rihd);;jE$-` zh}tppZMN}k-loI>D&K7;P0OOXd)2*vcbJovlXTGhO zjgMS=A(hhj;MKot8k+488BXt<$XZ`_0^itdKI9yYGkZxMb>^M>WL~jSex@8){jTSu zB{W)fHPYoC3}?++#f)?heLVik%y#LocZ5PIH6Nv5{zzL^5K%9oUL5IIC}$nbjo$dw zQ|7;d^Tl5pOtugQsc~&xx%WSSCJ-(@&xScmC-Kbtk`H$d#$DTBa4qC45kLQ+mUiwsA)J5;3C&{2b zXsavt|BAcvu$tDsogo~QgOo9Hl5Gm9jie%tnrB3$I?d7~X~I#5O0|n9wUOpY!*0~z zq*95pOVWhenk3EA;Ju%{`M&qPuJ^C+pKo95N?7|@&w8HUyw>l&tCNOr{B>3(hAE~d zM=cOSmHY)GSUTqWcDfP9rKVwYRsE_*i>k~QW!&{?5skR=Wh=J_kJW;##I|C!*fNDB zoctPBT2eEWt={RVmzXpdl)rk(im(--jVUpG;k}`^ztSW) zSzk^+2|?0y)^VO=$v)f5bC%C#E#hW5a77!PILPzs{%lqbD@U~i$=B!|s5fGqZ5^@^O<{ez_s`%(`DI6Mh?F8M z3{|SQr6e3$WqzxMUpL5fx9}?31IDgyzi}U-Rs3=}21jo*%xJn4rK&VFx_*%Ea{*mS za-qSYs;=UZqQ}{RH73u^bDmqi(>vps^iQAGwbGsRBo)sKjM=F>9GVL=R_ePo$gNzp z>cIl8l7U9wB9Qu0?ZoVttoImMDvw#dEh$bRq#o^FTv1i+2R||2x-zW{0`@*yeXhHx zxr}!7M(jT-X3MJhGpf2ARLqvE{25a9DRV0ys#V%mov*7{`2Ef6)up>k8Fw;P^54}j z_^cnN>bJ$OY-2%#kZW*Yu^+;_J)$r`uKX7HKEX<@x&ifK+^I^|K z7QAqm5`UC`9FRHf_~XlNPcX9xPy|roWBL7fI-2!EBXcuLp!gd%IUAo%HHUxW{Dz+@ zi~ehskc*45`@dF8NpbM^UxnCzuT=g=4fo#*rsN`v|Nk!%dL1nj+g1m(rAw_2=mqx+ z-vag`-1ol|in$NjgU&Tl#_QB8sbSUgO=y9428?l&4Yd$>-F%$&y05wmbyaV%!P50J zn!LUsEtHe=!c$hdOj<*O-mw&Y32|}F4eU|9#SWu*EPJ=Rx0hDYp(Q04COk3i$-~RL zmHw&^tQc{!?9;f+{z5&@Tg(CA+)e#1%G$!qf`u75In^D5nw;?V=Rm7^FiX|KJm{gL6Jlj$MOnxmUG^@i`rd!xIGsCaq9meOlxLj{MGugdk`*w>n zXAT7`9l?A(i;Gu25f>MK{=uG4F7n*Quxc{!EtM^Tf!1bb@;W*?H;!y{*td3Qa(dys zt2l;SrCNS2W!wVxl;460ba(w0zJ>VT#FUf<^vURHX$`)8Y0Wr}UmgHI9(d|0Cj|V; zvNAFrmX*o#ELl>$%irWJ69lhnoMm_Yhb+76?2W;Hi-?Gb@811DcEkPf@YRg$Z0R?$ zU1waS1TRVnLLiiA59{JVYe7z#nen`KSO^DX!A^vIrzOi}At)s|k2ERW=*kVhb4PPy zu;$sb(M7|N1JCw0?=fo(nlxSvXv18x9xM9MyA>_a#^QnZO^ ztd#i&d&A|+m*a)r+gG06$D6Ub!0^rh>$cVdAembOT_gPN-Maev(0TLb)z{bK!jEJ( zl&Eo%JJ%QN+fp?*H+SkN=ZVqYf?McD$AyDrq?vPov$JzzQj*Tb;M&g4N09rSam)lX zr6r`M-cL5P{f>{14uK~>kVq(kT5Mxp}p7nRW5M*adl0l-|!k&TD6IF}GyMud0?Wi4+X z0LApx)B*qoRTCe1&H@d?km&Eg*3C-HRb7vp;s(L?vhBU0^C6%0?FDZeBuxE_V ztpx@g1#?njkK$dxUg4u+cm2VX@$ltK^%V=R(X1w4zoxa=<;;Bbl~JO(UAjaDu@K*? zym0PpsM01!!nj-ucEQj})9yR$fw+v>w;#56@nQ;8J24S&vKMA$=`OZE<@$kJ`8AN0 zi6#TGadOfbeKEAW*wee>%gYr;$H$qwf0}?RM1h(=efq?A{YZUXotA?w9TtVcM=LW4 zhWikPlet)Us&KG;4eb$HU;EG!yUF<^=AtRQtgfYH?K+MozCX&|+kQ0RSXo5OtGP1M6H7{Ro4XKO=D17I;s7lk&S6xSYCnT3dr>AT6 zI33@!XOELEXR(^exIs>6F`%t0+#?~uup7BqV;+)4Wwn4D>R1c?%^Q7%LC$)({{~4v z&0OSLsv;7Sn3lG)a?ERRDst!CtA}7h0|EoXYBH@?uUT_TC5DgJx92hETQpS_L}#C2 zCsn8|!H>WR;!NMc?}skZ2IuOTv2#DNI|uNbJ5prx<`oO(c4x7_b((n=ig=nC5f!C> z^5nW}u2l_Y&={p0R6_T6f=Yn+;rD&w3IAxLJcbHdP2 zQ%#NM8f7US??aFHIGSbS2HWhdwqx1#uc~3oJ`PV{e<++l`|SvO#xMT)@EBchdQUQa3b|0dU7uG^-ty7#E3D?*mw0!-0V(I!62p=8EsyC0oJSKhCU~H_A-J)O6J2 zGIMRvIrFaAt5~?Fvod68!W|Iv?dv8#IqW}{@`lH{8sq947>tq@gRjyE7Gft(8?&Gf zAdRaBdr~~~+DvQ}nz0E<6BBJ;*c_FQO;q(b9sMM|bVL6x5w@gys|AoHwcHeIl)9)rJUk4)4+>l~TZWIIJ$kEPU>}-{8-duF92~rq1a}A^;KF))dV-lqg-g6Y z4(7r&caFNT#wR8A?1{GDm+UH)diyp%@p_<}+RC?(JzzuxEbHba+Pv z1qEE!8G+w~yL92?mjWmnv$i&9ajB+(fx&KyUzrISS3~*v`N6#y0}w=g2o$Zpy*&+4 z1YQaNC1%^Gbgq#omXPQmK93Uy7YlNg#NMhjHO*`iw4wt{q8AvIb-1uIqyz!U^yfci znAT~9u|-AF=so(Fotc^GHe9op%p>yPC4FouF|Dt&CH z5*LDg=lHQ>b)dC-2q>K%w1nM;9R}ynVD8ncSKonxiv%u8G^p1oNb`EZR$u%4`QNzP z5d*JLgLiq3aiDM8t_*!{gfM~fDxs&xlI5^pPhX$^YP7&9*F(5ZxOW}#)eXS6903D$ zH-JpFoSjGWE$jFN1V)+k8C?SC539;@$QuDAWmUh6H7Gh-M}MG=w;|ATj3b(HHKu_q+6^1yyyKW_WD{ZXU0r5l7jVJ+l zmjwD|D}81r=szyDeovbxNDEaGb^=ze$9O?|17b(%Z|~>8hNd-__q%Lc%PSzWIYe2x z@9I5YXHbB0&z{u}-~XCk8s+uP*UNBkuL8}k?Fo_I>2DP>(1QA}UmpX=c(k?)Y(RQ| zIUOu)?!OJMThURcf!+M*vS`sFD{4%| zkVeJKVJAi~?0DP9Tdn$oy?eBG7dTvrWi-ucZfI#qMsVbTHhDJy5e($L0=%^o7WQPG zgFG|`jghp*z8&htBFdL#We*-aNCI}`iXf$|XEKKaQW>~UqV}Rjx%ch&ZHKZTC?oc$ z%uysn*#j^Rl5QjMAP*g_HlESO7$m|1YEB|JH+?1lgvq@;)~mTRAE z8+Yoh-vV2zZkKa{{1t{%*Vs4>XqDYdyuMw9HNJ2m=XO}wz&<;XkYLN9&724QZ(IC9 z1K7n~g;>KMHkza?K)d?e#O5)OOAWwoj?HTKSwBgF?(S~G@h4HfqkhIyS0Xr0UxlMu zJCHviv=>rQ-54BH&3gDdM+|iEREo>yxL}|ntV*RR4Wj}JMCSJIBFJ^as#nn0a7KB2 zjBTqJNIjK=4+~KZ9UU{F$v*4%uH~&B7}q(?9`11u`z#5hMHb>JLMqQd(KGup*ERNk za{Y{3@Xlp;M8u^2ONssa6L1UTH(7*Y!`QgpCvr1%4F!|$tplD0F5}k7#i9RBM*luI z1EHv@h>mu&Yev&&k46x-S)&#Jgw}U*{o`4F3ehTY%y+=`U5Bz1J~nP5oAA?RbaXU4 zGV)eqpT|erO7l$OYY@?Nx)d-jjoXn-@%(wM!oot5r6b`a=;#6d{@nn0fW0P(sD?%$ zd=pS!(w3At>H9%ykUdkXQ%Cuo{vVzT7)? zk+q_5_~n7b)KtSuO?09i|wz?)MNo_b2koa&awK zrhMcOC!(J5XRF)J-xr`FVu4HuY`B4=M!<0XUQj$);9QM&VX#u0lt~Kg^7)P`Gqioc z;OJ35c!m15HsW*88eMIYZee4i3avl}NqYpGp>BiX@3$6S`)6I()Q~510~pk|QLUj> zK7#k7Rhph}zIl`PZft@kMR&?3-LU@c+jvk)PG%3DSC6Fb-;Y{R0l>lxZ-UWf|0ORKY-$!T55{=NZu+ z>27td*kAmFer9EFUmw{v%*BR!;=HkPMw3lh|KidhX3us{&mgL_C~V=o^t1EVtzb*q zdn!9YX?XLd7eFxWRg|bp6B{)r;BeAV=TWx)!!udGFJFuL`nbh%USB_YvEjL#=7CE$ zkqBBLN&umGAj?UTWN*lrZI#xn4}&>HSrELzby}RH%dP{jcX74g{-}^nsXA&FgV6)< z79DCt15|CMzkNmx`*Fdh5!DvtWIIGfiT6Say_KDv=*{}Pu>Um1LagD5ir3`<4#S_+ zY+Lhh@p6g_u~D zBhsxy(pq1k#SuXeM zHRdD&K_!S%zMLv9{skw~^NqeSoHioLR}o zF_`ZK*?H}J-_i$=af{QZWue)8ox73uK?l9DG@HY!`1AmaAA0y}&a;U5{^|`I21Av2?HV_%rdH6o__Q<) z1Qgg}Ei@wtK$pZ&aj)C3DwT!bpE6I5_=UovUW@pRMXJtL!krrqK&#M z{(%3f9t!Um%taAF9JZ{WH5G+R)Ep!^wcnDnq_|&lRvUo=65ea2XHbmjL%xcd4Td<| z3=eB_`g8fVkuH^$vSO?;xTiL1j~>Vn;^@>KM%T@9*R4#FV0? zoR&|_qMEuo>iH_7VMk%tC0)PXPuAbIm-Dpp{R#Fga-Qv4%*e_jK|LzukT*%kPyUb< z)P5nItWh_-W1<*MjE)r?H&XQnno8g{(B1I+`*Mz#lbXernOUC2#yEiU^7`4czmRB2 zP^qzpAKV9hubzPc!U>KpnOzI`x zo44~VM3Gwg_#%CP)*`Tu`|#mRjCO)aErNd(+J)GU6ea@Vj#RT8kV4})j=))bH4b7p z*Yf(hOVe=^44`GixtK0x4_;zU-mEXtdDb!bykih$VKrK4jX5fw4CFX?41wJgkXywR z_d64anipOvFM`7o-a>!14S|#KgnLo07d2wXmjRaom|1MjhT`^}1+6b@*n{JN1AA}8 zy|f}?v4U5gzF*hJeqeEAcXDOdFe38JsG#2+H&GL)k&j`1$$YZiN5a^R*X0=3Ys2n@qKvM [!NOTE] +> [Click here to go to acting architecture](./../acting/architecture_documentation.md) + +## Summary of Control Components + +### Steering controllers +> [!TIP] +> Follow this link for the [Documentation](./steering_controllers.md) on steering controllers. + +#### pure_pursuit_controller.py + +- Inputs: + - **trajectory**: Path + - **current_pos**: PoseStamped + - **Speed**: CarlaSpeedometer + - **current_heading**: Float32 +- Outputs: + - **pure_pursuit_steer**: Float32 + - **pure_p_debug**: Debug + +#### stanley_controller.py + +- Inputs: + - **trajectory**: Path + - **current_pos**: PoseStamped + - **Speed**: CarlaSpeedometer + - **current_heading**: Float32 +- Outputs: + - **stanley_steer**: Float32 + - **stanley_debug**: StanleyDebug + +### Velocity controllers +> [!TIP] +> Follow this link for the ([Documentation](./velocity_controller.md)) on velocity component. + +#### velocity_controller.py + +- Inputs: + - **target_velocity**: Float32 + - **Speed**: CarlaSpeedometer +- Outputs: + - **throttle**: Float32 + - **brake**: Float32 + +### vehicle_controller.py +> [!TIP] +> Follow this link for [Documentation](./vehicle_controller.md) on vehicle controller. + +- Inputs: + - **emergency**: Bool + - **curr_behavior**: String + - **Speed**: CarlaSpeedometer + - **throttle**: Float32 + - **brake**: Float32 + - **pure_pursuit_steer**: Float32 + - **stanley_steer**: Float32 +- Outputs: + - **vehicle_control_cmd**: [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) + - **status**: Bool + - **emergency**: Bool \ No newline at end of file diff --git a/doc/control/steering_controllers.md b/doc/control/steering_controllers.md index e7c0a474..3b8cacdb 100644 --- a/doc/control/steering_controllers.md +++ b/doc/control/steering_controllers.md @@ -2,10 +2,9 @@ **Summary:** This page provides an overview of the current status of both steering controllers, the PurePursuit and the Stanley Controller. -- [Overview of the Steering Controllers](#overview-of-the-steering-controllers) - - [General Introduction to Steering Controllers](#general-introduction-to-steering-controllers) - - [PurePursuit Controller](#purepursuit-controller) - - [Stanley Controller](#stanley-controller) +- [General Introduction to Steering Controllers](#general-introduction-to-steering-controllers) +- [PurePursuit Controller](#purepursuit-controller) +- [Stanley Controller](#stanley-controller) ## General Introduction to Steering Controllers @@ -16,12 +15,12 @@ Currently, two different, independently running Steering Controllers are impleme ## PurePursuit Controller -The [PurePursuit Controller's](../../code/acting/src/acting/pure_pursuit_controller.py) main feature to determine a steering-output is the so-called **look-ahead-distance d_la** (l_d in Image). +The [PurePursuit Controller's](../../code/control/src/pure_pursuit_controller.py) main feature to determine a steering-output is the so-called **look-ahead-distance d_la** (l_d in Image). For more indepth information about the PurePursuit Controller, click [this link](https://de.mathworks.com/help/nav/ug/pure-pursuit-controller.html) and [this link](https://thomasfermi.github.io/Algorithms-for-Automated-Driving/Control/PurePursuit.html). At every moment it checks a point of the trajectory in front of the vehicle with a distance of **$d_{la}$** and determines a steering-angle so that the vehicle will aim straight to this point of the trajectory. -![MISSING: PurePursuit-ShowImage](../assets/acting/Steering_PurePursuit.png) +![MISSING: PurePursuit-ShowImage](../assets/control/Steering_PurePursuit.png) This **look-ahead-distance $d_{la}$** is velocity-dependent, as at higher velocities, the controller should look further ahead onto the trajectory. @@ -32,17 +31,17 @@ $$ \delta = arctan({2 \cdot L_{vehicle} \cdot sin(\alpha) \over d_{la}})$$ To tune the PurePursuit Controller, you can tune the factor of this velocity-dependence **$k_{ld}$**. Also, for an unknown reason, we needed to add an amplification to the output-steering signal before publishing aswell **$k_{pub}$**, which highly optimized the steering performance in the dev-launch: -![MISSING: PurePursuit-Optimization_Image](../assets/acting/Steering_PurePursuit_Tuning.png) +![MISSING: PurePursuit-Optimization_Image](../assets/control/Steering_PurePursuit_Tuning.png) **NOTE:** The **look-ahead-distance $d_{la}$** should be highly optimally tuned already for optimal sensor data and on the dev-launch! In the Leaderboard-Launch this sadly does not work the same, so it requires different tuning and needs to be optimized/fixed. ## Stanley Controller -The [Stanley Controller's](../../code/acting/src/acting/stanley.py) main features to determine a steering-output is the so-called **cross-track-error** (e_fa in Image) and the **trajectory-heading** (theta_e in Image). +The [Stanley Controller's](../../code/control/src/stanley_controller.py ) main features to determine a steering-output is the so-called **cross-track-error** (e_fa in Image) and the **trajectory-heading** (theta_e in Image). For more indepth information about the Stanley Controller, click [this link](https://medium.com/roboquest/understanding-geometric-path-tracking-algorithms-stanley-controller-25da17bcc219) and [this link](https://ai.stanford.edu/~gabeh/papers/hoffmann_stanley_control07.pdf). -![MISSING: Stanley-SHOW-IMAGE](../assets/acting/Steering_Stanley.png) +![MISSING: Stanley-SHOW-IMAGE](../assets/control/Steering_Stanley.png) At every moment it checks the closest point of the trajectory to itself and determines a two steering-angles: @@ -55,7 +54,7 @@ $$ \delta = \theta_e - arctan({k_{ce} \cdot e_{fa} \over v})$$ To tune the Stanley Controller, you tune the factor **$k_{ce}$**, which amplifies (or diminishes) how strong the **cross-track-error**-calculated steering-angle will "flow" into the output steering-angle. -![MISSING: Stanley-Compared to PurePursuit](../assets/acting/Steering_Stanley_ComparedToPurePur.png) +![MISSING: Stanley-Compared to PurePursuit](../assets/control/Steering_Stanley_ComparedToPurePur.png) As for the PurePursuit Controller, sadly the achieved good tuning in the Dev-Launch was by far too strong for the Leaderboard-Launch, which is why we needed to Hotfix the Steering in the last week to Tune Stanley alot "weaker". We do not exactly know, why the two launches are this different. (Dev-Launch and Leaderboard-Launch differentiate in synchronicity, Dev-Launch is synchronous, Leaderboard-Launch is asynchronous?) diff --git a/doc/control/vehicle_controller.md b/doc/control/vehicle_controller.md index 62dfefe7..9a307c02 100644 --- a/doc/control/vehicle_controller.md +++ b/doc/control/vehicle_controller.md @@ -2,15 +2,14 @@ **Summary:** This page provides an overview of the current status of the Vehicle Controller Component. -- [Overview of the Vehicle Controller Component](#overview-of-the-vehicle-controller-component) - - [General Introduction to the Vehicle Controller Component](#general-introduction-to-the-vehicle-controller-component) - - [Vehicle Controller Output](#vehicle-controller-output) - - [Emergency Brake](#emergency-brake) - - [Unstuck Routine](#unstuck-routine) +- [General Introduction to the Vehicle Controller Component](#general-introduction-to-the-vehicle-controller-component) +- [Vehicle Controller Output](#vehicle-controller-output) +- [Emergency Brake](#emergency-brake) +- [Unstuck Routine](#unstuck-routine) ## General Introduction to the Vehicle Controller Component -The [Vehicle Controller](../../code/acting/src/acting/vehicle_controller.py) collects all information from the other controllers in Acting ```throttle```, ```brake```, ```pure_puresuit_steer``` and ```stanley_steer``` +The [Vehicle Controller](../../code/control/src/vehicle_controller.py) collects all information from the other controllers in Control ```throttle```, ```brake```, ```pure_puresuit_steer``` and ```stanley_steer``` to fill them into the CARLA-Vehicle Command Message ```vehicle_control_cmd``` and send this to the CARLA simulator. It also reacts to some special case - Messages from Planning, such as emergency-braking or executing the unstuck-routine. @@ -50,7 +49,7 @@ This is done to prevent firing the emergency brake each time the main loop is re Comparison between normal braking and emergency braking: -![Braking Comparison](/doc/assets/acting/emergency_brake_stats_graph.png) +![Braking Comparison](/doc/assets/control/emergency_brake_stats_graph.png) _Please be aware, that this bug abuse might not work in newer updates!_ @@ -65,5 +64,5 @@ Inside the Unstuck Behavior we want drive backwards without steering, which is w It's also important to note, that we always receive a target_speed of -3 when in the unstuck routine. Also the __reverse attribute is True in this case. This is the only case we can drive backwards for now. When implementing an exhausting backwards driving approach this has to be kept in mind, because we DO NOT try to drive at the speed of -3 m/s. We only use the -3 as a keyword for driving backwards at full throttle for a specefic amount of time! -(see [velocity_controller.py](/code/acting/src/acting/velocity_controller.py) +(see [velocity_controller.py](/code/control/src/velocity_controller.py) and [maneuvers.py](/code/planning/src/behavior_agent/behaviours/maneuvers.py)) diff --git a/doc/control/velocity_controller.md b/doc/control/velocity_controller.md index b4715997..6315e2bb 100644 --- a/doc/control/velocity_controller.md +++ b/doc/control/velocity_controller.md @@ -2,13 +2,12 @@ **Summary:** This page provides an overview of the current status of the velocity_controller. -- [Overview of the Velocity Controller](#overview-of-the-velocity-controller) - - [General Introduction to Velocity Controller](#general-introduction-to-velocity-controller) - - [Current Implementation](#current-implementation) +- [General Introduction to Velocity Controller](#general-introduction-to-velocity-controller) +- [Current Implementation](#current-implementation) ## General Introduction to Velocity Controller -The [velocity_controller](../../code/acting/src/acting/velocity_controller.py) implements our way to make the CARLA-Vehicle drive at a ```target_velocity``` (published by Planning) by using a tuned PID-Controller to calculate a ```throttle``` and a ```brake``` for the CARLA-Vehicle-Command. +The [velocity_controller](../../code/control/src/velocity_controller.py) implements our way to make the CARLA-Vehicle drive at a ```target_velocity``` (published by Planning) by using a tuned PID-Controller to calculate a ```throttle``` and a ```brake``` for the CARLA-Vehicle-Command. For more information about PID-Controllers and how they work, follow [this link](https://en.wikipedia.org/wiki/Proportional%E2%80%93integral%E2%80%93derivative_controller). **IMPORTANT:** The CARLA ```vehicle_control_cmd``` only allows you to use a ```throttle``` and a ```brake``` value, both with an allowed range from 0-1, to control the driven speed. @@ -17,16 +16,16 @@ For more information about PID-Controllers and how they work, follow [this link] Currently, we use a tuned PID-Controller which was tuned for the speed of 14 m/s (around 50 km/h), as this is the most commonly driven velocity in this simulation: -![MISSING: PID-TUNING-IMAGE](../assets/acting/VelContr_PID_StepResponse.png) +![MISSING: PID-TUNING-IMAGE](../assets/control/VelContr_PID_StepResponse.png) Be aware, that the CARLA-Vehicle shifts gears automatically, resulting in the bumps you see! As PID-Controllers are linear by nature, the velocity-system is therefore linearized around 50 km/h, meaning the further you deviate from 50 km/h the worse the controller's performance gets: -![MISSING: PID-LINEARIZATION-IMAGE](../assets/acting/VelContr_PID_differentVelocities.png) +![MISSING: PID-LINEARIZATION-IMAGE](../assets/control/VelContr_PID_differentVelocities.png) As the Velocity Controller also has to handle braking, we currently use ```throttle```-optimized PID-Controller to calculate ```brake``` aswell (Since adding another Controller, like a P-Controller, did not work nearly as well!): -![MISSING: PID-BRAKING-IMAGE](../assets/acting/VelContr_PID_BrakingWithThrottlePID.png) +![MISSING: PID-BRAKING-IMAGE](../assets/control/VelContr_PID_BrakingWithThrottlePID.png) Currently, there is no general backwards-driving implemented here, as this was not needed (other than the [Unstuck Routine](/doc/planning/Behavior_detailed.md)). From 5760c6d7bb16fa2dcc0ec27a7d7b3f0228699b52 Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Sat, 16 Nov 2024 23:49:22 +0100 Subject: [PATCH 29/85] Minor documentation improvements on acting and control --- doc/acting/README.md | 6 +++--- doc/acting/passthrough.md | 10 ++++++++-- doc/control/architecture_documentation.md | 2 +- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/doc/acting/README.md b/doc/acting/README.md index f2046e78..b081c665 100644 --- a/doc/acting/README.md +++ b/doc/acting/README.md @@ -2,7 +2,7 @@ This folder contains the documentation of the acting component. -1. [Architecture](./architecture_documentation.md) -2. [Main frame publisher](./main_frame_publisher.md) -3. [Passthrough](./passthrough.md) +1. [Overview and Architecture](./architecture_documentation.md) +2. [Passthrough](./passthrough.md) +3. [Main frame publisher](./main_frame_publisher.md) 4. [How to test/tune the acting component](./acting_testing.md) \ No newline at end of file diff --git a/doc/acting/passthrough.md b/doc/acting/passthrough.md index d4e42d4d..7c3e7d27 100644 --- a/doc/acting/passthrough.md +++ b/doc/acting/passthrough.md @@ -7,10 +7,16 @@ **Summary:** This page is ought to provide an overview of the passthrough node and reason why it exists -## Overview: +- [Overview](#overview) +- [Reasoning](#reasoning) + +## Overview The passthrough node subscribes to topics on a global scale and republishes them into the "paf/acting" namespace. The control package subscribes to these re-emitted topics. -## Reasoning: +> [!NOTE] +> See [acting architecture](./architecture_documentation.md) for further information. + +## Reasoning Before the control package was outsourced and became its own package it resided within the acting package. Therefor many global dependencies existed in the control package. As the goal of the outsourcing was to eliminate global dependencies in control theory the passthrough node was created as a first stepping diff --git a/doc/control/architecture_documentation.md b/doc/control/architecture_documentation.md index 56725431..9dd55d15 100644 --- a/doc/control/architecture_documentation.md +++ b/doc/control/architecture_documentation.md @@ -52,7 +52,7 @@ which starts the simulation. ### Velocity controllers > [!TIP] -> Follow this link for the ([Documentation](./velocity_controller.md)) on velocity component. +> Follow this link for the [Documentation](./velocity_controller.md) on velocity component. #### velocity_controller.py From 4fb8afbea53b32abaca81659f1ada27bba617a3c Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Sun, 17 Nov 2024 23:36:03 +0100 Subject: [PATCH 30/85] Made the linter happy with newlines and trailing spaces --- doc/acting/README.md | 2 +- doc/acting/architecture_documentation.md | 10 +++++----- doc/acting/passthrough.md | 4 +++- doc/control/README.md | 2 +- doc/control/architecture_documentation.md | 17 ++++++++++------- 5 files changed, 20 insertions(+), 15 deletions(-) diff --git a/doc/acting/README.md b/doc/acting/README.md index b081c665..e9845154 100644 --- a/doc/acting/README.md +++ b/doc/acting/README.md @@ -5,4 +5,4 @@ This folder contains the documentation of the acting component. 1. [Overview and Architecture](./architecture_documentation.md) 2. [Passthrough](./passthrough.md) 3. [Main frame publisher](./main_frame_publisher.md) -4. [How to test/tune the acting component](./acting_testing.md) \ No newline at end of file +4. [How to test/tune the acting component](./acting_testing.md) diff --git a/doc/acting/architecture_documentation.md b/doc/acting/architecture_documentation.md index f4699186..4bb6f520 100644 --- a/doc/acting/architecture_documentation.md +++ b/doc/acting/architecture_documentation.md @@ -14,18 +14,19 @@ navigate on a local basis. This information is then processed in the [control_co ![MISSING: Acting-ARCHITECTURE](./../assets/acting/acting_architecture.png) -> [!NOTE] +> [!NOTE] > [Click here to go to control architecture](./../control/architecture_documentation.md) ## Components of acting ### passthrough.py -> [!TIP] +> [!TIP] > For documentation on passthrough component see: [passthrough](./passthrough.md) ### main_frame_publisher.py -> [!TIP] + +> [!TIP] > Follow this link for [Documentation](./main_frame_publisher.md) on this Node. - Inputs: @@ -41,7 +42,6 @@ navigate on a local basis. This information is then processed in the [control_co - rot_quat = rot as quaternion - **transform** = position x/y/z, rot_quat, Timestamp(now), “global”, “hero” - ### helper_functions.py - **vectors_to_angle_abs(x1: float, y1: float, x2: float, y2: float) -> float**:\ @@ -73,4 +73,4 @@ Interpolate linearly between start and end, with a minimal distance of interval_ - **_clean_route_duplicates(route: List[Tuple[float, float]], min_dist: float) -> List[Tuple[float, float]]**:\ Remove duplicates in the given List of tuples, if the distance between them is less than min_dist. - **interpolate_route(orig_route: List[Tuple[float, float]], interval_m=0.5)**:\ -Interpolate the given route with points inbetween,holding the specified distance interval threshold. \ No newline at end of file +Interpolate the given route with points inbetween,holding the specified distance interval threshold. diff --git a/doc/acting/passthrough.md b/doc/acting/passthrough.md index 7c3e7d27..eabd32b1 100644 --- a/doc/acting/passthrough.md +++ b/doc/acting/passthrough.md @@ -11,13 +11,15 @@ reason why it exists - [Reasoning](#reasoning) ## Overview + The passthrough node subscribes to topics on a global scale and republishes them into the "paf/acting" namespace. The control package subscribes to these re-emitted topics. > [!NOTE] > See [acting architecture](./architecture_documentation.md) for further information. ## Reasoning + Before the control package was outsourced and became its own package it resided within the acting package. Therefor many global dependencies existed in the control package. As the goal of the outsourcing was to eliminate global dependencies in control theory the passthrough node was created as a first stepping -stone towards independence. \ No newline at end of file +stone towards independence. diff --git a/doc/control/README.md b/doc/control/README.md index a51234b3..211d7149 100644 --- a/doc/control/README.md +++ b/doc/control/README.md @@ -5,4 +5,4 @@ This folder contains the documentation of the control component. 1. [Overview and Architecture](./architecture_documentation.md) 2. [Overview of the Velocity Controller](./velocity_controller.md) 3. [Overview of the Steering Controllers](./steering_controllers.md) -4. [Overview of the Vehicle Controller Component](./vehicle_controller.md) \ No newline at end of file +4. [Overview of the Vehicle Controller Component](./vehicle_controller.md) diff --git a/doc/control/architecture_documentation.md b/doc/control/architecture_documentation.md index 9dd55d15..89c44042 100644 --- a/doc/control/architecture_documentation.md +++ b/doc/control/architecture_documentation.md @@ -1,6 +1,6 @@ # Control: Overview and Architecture -**Summary**: +**Summary**: The control component applies control theory based on a local trajectory provided by the [acting component](./../acting/README.md). It uses knowledge of the current state of the vehicle in order to send [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) commands to the Simulator. This component also sends the [/carla/hero/status](https://leaderboard.carla.org/get_started/) command, @@ -19,16 +19,17 @@ which starts the simulation. ![MISSING: Control-ARCHITECTURE](./../assets/control/control_architecture.png) -> [!NOTE] +> [!NOTE] > [Click here to go to acting architecture](./../acting/architecture_documentation.md) ## Summary of Control Components -### Steering controllers -> [!TIP] +### Steering controllers + +> [!TIP] > Follow this link for the [Documentation](./steering_controllers.md) on steering controllers. -#### pure_pursuit_controller.py +#### pure_pursuit_controller.py - Inputs: - **trajectory**: Path @@ -50,7 +51,8 @@ which starts the simulation. - **stanley_steer**: Float32 - **stanley_debug**: StanleyDebug -### Velocity controllers +### Velocity controllers + > [!TIP] > Follow this link for the [Documentation](./velocity_controller.md) on velocity component. @@ -64,6 +66,7 @@ which starts the simulation. - **brake**: Float32 ### vehicle_controller.py + > [!TIP] > Follow this link for [Documentation](./vehicle_controller.md) on vehicle controller. @@ -78,4 +81,4 @@ which starts the simulation. - Outputs: - **vehicle_control_cmd**: [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) - **status**: Bool - - **emergency**: Bool \ No newline at end of file + - **emergency**: Bool From 7ecd33e4d1f19a77d581331292543a3183b0c582 Mon Sep 17 00:00:00 2001 From: Ralf Date: Mon, 18 Nov 2024 17:08:25 +0100 Subject: [PATCH 31/85] update radar node --- code/perception/src/radar_node.py | 61 +++++-------------------------- 1 file changed, 10 insertions(+), 51 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index bd8f351f..b1a7d603 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -30,53 +30,29 @@ def callback(self, data): :param data: a PointCloud2 """ - # coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - - # Center - - # reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( - # coordinates, - # max_x=np.inf, - # min_x=0.0, - # min_z=-1.6, - # ) - # reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] - # reconstruct_coordinates_xyz_center = np.array( - # lidar_filter_utility.remove_field_name( - # reconstruct_coordinates_center, "intensity" - # ).tolist() - # ) - # dist_array_center = self.reconstruct_img_from_lidar( - # reconstruct_coordinates_xyz_center, focus="Center" - # ) - # dist_array_center_msg = self.bridge.cv2_to_imgmsg( - # dist_array_center, encoding="passthrough" - # ) - # dist_array_center_msg.header = data.header - # self.dist_array_center_publisher.publish(dist_array_center_msg) coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - # x_values = coordinates['x'] # rospy.loginfo("Erste 5 x Werte: {x_values[:5]}") # depth_values = coordinates['depth'] # rospy.loginfo("Erste 5 Depth Werte: {depth_values[:5]}") - dtype_info = "\n".join([f"Feld '{name}': {coordinates.dtype[name]}" for name in coordinates.dtype.names]) - + # dtype_info = "\n".join([f"Feld '{name}': {coordinates.dtype[name]}" for name in coordinates.dtype.names]) # rospy.loginfo("DatentypenNeu: " + dtype_info) # funktioniert - # rospy.loginfo("DatentypenAlt: " + coordinates.dtype) - - + #msg = np.min(coordinates['Velocity']) + # rospy.loginfo("DatentypenMsg: " + str(msg.dtype)) + # rospy.loginfo("WertMsg: " + str(msg)) - msg = np.min[coordinates['Range']] + #self.dist_array_radar_publisher.publish(msg) - dtype_msginfo = ["{type(msg).__name__}"] - rospy.loginfo("DatentypenMsg: " + dtype_msginfo) + for coordinate in coordinates: - self.dist_array_radar_publisher.publish(msg) + if coordinate['y'] == 0: + if coordinate['x'] <= 15: + msg = coordinate['Velocity']*3.6 + self.dist_array_radar_publisher.publish(msg) def listener(self): """ @@ -86,23 +62,6 @@ def listener(self): rospy.init_node("lidar_distance") self.bridge = CvBridge() - self.pub_pointcloud = rospy.Publisher( - rospy.get_param( - "~point_cloud_topic", - "/carla/hero/" + rospy.get_namespace() + "_filtered", - ), - PointCloud2, - queue_size=10, - ) - - # publisher for dist_array - - # self.dist_array_center_publisher = rospy.Publisher( - # rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), - # ImageMsg, - # queue_size=10, - # ) - # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( rospy.get_param("~image_distance_topic", "/paf/hero/Radar/array"), From c76df157312d7bfea06e7e0586a8dea456c20aa6 Mon Sep 17 00:00:00 2001 From: ll7 <32880741+ll7@users.noreply.github.com> Date: Tue, 19 Nov 2024 11:32:42 +0100 Subject: [PATCH 32/85] Update the sprint review presentation guideline Fixes #452 --- .../paf24/sprint_review_meeting_guidelines.md | 3 +- doc/development/sprint_review_presentation.md | 82 +++++++------------ 2 files changed, 30 insertions(+), 55 deletions(-) diff --git a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md index 0c41eeef..c5a2e19f 100644 --- a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md +++ b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md @@ -43,7 +43,8 @@ - Example: A team of three has a total of 15 minutes and may allocate time as they see fit. - A unified grade will be given unless individual assessment is warranted. - Timeboxing will be strictly enforced: only content shared within the allotted time will be evaluated. Presentations will be stopped at the time limit. -- TODO The sprint review presentation guideline will be updated. +- The sprint review presentation guideline will be updated. in [#452](https://github.com/una-auxme/paf/issues/452). + - [sprint_review_presentation.md](../../development/sprint_review_presentation.md) will be updated accordingly. ## 3. Sprint Review Schedule diff --git a/doc/development/sprint_review_presentation.md b/doc/development/sprint_review_presentation.md index 0452d84e..2e2e6703 100644 --- a/doc/development/sprint_review_presentation.md +++ b/doc/development/sprint_review_presentation.md @@ -1,76 +1,50 @@ # Sprint Review Presentation -**Summary:** Guidelines for creating effective presentations for Sprint Reviews in the PAF project. +**Summary:** Guidelines for creating effective presentations for the Sprint Reviews in the PAF project. -- [1. General Sprint Progress Overview Presentation](#1-general-sprint-progress-overview-presentation) -- [2. Individual Pull Request (PR) Presentations](#2-individual-pull-request-pr-presentations) -- [3. Presentation Style](#3-presentation-style) +- [1. Group Presentations](#1-group-presentations) +- [2. Presentation Style](#2-presentation-style) Creating a good presentation for a **Sprint Review** in PAF is important for communicating the team's achievements, identifying challenges, and planning for future work. -To present the sprint progress effectively, especially when dealing with complex software projects, it can be beneficial to split the presentations into two distinct parts: +## 1. Group Presentations -1. **General Sprint Progress Overview**: This focuses on the big-picture updates, team-wide accomplishments, challenges, and next steps. -2. **Individual Pull Request (PR) Presentations**: These dive into the details of specific features or changes made during the sprint. +These technical presentations meant to present project progress from the sprint. +Not every PR has to be presented, but **each students contribution should be presented**. -## 1. General Sprint Progress Overview Presentation +**Structure of Presentation**: -This presentation is designed for a broader audience and focuses on the overall progress made during the sprint. It highlights major milestones, project status, and challenges, without diving into technical implementation details. -There should be one general overview presentation per sprint, typically delivered a new student who has not presented the general overview before. - -**Structure of the General Overview**: - -- **Title Slide**: Sprint number, project name, team, and sprint dates. -- **Agenda**: Outline the structure of the presentation. - - *See below* -- **Sprint Goals**: Briefly describe the objectives of the sprint and how they fit into the overall project roadmap. -- **Completed Work**: Provide an overview of features that were completed. This section should focus on **overall vehicle improvement** rather than technical details. - - Optionally include a **demo** of key features. - - **Before-and-after visuals** of new functionality if applicable. -- **In-progress Work**: Mention features or tasks that were started but not completed, along with explanations of why they weren’t finished. -- **Challenges & Blockers**: Present the key blockers and how they were addressed or escalated. If some remain unresolved, suggest plans for mitigation. -- **Sprint Metrics**: Include relevant metrics: - - Any improvements in testing or driving score. -- **Next Steps**: Outline the focus areas for the next sprint, upcoming deadlines, and potential risks. - -**Duration**: 5-20 minutes, depending on the complexity of the sprint. - -## 2. Individual Pull Request (PR) Presentations - -These are more focused, technical presentations meant to review individual pull requests (PRs) from the sprint. They are aimed at the development team and technical stakeholders, providing detailed insight into the code changes, implementation logic, and technical considerations of each PR. -Not every PR has to be presented, but **every student should be able to highlight their contributions**. - -**Structure of the PR Presentation**: - -- **Title Slide**: Pull request title, associated issue number(s), and contributor(s). +- **Title Slide**: Area of contribution, PR numbers, and contributor(s). - **Agenda**: - - *See below* -- **PR Overview**: Start with the problem or issue the PR addresses. - - Describe the goal of the changes (e.g., adding a feature, fixing a bug, refactoring code). -- **Key Accomplishments**: Go over the technical changes made in the PR. - - **Code snippets**: Highlight important parts of the code that were changed or added. - - **Design patterns or architectural choices**: Explain any significant technical decisions. -- **Technical Challenges and Solutions**: Discuss any technical difficulties encountered while implementing the PR. - - Mention how challenges were overcome and what alternatives were considered. -- **Code Review Outcomes**: Summarize any feedback from peer reviews. - - Highlight any requested changes and how they were addressed. - - Point out best practices followed or any areas for future improvement. -- **Testing and Validation**: Show how the changes were tested. + - Clearly outline what will be covered. +- **Overview**: + - Start by describing the problem or feature request being addressed. + - Explain the goal of the changes. +- **Key Accomplishments**: + - Summarize the technical changes made during the sprint. + - Highlight key features implemented or problems solved. + - Design Patterns/Architectural Choices: Explain significant technical decisions. +- **Technical Challenges and Solutions**: + - Discuss challenges encountered and how they were resolved. + - Outline alternative approaches considered, if any. +- **Code Review Outcomes**: + - Summarize feedback received during peer reviews. + - Highlight requested changes and how they were addressed. + - Mention best practices followed and areas for improvement. +- **Testing and Validation**: Explain how the changes were tested. - **Automated tests**: Unit, integration, or end-to-end tests that were added or updated. - **Manual tests**: If manual validation was done, explain the scenarios tested. -- **Demo (if applicable)**: Provide a quick live demo or walkthrough of the feature or bug fix that the PR addresses. -- **Next Steps**: If the PR impacts other work or needs further iterations, describe those next steps. +- **Demo**: Provide a quick live demo or walkthrough of the feature or bug fix that the PR addresses. +- **Next Steps**: If the changes impacts other work or needs further iterations, describe those next steps. -**Duration**: 5-10 minutes per Pull-Request. +**Duration**: **5 minutes** per person. -## 3. Presentation Style +## 2. Presentation Style - **Focus on outcomes**: Highlight the progress made and how it impacts the overall project goals. - **Use visuals and charts**: Use screenshots, graphs, and videos to illustrate progress. -- **Interactive**: Ask for feedback, highlight areas that require input or decisions. - **Keep it high-level**: Avoid too much technical jargon. - **Stay concise**: Respect everyone’s time and keep the presentation focused on what matters most. -- **Collaborate**: Collaborate with the team to ensure all aspects of the sprint are covered. - **Consistent Slide Design**: Use a consistent slide design (fonts, colors, layout) to improve readability. - Templates for AuxMe-Presentations: From 9a693ebc9dbdb7eaedf127717a72cbf85b7e0b3c Mon Sep 17 00:00:00 2001 From: ll7 Date: Tue, 19 Nov 2024 14:49:01 +0100 Subject: [PATCH 33/85] Update sprint review presentation guidelines for clarity and accuracy --- doc/dev_talks/paf24/sprint_review_meeting_guidelines.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md index c5a2e19f..603190f1 100644 --- a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md +++ b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md @@ -43,8 +43,8 @@ - Example: A team of three has a total of 15 minutes and may allocate time as they see fit. - A unified grade will be given unless individual assessment is warranted. - Timeboxing will be strictly enforced: only content shared within the allotted time will be evaluated. Presentations will be stopped at the time limit. -- The sprint review presentation guideline will be updated. in [#452](https://github.com/una-auxme/paf/issues/452). - - [sprint_review_presentation.md](../../development/sprint_review_presentation.md) will be updated accordingly. +- The sprint review presentation guideline was updated in [#452](https://github.com/una-auxme/paf/issues/452). + - The [sprint_review_presentation.md](../../development/sprint_review_presentation.md) is updated. ## 3. Sprint Review Schedule From 0f53cbf316ff40ab67b1a4c18c388452d1781323 Mon Sep 17 00:00:00 2001 From: ll7 Date: Tue, 19 Nov 2024 14:51:40 +0100 Subject: [PATCH 34/85] Add autoware mini to the research section Fixes #389 --- doc/research/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/research/README.md b/doc/research/README.md index 1b2caa70..26cea173 100644 --- a/doc/research/README.md +++ b/doc/research/README.md @@ -52,3 +52,4 @@ In addition to the research of the previous years, the following resources can b - [Awesome 3D Object Detection for Autonomous Driving](https://github.com/PointsCoder/Awesome-3D-Object-Detection-for-Autonomous-Driving) - [Microsoft Autonomous Driving Cookbook](https://github.com/microsoft/AutonomousDrivingCookbook) - [End-to-End Autonomous Driving](https://github.com/OpenDriveLab/End-to-end-Autonomous-Driving) +- [UT-ADL/autoware_mini](https://github.com/UT-ADL/autoware_mini) From 08e9711afb0c2ddb4d5d4f41def316f3216f429b Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 20 Nov 2024 16:54:16 +0100 Subject: [PATCH 35/85] Aleks and Ralf, implemented first distance detection with radar_node --- code/perception/src/radar_node.py | 72 ++++++++++++++++++------------- 1 file changed, 43 insertions(+), 29 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index b1a7d603..1fa98f2e 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -4,14 +4,15 @@ import numpy as np import lidar_filter_utility from sensor_msgs.msg import PointCloud2 - +from sklearn.cluster import DBSCAN # from mpl_toolkits.mplot3d import Axes3D # from itertools import combinations from sensor_msgs.msg import Image as ImageMsg from cv_bridge import CvBridge - -from std_msgs.msg import Float32 - +import json +# from std_msgs.msg import Float32 +from std_msgs.msg import String +from rospy.numpy_msg import numpy_msg # from matplotlib.colors import LinearSegmentedColormap @@ -30,29 +31,10 @@ def callback(self, data): :param data: a PointCloud2 """ - - coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - # x_values = coordinates['x'] - # rospy.loginfo("Erste 5 x Werte: {x_values[:5]}") - - # depth_values = coordinates['depth'] - # rospy.loginfo("Erste 5 Depth Werte: {depth_values[:5]}") - - # dtype_info = "\n".join([f"Feld '{name}': {coordinates.dtype[name]}" for name in coordinates.dtype.names]) - # rospy.loginfo("DatentypenNeu: " + dtype_info) # funktioniert - - #msg = np.min(coordinates['Velocity']) - # rospy.loginfo("DatentypenMsg: " + str(msg.dtype)) - # rospy.loginfo("WertMsg: " + str(msg)) - - #self.dist_array_radar_publisher.publish(msg) - - for coordinate in coordinates: - - if coordinate['y'] == 0: - if coordinate['x'] <= 15: - msg = coordinate['Velocity']*3.6 - self.dist_array_radar_publisher.publish(msg) + + clustered_points = cluster_radar_data_from_pointcloud(data, 10) + clustered_points_json = json.dumps(clustered_points) + self.dist_array_radar_publisher.publish(clustered_points_json) def listener(self): """ @@ -64,9 +46,9 @@ def listener(self): # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Radar/array"), + rospy.get_param("~image_distance_topic", "/paf/hero/Radar/dist_array_unsegmented"), # PointCloud2, - Float32, + String, queue_size=10, ) @@ -79,6 +61,38 @@ def listener(self): rospy.spin() +def pointcloud2_to_array(pointcloud_msg): + cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) + distances = np.sqrt( + cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 + ) + return np.column_stack( + (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) + ) + + +def cluster_radar_data_from_pointcloud( + pointcloud_msg, max_distance, eps=1.0, min_samples=2 +): + + data = pointcloud2_to_array(pointcloud_msg) + + filtered_data = data[data[:, 3] < max_distance] + filtered_data = filtered_data[(filtered_data[:, 1] >= -1) & (filtered_data[:, 1] <= 1) & (filtered_data[:, 2] <= 1.3) & (filtered_data[:, 2] >= -0.7)] + + if len(filtered_data) == 0: + return {} + + coordinates = filtered_data[:, :2] + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) + + labels = clustering.labels_ + clustered_points = {label: list(labels).count(label) for label in set(labels)} + clustered_points = {int(label): count for label, count in clustered_points.items()} + + return clustered_points + + if __name__ == "__main__": lidar_distance = RadarNode() lidar_distance.listener() From f2ae9e85c174c4505ef6362df841a2a03d339eab Mon Sep 17 00:00:00 2001 From: ll7 <32880741+ll7@users.noreply.github.com> Date: Thu, 21 Nov 2024 07:43:08 +0100 Subject: [PATCH 36/85] Refine sprint review presentation guidelines for clarity and conciseness --- doc/development/sprint_review_presentation.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/doc/development/sprint_review_presentation.md b/doc/development/sprint_review_presentation.md index 2e2e6703..b875ff5c 100644 --- a/doc/development/sprint_review_presentation.md +++ b/doc/development/sprint_review_presentation.md @@ -9,7 +9,7 @@ Creating a good presentation for a **Sprint Review** in PAF is important for com ## 1. Group Presentations -These technical presentations meant to present project progress from the sprint. +These are technical presentations meant to present project progress from the sprint. Not every PR has to be presented, but **each students contribution should be presented**. **Structure of Presentation**: @@ -34,7 +34,8 @@ Not every PR has to be presented, but **each students contribution should be pre - **Testing and Validation**: Explain how the changes were tested. - **Automated tests**: Unit, integration, or end-to-end tests that were added or updated. - **Manual tests**: If manual validation was done, explain the scenarios tested. -- **Demo**: Provide a quick live demo or walkthrough of the feature or bug fix that the PR addresses. +- **Demo**: Provide a quick demo or walkthrough of the feature or bug fix that the PR addresses. + - Prepare screenshots or recordings. - **Next Steps**: If the changes impacts other work or needs further iterations, describe those next steps. **Duration**: **5 minutes** per person. From 9cb4c9e5287aebbb23ea213df5b9470ec42da63e Mon Sep 17 00:00:00 2001 From: vinzenzm <73160933+vinzenzm@users.noreply.github.com> Date: Thu, 21 Nov 2024 09:32:40 +0100 Subject: [PATCH 37/85] Renamed passthrough dataclass to TopicMapping in passthrough --- code/acting/src/acting/passthrough.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/code/acting/src/acting/passthrough.py b/code/acting/src/acting/passthrough.py index 253e108c..3d49d207 100755 --- a/code/acting/src/acting/passthrough.py +++ b/code/acting/src/acting/passthrough.py @@ -13,7 +13,7 @@ @dataclass -class passthrough: +class TopicMapping: pub_name: str sub_name: str topic_type: Type @@ -28,34 +28,34 @@ class Passthrough(CompatibleNode): role_name = "hero" # Legacy will change soon # Topics for velocity controller. - target_velocity = passthrough( + target_velocity = TopicMapping( pub_name="/paf/acting/target_velocity", sub_name=f"/paf/{role_name}/target_velocity", topic_type=Float32, ) # Topics for steering controllers - trajectory = passthrough( + trajectory = TopicMapping( pub_name="/paf/acting/trajectory", sub_name=f"/paf/{role_name}/trajectory", topic_type=Path, ) - position = passthrough( + position = TopicMapping( pub_name="/paf/acting/current_pos", sub_name=f"/paf/{role_name}/current_pos", topic_type=PoseStamped, ) - heading = passthrough( + heading = TopicMapping( pub_name="/paf/acting/current_heading", sub_name=f"/paf/{role_name}/current_heading", topic_type=Float32, ) - passthrough_topics = [target_velocity, trajectory, position, heading] + mapped_topics = [target_velocity, trajectory, position, heading] def __init__(self): self.publishers: Dict[str, Publisher] = {} self.subscribers: Dict[str, Subscriber] = {} - for topic in self.passthrough_topics: + for topic in self.mapped_topics: self.publishers[topic.pub_name] = self.new_publisher( topic.topic_type, topic.pub_name, qos_profile=1 ) From 0af4cc90c99b22e64cc1bcf269a01f085a02a3c6 Mon Sep 17 00:00:00 2001 From: Ralf Date: Thu, 21 Nov 2024 13:13:30 +0100 Subject: [PATCH 38/85] Add radar_node.md --- doc/perception/radar_node.md | 36 ++++++++++++++++++++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100644 doc/perception/radar_node.md diff --git a/doc/perception/radar_node.md b/doc/perception/radar_node.md new file mode 100644 index 00000000..26783bc2 --- /dev/null +++ b/doc/perception/radar_node.md @@ -0,0 +1,36 @@ +# Radar Node + +**Summary:** This page explains what the radar sensor does. + +- [Radar offsets](#radar-offsets) +- [Radar specification](#radar-specification) +- [Radar data output for each detected point](#radar-data-output-for-each-detected-point) +- [Todo](#todo) + +## Radar offsets + +- x: 2 +- y: 0 +- z: 0.7 + +## Radar specification + +- points per second: 1500 points generated by all lasers per second +- maximum range: 100 meters +- horizontal fov: 30 degrees +- vertical fov: 30 degrees + +## Radar data output for each detected point + +- x +- y +- z +- Range +- Velocity +- AzimuthAngle +- ElevationAngle + +## Todo + +- Discuss further processing of radar data +- Combine lidar, radar and camera data From cfbd1700b1537a086bc5a3b97b73da27e270c6d8 Mon Sep 17 00:00:00 2001 From: seefelke Date: Thu, 21 Nov 2024 18:36:02 +0100 Subject: [PATCH 39/85] Added new message types Trajectory and Navigation Point. Added Behaviour Enum in localplanning/utils.py --- code/planning/CMakeLists.txt | 23 ++++++++++++++++------- code/planning/msg/NavigationPoint.msg | 3 +++ code/planning/msg/Trajectory.msg | 2 ++ code/planning/package.xml | 4 ++++ code/planning/src/local_planner/utils.py | 7 +++++++ 5 files changed, 32 insertions(+), 7 deletions(-) create mode 100644 code/planning/msg/NavigationPoint.msg create mode 100644 code/planning/msg/Trajectory.msg diff --git a/code/planning/CMakeLists.txt b/code/planning/CMakeLists.txt index 34c3ccd0..9da52430 100755 --- a/code/planning/CMakeLists.txt +++ b/code/planning/CMakeLists.txt @@ -13,8 +13,11 @@ project(planning) find_package(catkin REQUIRED COMPONENTS perception rospy + rosout roslaunch std_msgs + geometry_msgs + message_generation ) roslaunch_add_file_check(launch) @@ -48,9 +51,11 @@ catkin_python_setup() ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) ## Generate messages in the 'msg' folder -# add_message_files( -# MinDistance.msg -# ) + add_message_files( + FILES + NavigationPoint.msg + Trajectory.msg + ) ## Generate services in the 'srv' folder # add_service_files( @@ -67,9 +72,12 @@ catkin_python_setup() # ) ## Generate added messages and services with any dependencies listed here -# generate_messages( -# perception -# ) + generate_messages( + DEPENDENCIES + std_msgs + perception + geometry_msgs + ) ################################################ ## Declare ROS dynamic reconfigure parameters ## @@ -105,7 +113,8 @@ catkin_package( # LIBRARIES planning # CATKIN_DEPENDS other_catkin_pkg # DEPENDS system_lib - CATKIN_DEPENDS perception rospy +# CATKIN_DEPENDS perception rospy + CATKIN_DEPENDS message_runtime ) ########### diff --git a/code/planning/msg/NavigationPoint.msg b/code/planning/msg/NavigationPoint.msg new file mode 100644 index 00000000..e9eb53c9 --- /dev/null +++ b/code/planning/msg/NavigationPoint.msg @@ -0,0 +1,3 @@ +geometry_msgs/Point position +float32 speed +uint8 behaviour \ No newline at end of file diff --git a/code/planning/msg/Trajectory.msg b/code/planning/msg/Trajectory.msg new file mode 100644 index 00000000..94060cdd --- /dev/null +++ b/code/planning/msg/Trajectory.msg @@ -0,0 +1,2 @@ +Header header +planning/NavigationPoint[] navigationPoints \ No newline at end of file diff --git a/code/planning/package.xml b/code/planning/package.xml index a321a109..daf36bc6 100755 --- a/code/planning/package.xml +++ b/code/planning/package.xml @@ -47,6 +47,9 @@ + message_generation + message_runtime + rospy roslaunch @@ -57,6 +60,7 @@ carla_msgs sensor_msgs std_msgs + geometry_msgs perception perception diff --git a/code/planning/src/local_planner/utils.py b/code/planning/src/local_planner/utils.py index d976506d..5d684df9 100644 --- a/code/planning/src/local_planner/utils.py +++ b/code/planning/src/local_planner/utils.py @@ -3,6 +3,7 @@ import math import carla import os +from enum import IntEnum # import rospy @@ -23,6 +24,12 @@ EARTH_RADIUS_EQUA = 6378137.0 +# getattr(Behaviour, "name").value returns the ID +# Behaviour(id) returns Behaviour.NAME +class Behaviour(IntEnum): + CRUISING = 0 + + def get_distance(pos_1, pos_2): """Calculate the distance between two positions From a4355e7c451a7dbaf616cdb63eb61673091e4d45 Mon Sep 17 00:00:00 2001 From: seefelke <33551476+seefelke@users.noreply.github.com> Date: Thu, 21 Nov 2024 18:51:17 +0100 Subject: [PATCH 40/85] Update code/planning/CMakeLists.txt Co-authored-by: coderabbitai[bot] <136622811+coderabbitai[bot]@users.noreply.github.com> --- code/planning/CMakeLists.txt | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/code/planning/CMakeLists.txt b/code/planning/CMakeLists.txt index 9da52430..c6288e03 100755 --- a/code/planning/CMakeLists.txt +++ b/code/planning/CMakeLists.txt @@ -113,8 +113,7 @@ catkin_package( # LIBRARIES planning # CATKIN_DEPENDS other_catkin_pkg # DEPENDS system_lib -# CATKIN_DEPENDS perception rospy - CATKIN_DEPENDS message_runtime + CATKIN_DEPENDS perception rospy message_runtime ) ########### From 90cf9f31322e3da23e85ccff9160059574ae4727 Mon Sep 17 00:00:00 2001 From: Ludwig Holl Date: Sat, 23 Nov 2024 16:10:40 +0100 Subject: [PATCH 41/85] updated project management.md and issue templates --- .github/ISSUE_TEMPLATE/BUG.yml | 13 ------------- .github/ISSUE_TEMPLATE/FEATURE.yml | 12 ------------ .github/ISSUE_TEMPLATE/ISSUE.yml | 13 ------------- doc/development/project_management.md | 21 +++++++++++++++++++++ 4 files changed, 21 insertions(+), 38 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/BUG.yml b/.github/ISSUE_TEMPLATE/BUG.yml index aee5410c..afed0980 100644 --- a/.github/ISSUE_TEMPLATE/BUG.yml +++ b/.github/ISSUE_TEMPLATE/BUG.yml @@ -35,13 +35,6 @@ body: - The car detects traffic lights on Map1 correctly. - The issue no longer occurs in similar scenarios. - - type: input - id: effort_estimate - attributes: - label: Effort Estimate - description: Approximate effort required (e.g., hours). - placeholder: Enter effort estimate. - - type: textarea id: testability attributes: @@ -59,12 +52,6 @@ body: - type: markdown attributes: value: | - **Add Priority Label**: - - p1: Immediate attention - - p2: High priority - - p3: Standard priority - - p4: Low priority - **Add Group Label**: - perception: Related to sensor processing and scene understanding - planning: Related to path planning and decision making diff --git a/.github/ISSUE_TEMPLATE/FEATURE.yml b/.github/ISSUE_TEMPLATE/FEATURE.yml index 366bab21..3c906a58 100644 --- a/.github/ISSUE_TEMPLATE/FEATURE.yml +++ b/.github/ISSUE_TEMPLATE/FEATURE.yml @@ -19,13 +19,6 @@ body: - Detects 90% of traffic lights. - Correctly identifies 90% of traffic light states. - - type: input - id: effort_estimate - attributes: - label: Effort Estimate - description: Approximate effort required (e.g., hours). - placeholder: Enter effort estimate. - - type: textarea id: testability attributes: @@ -43,11 +36,6 @@ body: - type: markdown attributes: value: | - **Add Priority Label**: - - p1: Immediate attention - - p2: High priority - - p3: Standard priority - - p4: Low priority **Add Group Label**: - perception: Related to sensor processing and scene understanding diff --git a/.github/ISSUE_TEMPLATE/ISSUE.yml b/.github/ISSUE_TEMPLATE/ISSUE.yml index 6ad88fbf..355cb64f 100644 --- a/.github/ISSUE_TEMPLATE/ISSUE.yml +++ b/.github/ISSUE_TEMPLATE/ISSUE.yml @@ -25,13 +25,6 @@ body: - Code review passed - All tests passing - - type: input - id: effort_estimate - attributes: - label: Effort Estimate - description: Approximate effort required (e.g., hours). - placeholder: Enter effort estimate. - - type: textarea id: testability attributes: @@ -58,12 +51,6 @@ body: - question: Further information is requested - wontfix: This will not be worked on - **Add Priority Label**: - - p1: Immediate attention - - p2: High priority - - p3: Standard priority - - p4: Low priority - **Add Group Label**: - perception: Related to sensor processing and scene understanding - planning: Related to path planning and decision making diff --git a/doc/development/project_management.md b/doc/development/project_management.md index 29a1a0f0..cb4d590e 100644 --- a/doc/development/project_management.md +++ b/doc/development/project_management.md @@ -13,6 +13,27 @@ Issues can be added via the [issues overview](https://github.com/una-auxme/paf/i By clicking "New issue" in the overview you have different templates to create the issue. +After creating the issue it has to be added to the project board. The project board is used to keep track of the +progress of the issue. The project board can be found [here](https://github.com/orgs/una-auxme/projects/3). + +For tracking time and complexity of the issue we will use the predefined `Priority` and `Size` states of the PAF Project +Backlog Board. + +Priority has following states: +- `Urgent`: Critical bug causing system crash, needs immediate fix. +- `High`: Major feature request or significant bug affecting many users. +- `Medium`: Minor feature request or bug with a workaround. +- `Low`: Cosmetic changes or minor improvements. + +Size has following states: +- `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes. +- `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours. +- `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days. +- `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks. +- `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should + be tagged with this size. + + ## 2. Create a Pull Request To create a pull request, go to the [branches overview](https://github.com/una-auxme/paf/branches) and select ``New Pull Request`` for the branch you want to create a PR for. From 9c40f314a3aeb82a7cf825f631158fab48d2ad05 Mon Sep 17 00:00:00 2001 From: Ludwig Holl Date: Sat, 23 Nov 2024 16:12:58 +0100 Subject: [PATCH 42/85] added size and prio information to the issue templates --- .github/ISSUE_TEMPLATE/BUG.yml | 15 +++++++++++++++ .github/ISSUE_TEMPLATE/FEATURE.yml | 15 +++++++++++++++ .github/ISSUE_TEMPLATE/ISSUE.yml | 15 +++++++++++++++ 3 files changed, 45 insertions(+) diff --git a/.github/ISSUE_TEMPLATE/BUG.yml b/.github/ISSUE_TEMPLATE/BUG.yml index afed0980..0bdbe38e 100644 --- a/.github/ISSUE_TEMPLATE/BUG.yml +++ b/.github/ISSUE_TEMPLATE/BUG.yml @@ -59,3 +59,18 @@ body: - system: Related to the general behavior of the system - research: Related to research and experimentation - infrastructure: Related to system infrastructure and setup + + **Add Labels on the Project Board**: + **Priority:** + - `Urgent`: Critical bug causing system crash, needs immediate fix. + - `High`: Major feature request or significant bug affecting many users. + - `Medium`: Minor feature request or bug with a workaround. + - `Low`: Cosmetic changes or minor improvements. + + **Size:** + - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes. + - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours. + - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days. + - `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks. + - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should + be tagged with this size. diff --git a/.github/ISSUE_TEMPLATE/FEATURE.yml b/.github/ISSUE_TEMPLATE/FEATURE.yml index 3c906a58..bdb42505 100644 --- a/.github/ISSUE_TEMPLATE/FEATURE.yml +++ b/.github/ISSUE_TEMPLATE/FEATURE.yml @@ -44,3 +44,18 @@ body: - system: Related to the general behavior of the system - research: Related to research and experimentation - infrastructure: Related to system infrastructure and setup + + **Add Labels on the Project Board**: + **Priority:** + - `Urgent`: Critical bug causing system crash, needs immediate fix. + - `High`: Major feature request or significant bug affecting many users. + - `Medium`: Minor feature request or bug with a workaround. + - `Low`: Cosmetic changes or minor improvements. + + **Size:** + - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes. + - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours. + - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days. + - `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks. + - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should + be tagged with this size. diff --git a/.github/ISSUE_TEMPLATE/ISSUE.yml b/.github/ISSUE_TEMPLATE/ISSUE.yml index 355cb64f..e5cbc82c 100644 --- a/.github/ISSUE_TEMPLATE/ISSUE.yml +++ b/.github/ISSUE_TEMPLATE/ISSUE.yml @@ -58,3 +58,18 @@ body: - system: Related to the general behavior of the system - research: Related to research and experimentation - infrastructure: Related to system infrastructure and setup + + **Add Labels on the Project Board**: + **Priority:** + - `Urgent`: Critical bug causing system crash, needs immediate fix. + - `High`: Major feature request or significant bug affecting many users. + - `Medium`: Minor feature request or bug with a workaround. + - `Low`: Cosmetic changes or minor improvements. + + **Size:** + - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes. + - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours. + - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days. + - `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks. + - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should + be tagged with this size. From bf594eee06f564485a0233ed2a6a7c178f5027e9 Mon Sep 17 00:00:00 2001 From: Ludwig Holl Date: Sat, 23 Nov 2024 16:18:58 +0100 Subject: [PATCH 43/85] fixed md linter --- doc/development/project_management.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/doc/development/project_management.md b/doc/development/project_management.md index cb4d590e..ef5e45d7 100644 --- a/doc/development/project_management.md +++ b/doc/development/project_management.md @@ -13,19 +13,21 @@ Issues can be added via the [issues overview](https://github.com/una-auxme/paf/i By clicking "New issue" in the overview you have different templates to create the issue. -After creating the issue it has to be added to the project board. The project board is used to keep track of the +After creating the issue it has to be added to the project board. The project board is used to keep track of the progress of the issue. The project board can be found [here](https://github.com/orgs/una-auxme/projects/3). For tracking time and complexity of the issue we will use the predefined `Priority` and `Size` states of the PAF Project Backlog Board. Priority has following states: + - `Urgent`: Critical bug causing system crash, needs immediate fix. - `High`: Major feature request or significant bug affecting many users. - `Medium`: Minor feature request or bug with a workaround. - `Low`: Cosmetic changes or minor improvements. Size has following states: + - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes. - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours. - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days. @@ -33,7 +35,6 @@ Size has following states: - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should be tagged with this size. - ## 2. Create a Pull Request To create a pull request, go to the [branches overview](https://github.com/una-auxme/paf/branches) and select ``New Pull Request`` for the branch you want to create a PR for. From 668b6d745a1a443aa265330d47a5e562006946d0 Mon Sep 17 00:00:00 2001 From: seefelke Date: Sun, 24 Nov 2024 11:45:39 +0100 Subject: [PATCH 44/85] refactored enum into seperate file --- code/planning/src/BehaviourEnum.py | 8 ++++++++ code/planning/src/local_planner/utils.py | 7 ------- 2 files changed, 8 insertions(+), 7 deletions(-) create mode 100644 code/planning/src/BehaviourEnum.py diff --git a/code/planning/src/BehaviourEnum.py b/code/planning/src/BehaviourEnum.py new file mode 100644 index 00000000..361b0b43 --- /dev/null +++ b/code/planning/src/BehaviourEnum.py @@ -0,0 +1,8 @@ +from enum import IntEnum + +# getattr(Behaviour, "name").value returns the ID +# Behaviour(id) returns Behaviour.NAME + + +class BehaviourEnum(IntEnum): + CRUISING = 0 diff --git a/code/planning/src/local_planner/utils.py b/code/planning/src/local_planner/utils.py index 5d684df9..d976506d 100644 --- a/code/planning/src/local_planner/utils.py +++ b/code/planning/src/local_planner/utils.py @@ -3,7 +3,6 @@ import math import carla import os -from enum import IntEnum # import rospy @@ -24,12 +23,6 @@ EARTH_RADIUS_EQUA = 6378137.0 -# getattr(Behaviour, "name").value returns the ID -# Behaviour(id) returns Behaviour.NAME -class Behaviour(IntEnum): - CRUISING = 0 - - def get_distance(pos_1, pos_2): """Calculate the distance between two positions From 4ca5de6d8dfe5792774bf93a9844426e71497c7a Mon Sep 17 00:00:00 2001 From: vinzenzm Date: Sun, 24 Nov 2024 14:41:57 +0100 Subject: [PATCH 45/85] Fixed incorrect transformation in MainFramePublisher The hero frame was rotated 180 degrees from its true orientation. The code publishing this hero frame was cleaned up, the bug fixed. --- code/acting/src/acting/MainFramePublisher.py | 41 ++++++++++---------- 1 file changed, 21 insertions(+), 20 deletions(-) diff --git a/code/acting/src/acting/MainFramePublisher.py b/code/acting/src/acting/MainFramePublisher.py index a34240e8..50fb47c7 100755 --- a/code/acting/src/acting/MainFramePublisher.py +++ b/code/acting/src/acting/MainFramePublisher.py @@ -1,6 +1,4 @@ #!/usr/bin/env python - -from math import pi, cos, sin import ros_compatibility as roscomp import rospy from geometry_msgs.msg import PoseStamped @@ -9,6 +7,8 @@ from scipy.spatial.transform import Rotation as R from std_msgs.msg import Float32 +import numpy as np + class MainFramePublisher(CompatibleNode): @@ -49,27 +49,28 @@ def loop(timer_event=None): if self.current_pos is None: # conversion only works if pos is known return - rot = -self.current_heading - pos = [0, 0, 0] - pos[0] = ( - cos(rot) * self.current_pos.pose.position.x - - sin(rot) * self.current_pos.pose.position.y - ) - pos[1] = ( - sin(rot) * self.current_pos.pose.position.x - + cos(rot) * self.current_pos.pose.position.y + + # The following converts the current_pos as well as the current_heading + # messages we receive into tf transforms. + + position = np.array( + [ + self.current_pos.pose.position.x, + self.current_pos.pose.position.y, + self.current_pos.pose.position.z, + ] ) - pos[2] = -self.current_pos.pose.position.z - rot_quat = R.from_euler( - "xyz", [0, 0, -self.current_heading + pi], degrees=False - ).as_quat() + rotation = R.from_euler("z", self.current_heading, degrees=False).as_quat() + + # The position and rotation are "the hero frame in global coordinates" + # Therefore we publish the child hero with respect to the parent global br.sendTransform( - pos, - rot_quat, - rospy.Time.now(), - "global", - "hero", + translation=position, + rotation=rotation, + time=rospy.Time.now(), + child="hero", + parent="global", ) self.new_timer(self.control_loop_rate, loop) From ae01b8de9792bdd5a4edc5e90096355e55d89e98 Mon Sep 17 00:00:00 2001 From: Ralf Bernitt Date: Sun, 24 Nov 2024 18:57:00 +0100 Subject: [PATCH 46/85] finish radar node --- code/perception/src/radar_node.py | 54 ++++++------------------------- 1 file changed, 10 insertions(+), 44 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 1fa98f2e..9b54bd18 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -4,15 +4,14 @@ import numpy as np import lidar_filter_utility from sensor_msgs.msg import PointCloud2 -from sklearn.cluster import DBSCAN + # from mpl_toolkits.mplot3d import Axes3D # from itertools import combinations from sensor_msgs.msg import Image as ImageMsg from cv_bridge import CvBridge -import json -# from std_msgs.msg import Float32 -from std_msgs.msg import String -from rospy.numpy_msg import numpy_msg + +from std_msgs.msg import Float32 + # from matplotlib.colors import LinearSegmentedColormap @@ -31,10 +30,10 @@ def callback(self, data): :param data: a PointCloud2 """ - - clustered_points = cluster_radar_data_from_pointcloud(data, 10) - clustered_points_json = json.dumps(clustered_points) - self.dist_array_radar_publisher.publish(clustered_points_json) + + coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + msg = np.min(coordinates["Velocity"]) + self.dist_array_radar_publisher.publish(msg) def listener(self): """ @@ -46,9 +45,8 @@ def listener(self): # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Radar/dist_array_unsegmented"), - # PointCloud2, - String, + rospy.get_param("~image_distance_topic", "/paf/hero/Radar/velocity"), + Float32, queue_size=10, ) @@ -61,38 +59,6 @@ def listener(self): rospy.spin() -def pointcloud2_to_array(pointcloud_msg): - cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) - distances = np.sqrt( - cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 - ) - return np.column_stack( - (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) - ) - - -def cluster_radar_data_from_pointcloud( - pointcloud_msg, max_distance, eps=1.0, min_samples=2 -): - - data = pointcloud2_to_array(pointcloud_msg) - - filtered_data = data[data[:, 3] < max_distance] - filtered_data = filtered_data[(filtered_data[:, 1] >= -1) & (filtered_data[:, 1] <= 1) & (filtered_data[:, 2] <= 1.3) & (filtered_data[:, 2] >= -0.7)] - - if len(filtered_data) == 0: - return {} - - coordinates = filtered_data[:, :2] - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) - - labels = clustering.labels_ - clustered_points = {label: list(labels).count(label) for label in set(labels)} - clustered_points = {int(label): count for label, count in clustered_points.items()} - - return clustered_points - - if __name__ == "__main__": lidar_distance = RadarNode() lidar_distance.listener() From a8a585e3451169b9cf60365cf4b5a686916deef1 Mon Sep 17 00:00:00 2001 From: Ralf Bernitt Date: Sun, 24 Nov 2024 19:28:29 +0100 Subject: [PATCH 47/85] Bug fixes --- code/perception/src/radar_node.py | 32 +++++++++++-------------------- 1 file changed, 11 insertions(+), 21 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 9b54bd18..04a9d59b 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -2,33 +2,24 @@ import rospy import ros_numpy import numpy as np -import lidar_filter_utility from sensor_msgs.msg import PointCloud2 - -# from mpl_toolkits.mplot3d import Axes3D -# from itertools import combinations -from sensor_msgs.msg import Image as ImageMsg -from cv_bridge import CvBridge - from std_msgs.msg import Float32 -# from matplotlib.colors import LinearSegmentedColormap - class RadarNode: - """See doc/perception/lidar_distance_utility.md on - how to configute this node + """See doc/perception/radar_node.md on + how to configure this node """ def callback(self, data): - """Callback function, filters a PontCloud2 message - by restrictions defined in the launchfile. + """Process radar Point2Cloud data and publish minimum velocity. - Publishes a Depth image for the specified camera angle. - Each angle has do be delt with differently since the signs of the - coordinate system change with the view angle. + Extracts velocity information from radar data + and publishes the minimum velocity as a + Float32 message - :param data: a PointCloud2 + Args: + data: Point2Cloud message containing radar data with velocity field """ coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) @@ -40,8 +31,7 @@ def listener(self): Initializes the node and it's publishers """ # run simultaneously. - rospy.init_node("lidar_distance") - self.bridge = CvBridge() + rospy.init_node("radar_node") # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( @@ -60,5 +50,5 @@ def listener(self): if __name__ == "__main__": - lidar_distance = RadarNode() - lidar_distance.listener() + radar_node = RadarNode() + radar_node.listener() From f764ca38f87c657bcdb4777a2fda31b11683a7ad Mon Sep 17 00:00:00 2001 From: Ralf Bernitt Date: Sun, 24 Nov 2024 22:29:51 +0100 Subject: [PATCH 48/85] Added clustering of radar data --- code/perception/src/radar_node.py | 57 +++++++++++++++++++++++++------ 1 file changed, 46 insertions(+), 11 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 04a9d59b..ca3cded6 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -2,8 +2,10 @@ import rospy import ros_numpy import numpy as np +from std_msgs.msg import String from sensor_msgs.msg import PointCloud2 -from std_msgs.msg import Float32 +from sklearn.cluster import DBSCAN +import json class RadarNode: @@ -12,19 +14,19 @@ class RadarNode: """ def callback(self, data): - """Process radar Point2Cloud data and publish minimum velocity. + """Process radar Point2Cloud data and publish clustered data points. - Extracts velocity information from radar data - and publishes the minimum velocity as a - Float32 message + Extracts information from radar data + and publishes the clustered radar data + points as a String message Args: - data: Point2Cloud message containing radar data with velocity field + data: Point2Cloud message containing radar data """ - coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - msg = np.min(coordinates["Velocity"]) - self.dist_array_radar_publisher.publish(msg) + clustered_points = cluster_radar_data_from_pointcloud(data, 10) + clustered_points_json = json.dumps(clustered_points) + self.dist_array_radar_publisher.publish(clustered_points_json) def listener(self): """ @@ -35,8 +37,10 @@ def listener(self): # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Radar/velocity"), - Float32, + rospy.get_param( + "~image_distance_topic", "/paf/hero/Radar/dist_array_unsegmented" + ), + String, queue_size=10, ) @@ -49,6 +53,37 @@ def listener(self): rospy.spin() +def pointcloud2_to_array(pointcloud_msg): + cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) + distances = np.sqrt( + cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 + ) + return np.column_stack( + (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) + ) + + +def cluster_radar_data_from_pointcloud( + pointcloud_msg, max_distance, eps=1.0, min_samples=2 +): + data = pointcloud2_to_array(pointcloud_msg) + filtered_data = data[data[:, 3] < max_distance] + filtered_data = filtered_data[ + (filtered_data[:, 1] >= -1) + & (filtered_data[:, 1] <= 1) + & (filtered_data[:, 2] <= 1.3) + & (filtered_data[:, 2] >= -0.7) + ] + if len(filtered_data) == 0: + return {} + coordinates = filtered_data[:, :2] + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) + labels = clustering.labels_ + clustered_points = {label: list(labels).count(label) for label in set(labels)} + clustered_points = {int(label): count for label, count in clustered_points.items()} + return clustered_points + + if __name__ == "__main__": radar_node = RadarNode() radar_node.listener() From 292075598cab544f4351a9865bcc9e9c80999b14 Mon Sep 17 00:00:00 2001 From: asamluka Date: Mon, 25 Nov 2024 04:37:02 +0100 Subject: [PATCH 49/85] Updated the architeture_current.md with the current state of the system. --- doc/assets/overview.jpg | Bin 113753 -> 61362 bytes doc/general/README.md | 3 +- doc/general/architecture_current.md | 348 ++++++++++++++++++ ...rchitecture.md => architecture_planned.md} | 67 ++-- 4 files changed, 392 insertions(+), 26 deletions(-) create mode 100644 doc/general/architecture_current.md rename doc/general/{architecture.md => architecture_planned.md} (87%) diff --git a/doc/assets/overview.jpg b/doc/assets/overview.jpg index 3bdc9225299eff033503f29dafce75defacaa958..7c6b3c76577a342fcb394619d1cce63e5df4c314 100644 GIT binary patch literal 61362 zcmeFZ2V7LWwm!UvB27gQ6cibnQbj>J!ce65UIeKkpn!mah&U8c=^ZS{AiXP1P*hOq zAiYTuk=~`3Y5#x?J@5OS_uNzNz2EQZkC|k4c6O4TtUPP2Ckx+${{-z*mRFL8U@#bD z4*o;LoW>VsqGgAO450fT&0bE|TmfgfT+|R4_s+7`_sMgVqy+aoHN0Z~tHfgha%< zNJz=ZDL{eZeGmbRkdT0gkeHZ=2$c2$*C8S*VrphS>0SG^EJ#?KY50929+R@l1%*Y$&q_+4zj*tuvZ}hK zwywUdy`!_MyXQmi(C6Wi(XsJ~$*G0KrR9~?we^k7t$x8E!mr)>(X-$BMFsjrKtx1H zM6%T{7=b(ZBcviCX6D;PEv-dj;k=)P--nb&CgO4a8#2~Y+FxibU0TTxun7zuUD)c{ zcF+D=$9(@wJ^RtIpZ)5Ez}o{akB|yNKr<7G1c4C8|9$+6#y~km@aWOEXH7&5toyT0 zDzY)+lA`P!3Gk3D9%_Hojs1eC4x5EQy zeBl2s{ijBw{qbv~JfdUtNp9Nju6vWxH6xwX)K2C*20kXHfwZK4evlb)e7 zA%mS|-*%-K~gomoMcBW@W;Kr%_h!QX_P~uPO5bIex(-QH1)4FAMR+o`W<5xG> z@er-T&U9h8mwnu2+{ZB7jk$6*JoGtZXL{9zGFN+UXH$2k8Jnb6vP|EhuOl{=USOi| zP+;=T^oLr>VwF;)lL8)+bT^AcF6iz|dy10$|Dwy8GsTMY7i?qclh2zDzNDya65p@% zCbz-=n%W2cmE%fJcTNm2MY_%JHeQE4NP3X;f;%_0RiB>3eB|a;UVYjcq#g3d;y>|y z@wbgjUxD|UEstNtLpLZFlF=%-__^|VADn<|;tR^zALUxHsXL@Xiz&%!99DDyIY@}H z#kJv~bnz$XPsk9430}XSHT-;F=#_)gJ1amGl}|QJtTuA~;fJewYI#znp^_zrZnxx84A?d|9TuG=)4FgfTy{$aG~z8Qd+ z{_KRM>x?nI9i(f(XYm)Bq4y9c(>1tKZ8jE@inyynA32WfIMIQJ#Cl`L zcZm<3>ChjK{;kj-Woez{@KAUPYNZl6q4!AR*3?@h?crquzS*Awa63iSkIaa|wqvp$ zg<-CpMRp&>$>e9937E)pk@*W?;&B0Zi2pb`9}gLKp(;h@%#vQH{r8{{ZiG4>(qhNn zP{TvXhYGTvw%P}d@%#li#8rr_HSWWeHelL{(ih0$Ci0Sg>j9BqtuY?TFw4YU%{|_< z+x=}oMxI|iIR}*F{dYb}lJHQiw#Mcs#4=YPimdY%j!SqVPp9{{+gMT9GpIS#sO}76 z_-!BV`H4l^kaM>b69UKC{z?Z9pV%P%h%AGzCAkrATMJM)DZTp;>BjwCk9n6YZ?3 z!9ImCVqQ}2Y1E|J#q`+fCY5PTqp@J#51t7j6Xqr2l;!c_>8}`EUP`>6eotEPF$@4FmSIr&P zWUd5tr>f}pMBWO#KjS2Q&RV%m>?}RS$t9fjJEA<1Y~h0+&y*P*bd;)fM%AZ^A69N!puSENK>|FRjIc|t;y@k9ye#C zH(ZN)HSTIF&s2`#^Ftgs_BKu!)I>N9(gHU1@77qb!WL$639 zBxsuycb24oG0+@Cq#1y@ognqvX12^AQ*>6-*gpF})RRUW%@#4?ZU(W}&pQcds_ogFVT;Lp%( zAT=%bKHag_MKDJfbKW+^-%o*w{taWthWBj;{W$IDi)Y1HJdFlzpsW4ip(ug5q` ztQv@{j<_mi$C0^|-TLD3o@yZM_}Y~w`!c(}mv6=`OiPAsn{F2K3Jdx>>RsF)bVKRX z93C=+s>PgD1DhLc_hL4b4bn~8M=2d%`>BO$%PmP_5-zAGbe{OIz}8%bwI!sRtYS!< zHhU~%c*}|51Xp5!$OW}GuYI3f5@nzM7z?R`ZSWZ&qOV5?p(A2q4nhY zsamC)TIAdEy16JQWwrG$Ny{M0EGf64DvtpmboaLo?CWN}hm+z`{oZR>ZAG%On^ zCH`D6|G^ZQk&yedr!`zES9d$|9;+|%rb1WG8tL`eqR`4UIHUs}nxDc$A@E*(#1h&G z4YiBSVe0q$m*bzl(XFM4QvS>D$m9VAngo+U0}8xi#1zFY9#!(Jq|qmKl!+STkkrY z``jq+PIc~%qItc#f#lb%WK`K@U3eUgGWbF?me zsS_dg?OLccW4)>0x0}9Q5)JqK>lLE@phB;Irow-D3x8Dj>ak*^y-T!tg=`NVD%KK; zR}U5xl~1}fk&)-xy+gEYNzL!thmpRq|AP-_vrQ}LCS4B ze`(kOi~pTnY?~}p5S$%;$D&vo>?mJ5aZ%a6jZ6H2u7UJlu}b^}!^J;Xn~zm zf^M=h4rX&<^V)(w5)+nu-xOh#|{06YddY=BN)Ot!~ES8nP;KMQHXijgl6TtZLQ z6h@_X{kN8n4>v1| zO$FA1+^7jI_AigW zS$$l67&>T!d>7+Zu2ySQ0b7OfC!pj)%$*qFSWL!!#>sg97jr?unHkkVPW0r78($Vl zumZ+qvOUsr%sa+SRIKyeXBn%>i#guEDiknEGaKH^?b`U;CjE!m zwpL_U-7+n$Dl4m-wJ7M#9D8n#n8G68+Algx69nY{& znh1W`gXXLhTT(bNOF=%f;!*Xzl(JG3a*%fU)yPhAhOnYD2u}UHc1v>3-9L3Q&bqEV zIQ4$GimCN)Q=9a<0U!Hj_2z@#IGv`NOSfCkCYb*PWl29a2=`1QF(dO!Ve%e~?j&>omX^(QS{Vs+=i{^;wtrOM-~XEyV_JT8z7}=hI0sh> zd~x5)P4-2Bmb-+)J-DiohH-}vYkLRRN~{>Mu4-4$KaaET4+u`IHgJ1;@>Kkd*RPP| ziBzp44<<=a$3~nU@+X=}!8SBHtR_1;+->ATk3K^y6RXuKH>$v8YilqR5_UeeOKuSJM7SG!M~y3=suHoZ_plcYnHgt*N;Qf=Xq28y<+sq=Nw3~SYhRpSSy=(9-F$i~Z= zfilO|V5_leFGO`X8H2Vei~PlyJG}BnG0zrC*q@BQHVr=${j&vc)B@-c>_(_hAM zcF~z1o@`T)l@}h}Mp+EdfCMqz{tmhZw;_0k8(tJ}Zb|FFRA|sE*V{zr}%n0MT~`y3F@YO);K=1@413aExJnU-iZz$pY@IgmcnQf9thzxiOJ%z=Qz)! zyH9cIRBdV^LBu_-SVxFnU^lHF$N3Se2o)*P#w;ltD8Hg^%3dUoB_=SL!B>Gx-npB8 zN}}q}-PpigECnxaYtw5m`Gwor!F06oP?$9^;(ftG6IIz)Hld#m1uz%lAK4ErF!L=J zcS-#wV(z56QX_MmGIKMpo}O{5b)bDd_M4pg!>pZc`Ly*Wc_4~H?BrmTd=+iI=Wj?3 zz>9NFvs(g)X?>Xg{=0x_%Y6i1wEr|FR8%Bn^X4Gf@9wzwbf?wCOH^CbtPvhE*xihW zV11Yc^-9+~pD`1789~_EAiVaF(10+eD8S2iKh~DgV}m4$58cg+7|??^9+Ir59E{b+ zLp~9hd?}aLIg&LbR|aqk>>F)C;^xMa*XU#i^7{NjZ!rt42eZShneWio5pm4FAzIMp9degE(Rk{V zGR2b+lI%j6mL{~)cG=_emMAQN=2x)WW7GTIHXayET_?60!FeZk}h|6 zuE;a2=pcDR%wX_%NX7oX?xi#WNj$^_FY?O9YW9sfHQ~_Da7V7C7oDmtI2|GqL8W}l zW!H>r#iymdRHkDc<-;Ek(=QR5eD(t>P*V8YpP1tR=KXK9hG?ief|cG)k8zy#U>`HW zIT$s^=`w8HK|I6 zW#6b-NfZ^2;_|11V6*BehTlcXnd=X#^Qz7$bH^uU0sGA&RoV7FeqbVnkky}s*Fe-Y zQe{78a=Ak8ymO5CJCRz^)I=iv-TWz3Q=E2C;G5gJzNbPtZMWUy1ZnAbh_NmdfuzI* z8$Sf14Oryn!*H+m*a~!O_8~CK!FZ^Ga=kSG551zt>`_l%lU>8zMT!Y);Gxq|I5c8N z{&8Z0^}8I=O+iM_uvbKWi-@kE*Y67EI7-bv8Z<$ZVy+i}(y~ z|Nl(HMoc%)o3^*5mzBv~%J|a$;=tv;S@oqS<>O5!(0B+B^|Zjo&5+IUW@}ry{N$$B zK$R6KpWn(^Ns&DA0u(T3^!KLwo*sa`*U4hBRs>6z1&a;|I;1>%ZdlM;~5%;Mj`JPKxN$wy^P$zlb zvl8*p(s=A>yWegP+8DlK$BNxIymVS?tY3JbgaU{5!4#?{*sSh}JHD2BhB5Fy;y$7+ ztiTUfU}T0P4jT<5jCoaaG>6nBpGmTGd@0k8CQ_zVsuFC$KcogxMzfA#XOFG2jMS7= z4*BzQW2@p0{o=t6Qt;CGEASdKasD}mN{a7G{oFV z;yy#cz52Y?j)iL1np`#=JXG_d;mYyoYJULmnI#lhCo5`<1qkTpj@=e891SJnS5ysS zl73VZ9Alv)*q+-#akTCHTio11+0uk{RyI$+b@z00ftZ*M{_u)rrV;HfD{>BkG{7Na ztiwa5LwKk)NPlv9pO&JU-EopjX3HH0I&#|^>Dfms%{WwC@=!40zi&qr5JohSncJ+@? zT5c9RY8>fFmR52g(DJ7yx^FqpQe!1#MX;DR{ZZ(LJxL{}D}L2%w?zPy)xugwUZ%ms z=2o+=?fF1DC9kt)0~mi1)OcvPd`Ka3aB1NLP8>&*gN|utd^1vl!KmP&P(0+%sDf;+ zEMK2r*SgRzI^1&_NF!7La$)dGa-Gx0dK?})f``a?(05LIlKiN|<7drssLSJF=8I=> zH;;lhfqWZww0!)t8O9yMQ8>r2fYZu(vcC#FZr<#>SAsGzH}@d+5=vT!d$G`7=&EI# z5J#R>&(F?or}iypt@s0G4o42zZ&&^>8_Bx@cwNr@v4KbMoT}D%0pWpsrmw5)jRC|8+R5ZE=rSGYc~`{L`rbLI*I2o9wx|cA)GFZ z_SL|PzRI*~Z%AQ>?=a}1E|tu3p;C!lDV~1js&@;8L_dP-1O-6=yUjdDZD|TZtV4&pfsFFRG*#G6vv{Cgrgzy zMHb?o0CCFZoe$FJ#rnZ7r;$9mHf;>?nNDl>P-7Pl<<+JVtx*=7UGt~xu!%PA3k^Sm z_(bq@%xcw{rS$3TVRI%f&N^~FRP}wkLsec^A~N(~CrMh`#~ch<)i^~D+Gc>44$H63 zKh{B~)nfBVl>qP;4wfu4wmc(h($MYnPzU-aV?F!o-fV~DF8 zB)z&`D_1t3tW0XN1u)f%I6cnN){qv-?DdnI+&k;XB3dPk^UJQJc2mhd8zYPgwr(NJq8MCX1hkMm2TTU6t9)Ua5*>ueQU>QDh`)(v>ewBd zF?p!b=OC}D`pC-(D~szZtayPMFmV!nLA!yrQaKg)__TE^P0IQ{#%k7SOs=TsCo=+IU21}D_cU4`zdirwKhI4(@yMrb^MZ<|s z)5>eYEF6O)dgG1G^p{UMx13~MNvfr&^yXJ2?0Ps3=>4*5;i(eGLS+}lq9*nT zN(QS-Xl@!8ocZB$Qpp^*dM0a|+kEmjn7f_jqOf?;3Y*Z6)9!xD;YU_fKif_;JX$lP z5YD$Yc+<5Uz;7Nc%U4Mg-hH=E*J6Ci(nT;_a#GK0Tp#eTi%&2Gdz>>9sqVe-p?YTi zlJ$|7<`L_fEu6*9pP3-S(?U~3=3G9gxYPp&PX>`^Fzv7R$8eDZV7}DfVTGNg2=*LD z)kn#PKPY?7gNLqDZcbwNT>5HpxIgp$BpzZ=3*^4HD)R%fZG$%=iT_5Mb)+|EhzO?> z@7NISeUyD^1zV)&^(d89LV#A{%+`RvnH-X=01oMC92!2P&_jvAnIZ?RFdPsXw&fas zf}TP8!_9%q92^Dk3j2~sI75O%@|Mr%<7m9Rx4hNe*j2<^Z_1~@9lmvP2p}RM)GOuU zfmZF4($3A3QU`{m8SMQ;G@A5)?%d#~Q9L?dd5zg1=D^XKJRAEMk zQMJgsX$pd?l!fA8!`3=Ap+T*W;YNL=y9qwR+2W&ngvKY; zXJm?V%c@3CQwf;5(GVlKH1hi#LtZ!Uov7Y7L$5VEDc7@ipG;m;K9id$4~;d-n9Y|y zCe|>b^Qj@fFJ)JdcP5Qpi6z(Uq))I8TTw|&Oo}f%XML=c+uG+K@Ac1yozc5*v&FBy zXH-Qly%(o^A$|puQA(smT4Ek)6h!UWK0*Jx$?VDwJPfvgKhy#_!)RQ*mi0FS)s6|w zD6C#abkbt5;B`O-PFiNmMS;b2j=HQAsJRgJXyx%mkXH zWOLlZ>)xlEvVoR`u_Kd*s>`%w!ld}rQ?&KTIq1II8fc)MKD%bLs{W>bb9|pWQ4P_m zpyHYGUN_WIHxLv~Uy{-4?YQeeV+g^~7Z5eb3c&q`F&v}j@ZT#!p@+)fZZW*T-BZZ<+hAqyxR)EkwHM)`g!1)a zu%5T>1xGLj_uyz;p8nY#1QZQDysV)j@rCz4GdW14XnX3%>?R0|*v463jjw;^0aS*5 zcmR#tmHL+!a`W_Ww;Ig!t{c_NM!y!koD^o;UFr8h-i)wR%b4?6@OhGhHZ(fF9u9a6 z+8btzi+&Nes+5)clADdIv5opVZsE?#yO<0!(dUJ4C;Y0FD6b@Ii-Zm=d zX+-ip*Sczp1@@WpT%3T*V^6z3{5^5Cjn0ZnV{aQKa<553O-JVgTb-zwhs>yXU|Tmu zJkAZ-R-&{d?!Sf)2jt7SGS>cl)7z;#sRrBR1v&Fy7~g+rod%O5!abK0BO5wWWT5qL zBO@M#j?+Lf3~^LvoY?}?TM~dtf(o08!m9G(W`x4JQEee{{9YUS%oBd>ONb%Wpy!u3 z3hyx0?#`WN9>8qsezHnsiPk>wt5&k5`QBX-3^5J78*Lye4K{wAZ_4lk1B~DC^67iY zi3cXOtraQ1Ew4WoS$}T0+C`)9_`q@6)vzm4-;7l*oO}#`x~xCwFpg zIkr{47*V+oiAfm`PbL9IJESXwT9}2m#cAW}1f?&c3ev$lHW(|W~(@D;TBQt<@%mGBt`ta*PGX- z4_6&(Bp=y^D$ykiz0XmsAYom2FP<+_X;j`Vja$IUr=L=(_{(hOA|x$(VKWU*n-0JjHi)q$5Y3r!Xuq*2 zpw#Z#|01k2v$e;lf$mzbg8T@7zbMJVfYe@G<1;*zHn;{1V%0luh5pioq!;a7q^mYHaTJJcJP$UhF$s1szL0G>qeVDA;VrVEprzq z7tZqTH@F2n)S{+l^jt}Ts>q6jwsA%l@$n8j9I-5zol=++c}cB*?|M!;=ZA@_n*Ng4 z(ADYpg)zX(SL1);d%|@|C4XwMrZmBNa0wU$7->ABkj<2sYg+Gl-!w1|ji~{PIAUQ) z;d^<8wi$-}ImSz0OVhGxjLGNi;yDMQBL(*7iRxRaD{5Y;93#0(PQE->gMkFIDCU3Y$pqZaE)Ji2TVYSFm=ZdVH6-Jq z<4N$ySCSOfQBs^u`O-KBQSPnD;yz*iB;L-9&u-X@q z3Pf7S?2!G~P6Cu-O3rbb9bA&_x&QNHC*|b_{R#F-&y+ias~K0yj`QVQCg|LG2LNj_K*r>5)r7RdRMv#@EN%Jjlt&TWL$$dH^NJ^(n zbhs^om%hW2g&`htAsLfLDw|ZHkG@)_6udP`+OSWgnefT=e6>@e*@m~xR$7oRk<0sa zG)u@X-MxVRg6!6qxM&3qvz}#d(bcfIVu2HRNMo?QRcJ|(Uf0zx2m2U0DLrFzzn1Pc z8V7W$Cx&_xXM6)I!v7YXe^aD>UdUvbH`W2?9RRH}S?cG{|K-#vo_UsMfr_a{egUbc zrAEwaD_uw)XX2rvSu8tnb$KAxA3y+U{>bc1|C1L2r!{?5j3N%WGzLTH(~lH4HHjO{ z<%*=fxP9L){y?z*VkX$bBxQMo3P zY{w*HU)1g}fNTx|_V7fqLMO+7uwIv#f2_HLiX$~4OU+R50s!(XhBkvkH z60trmV6;d1qQ#BU1;1u>CDGw@0Zf>&(0+$GIZnX(oQGqHIy#QOJdaR1J(UW=Gg2Na?`vl{ufSbsilDyTSN4h;!vTfO2wAZPalAivG%YSZ` zJ5yYWWnIxY<{B4c?u`GY)4E9#YE}l8Nn4h>AMX-&ZgK4JwT08!j9+BtM2Lpd?2mJe z(dP^)rW)9OmKsubi+9Il<;<|m(z5>cg1=_}8J4PoK!Wah?}jT{Q=VEx=X5PxW2b65 z)&yR}6-g*@q)Giitle+bv<};n;UOJ3_6vvo5Pj(k+{O=gtp)^NAeVekf>{W|t<$(9 zy(&V75A?|#kI&Ka3w=;F!C3?!jhOwj>HT`X zYz}qQoGawSN@{F(qvMOMPhr;))9K5C`Ckdz+@dp0@rauJmVsju+Y$yyoWO3N^aJ*~ z?h0JSp6k~CfQ|QetzsLC{eOS#Sp8f%aiP479JwjciNt{gKFuA0b|yqfT^u3+4^1P*5+ZrM_GzhlXE-2+dl9L;sZVY_2n3u` z*q%X*C!#GawWGX%Mh7q!NPpY>^j$wZy7t$_P!{S^cpXcX9gnY2uOYur{DtR?#er;+ z-^UQ_;6L9Wh-C99oaEbUnFXO~el7NM^tM9Y6q_KMZw;>Xf=Dq&(2qfH--;{qZCqDD z;G6?eaC_i_K#`Tt1G~iMpYJ0b%mBIn(!<R}i2JGeO)AaT{W2PFy>YGNwE#sUj|6}5Z)k+Obr-jPZ~4s;?LeGDi|WU5}2c2IqERk;iEjhE_K3VDi9 zs|{h(V<=#7E!~Fywa$fvUAy=dO0!9aTKGo@PAzegES_$&OFSaS9K%~ayxM?W1rbt@vwvwKnIP6sx@3Yo1|~h%VU6|Gut}9nr1jS|p`iU@pImXoUFUau z?=NQywPTZ*nY6R6U&v%E=0tZ1Uzt@>j15c%@Zxu)f>E>0)uF$R6tfKRP)-@Jn~&om zY2%v5M_>GoZ(v$@XoUM9_A(MnWp*Zo|7sA)q2O`#q}%OQdcpz%n>XTyPgFg1 zFla!$3Hw33Sp&oy_*deM?b19T`5=Cfd8lDW@B^;oLJkjRS;qo`qgiewG z(nxo5%*Ro*Vd-Lz=^s}yQONq>$n7!fSV4Dv1GdYhGa9*uX?d!%$!C7UK3wdDV!t}> zfV+;{3@lr0t4@a(Sw_~rZ7KNOa;L|G>@o!naK%H3xmGQa0|v1Z3YWw0epGNqMQ2p3 zj0EH8AHxpYQ!uzHoz|e1?~^^n%P`L1S~DCNJbfT(z@~ri7Woekp9|4Lc)7lR%=~>jj4<;bFq( zuf8bOjBW;Ae&xM!pEtqqXi0TLO-AjA7YD4xRPJ(Pe(dg7vdNsApL`7&=jR zfvZ!_uUDbetDq0(nT}miS#3aWOqD<4CMmiLs6)V~;u|*`jzlgC7>a&o?_=Jwo4wXp z*T&|Z0GrHwAJSi(L~Q?T#C1RcyZI2qfi`wi(!drteMx%LWmKCC{=KQKKr5 zAqV!Fqt86bO+~CVueXi^M><2tLa>56ueqP;}FF`mQ3U@4|+iaG~}e+>W%>)t)>fch0E;QBCyo_VCeAq80=Wiw#AAo%xW68l; zdRWMAJgn|#+<4DaR&sLV?X{Or=I0M1#q`aU7yQ>?+G`-J5J`as;0KG^9VU$HgIrW5M;7 z152SDeE^PVq#i8etg04^(y?|vbU;*Od0O>7cNyuTzaGB~dcDiEcUYHG8>kW7eF z$#7aT5PJ^UO#+~1WUgif$FJUmfA#UU-w9b-YLpMG*gmm3R*QX6SV<&h&R>inc~F_n zHxPPR9>VMbHfroWhfk&F7aK#UGzMggN}i95v=H|&#hkah5MymwW?=6C-MsLiP>NXE z6PQO0;4AOTW1s^QAs6?Kl8l^7?v3uPxc-hF4|xZYIjdS38kd~ChKGm=?g=!UM+ep- zKe!-r#lt7%LeNA3xU4xX+{S=X!6ssu`leX};YO>A$a#xYpE)g`D&XX;W1kJUl&YQE6G}0hti>^@MmB~q!DaQCY?RR%>{!l3SkuezdZZgrTm&}dbavy?8;Yu4$FGL}VgQwcm?upt zQPYQ~F4~)Fh#x69Ea&Lqv(s!syQQd?1B%0Wg)2aISZKYhz2n3)IB-sFw{zIZ*75Q+ zR`^;g*diY(T--Z-tu9ji5v)o*ck1G`YB8!;cOJUF8hFM*w-La;FsskA{!Am4qq;FG zM)Y%>rG21bue>H*2E!cP^m^wjRi-v~YYVn8J90A{1+7TV88er9R;xF}E~hXHn;oFO zSB}al1-`nO%L2vnJpT$oqa?M*U60;|aLPWtmt~d(_4vK3ek93(Rpx}{Gt)lLDbI=S ziqbG2n~ZyWF9I0baxLghi$vR;10!4llc{eNG%XY+*XD2dD}~7NXAJxJB`7@3WG!VL z3LuJubwu&%T9K3vFVniw^{j|6G(n=bs4MuN0qJrDRr@(+uBUoEP|;L5qMX6kIl|ZW zX%188@%JB|k(`K3-u)7#dI6Efb#0DX#>d4y4M0ht+(={!nv;z$D*GI+eIL(d#SYgd zW;5XA)FdR37GX`>ODd2;0TcrpEroMV#WlnV^UKA;e-X*jWJPS087L`D27rB#k5!90s zbkN`@q_U;QQC|g~XN&MpRv4dJg#RgVqbW694E)*{e60>wL{WL}nEow1^h^Y^scG8V z|CE%KX+%pg|BuAcPXCuqK&#;4S2Nk+kJQBv*~+0LPi#z~)>@LAgK*c=vCAA!-+fOl zfzv4oz^&p%&I22-0@FbUw@Kr%03rf`QS(0l{k(p9y?i_iIVckZ{kY6{!))sq(qlRA z?-#?qJt?W;`!xmBK@fZhJ)vdJ)h{M78(Xdau0$5~Nzm=~cak>gh`-6)s2RH9O`22e ziIt#N$d|8>RNBj(G{vn^tl1e{(j;xM84rp7S)}p-4^fWGa)~F|a~#y(GmqFT(3hO= z$0DjzLj^-F`w?!m8Bf`<*FRVIW+D$w!A9C=UldSr^huFYuzY)ariSjhT+hSVeE@XX z0>t}Rp%Orl$?UaFw#3>|J6&(EegwqK3y{@)^-_rSZogW&l$dSc9elj^;l4JApzcxW@r zB=V5KeqqWM9@)V$0WXyMX5A5RJ7rs1)7h9S&uGrRjnA>C%o9!1*JFvTc8&6kc*(KI zUD~hfoZy?7kB5xh0sp8O=UW`9Uv{*v*ye1Kukzr9sJ+?Zm8lJ!YAH({41OQO@-wJr zBjx(SFDo=BJO_v+>ysc44J)@Ax9`JUv*lcyyJ0#?j*--cB}{uILTyX;oONYLZL^c1 zHmnqyWnZAj+H){P=qu6CB`A~gUf%&jl>x#ADL-H!=F%T<0I%o$zq5c z{;2u{vlKpZlOzLcSLYJ?(Im?%91l^rZ!#{|u3zyab=b%7)_6beO$FwK){C(dFSGeK zpVSY=X>@rPhQ3RF9w=KR)Qy|o4X;m6F?Roj5V&nW*vSeERIxqk&?bGjB%A5jqe|f! zebmx4B^FKN71)mRvH&`kWl*qW6|iVaJ_R#6U!f-#G2R77uX6Si{!v-)pZA638zY-@ z5Nk79mnnZFSGhGdR_@@ifxNIE$sN_pRqV+8e3l8x(cG7gj3O-ZN5~V2bc=Qz+zuFe zcku3vBks-=hf+Zwn`zi&50=Y~`-%#1E96MB$+9K=t=dW7fj9k`2cok|T0z z`CGx3OqIuOJpLJWNxgE3PsaNibd#ottSr2F?GrGQqFTDDx5HQDj2DW5LI2ZbZqFXi zeM!n1ITt#p(;Fa8U~q`p!{bpY?(-MK{*P(8x+WaZb#kpReW6X}4!y|lOqE~MoMpC> ztw1;gWG9#d)j}Idr)2mjR+!9h3M>hj^BsTtROiiuRugyOA$wqCZf-YXPRRQkLjImrjTDG+t9=~T5(vu<_i&ZQrM~RI4JRnHfZ&Wuv~QJ_ zef4T|Eqpn{Uk%VrS}GY_x=ZI77*q$gO6n1$i@L%mz~&W`8t#P3$laPk$W~5gV(crJ zg8d?-I`U|WXudyYyCpkZlRt?Gf0BC0c9CV)B0`GYl4+KVg0tQYxsc7-mGy8fl8iUQ z>$n>|pc#I5)oi8y?ja~4xxvFHGFWa4zTnQjZxJXU!sDI4OnY9J%U{b|gdkEN;Q@u* zDW)GDJ+S+70h2FLEhPhU}&J{J88IDb(N3YPuB46E0 zUWQ-8No3g$8+O}s5cb|pTQMIzBN=;u!;Ic^2ZC8j?< z_Q2Dhnke849Zj8uPs?~%SHfzfK-jbMRN^Gug~ua8HzsRR^(tJ??!VN^860al_%h68 z(Y2lB-m@r{O6{Q=l|pncyfrz>x`zo?Hlwza%hf_G|mJ@3SFJPByma}zFGF@!2wtV7D z{`8aYCn}}YX^o9d5S$ADxgSZ%0U*v1njo&0I*7~Fg<4txak*%`UbN$GCIW%)yA_lR zi0%#$lS}KzO*|DpZ&T<4o50l90A4V$r{{O4(6WLM8}^1}ojU8cOMV78%ACYHmQN3r zr$Q#bSZlXPE1al}-RxM;65K7WQE+kxrW$!Bz+HJNXsU+5n+5Haj=@R;ZwWEn3Ai{> z8DC?9L6U>to4yqi>|29DNH7o)?As070m;7hnQ|c!gdO|Zy{)igfV}>-(cY9LfZ)E> zzpa>K|4ZuE2)uToIf_duw2Y47rY;PysW0VsMxnVU<_mxf;NtITzx0B13>oB^fS9yhDoY zaQObsB--Ht_{KfkdQ^t)L!0Jfa4aDR`KM;bR$X@B4Ux6Wp5t!!fAc8+UEw6yFYn)% z_&A2vP1^jS!yCl4NXk#nVQo2Wp;fx;JzA=bI{`q_eW1!}b~>K>$m8J|Q7wGoakfy@ z=`UoaLXIQ5#{+L+r;kwk>PF|O$r&{P3HF=wXN&mqa)-H6R%+krsyf46O9Np8@L{z= ze|@&_(fB7ieLdIp&1jyqv=0T?#1^009)a&ir@0#iG)fm6HRhj; zE8Ig3nl*V-@*!TAKVq~*dLYH1)0MbQ+!c=iECAWi(th;xM(Y^+TK7^S;cvIR+`h#N zDaHfaE|9!^U5YkfPga#LD(mFA6I#>j3OAc*D81-&vw+`agd<;9hN>YB#AJ`AXN_1~t$ zj~PR7AH+L*i|j5#PRM{GqJVR)p#xO`&AAzlyTw6J6LAo;sDU2Q8Ubub5E^5H2J)an zHnV|sBFA{fY^e@0A0b8ZzpRjciJqGF1eZUfstGJ~Uh3esfuN~9H!<>~d?e{W@RD@_ z0kTWb7!4SAXjx!AuY%x~#X#KJBIkS3>KrZ{n)AFSRSTc0xe1P~N4&G*t_>hMnk3>p z>f;x@seR_bjW@e5zm<(VxF#DZwz`@~cA)qDhZu*UqkAdmYK~wz2Y*xsEF}8nOS3?+ zpxrZ?`r<=VgVR11A*Ndl&Qb@CBZs@-YX>)UqoJZ7(q$W;9Fx`g~+lxIZ}iVJO+*MBfQneiIVkv)}laa(FS4(}MzCtKYemOx z^Xh#4O|u}vMA{=?S)J*H?2iR$WquV~Bn8D04RsC_`BTOxm2!00oK``6(ap0!;Y{5+ zI#vjf-gw&}4tru=4X>rQiOITqOHl4f|}A3zM! zNhdJRf#DC=3|yBe6(ky1{^WX0c0NN3i@E^x-B{ou1SY>A5C&pLJ;`XvW}Fu=_swtF z`VLxL-dT~tcGCcE*?K}5MOa|h$6W)vspKoIIJ_Bd(h43U7WeHcf!mS4-_QF&CO9HA zB&->6CskUq?7WjR^=a=KuF><_^sW=mZJGa%y|<2wa$VbohY%El5F|u~lm-P9kr)JN zlukif2|-#=U=Rcp=?0M@rKAK25h>{okq+q)q+`PG8c>(6XRW>Wv-Vo=@B7~0_YdAP zb5D5RSDfc@9OrRLPqOyt=(B}8&XB9G|w?QhMv(W$u_l>+3A^x zWA82EOZ7i-L>mA0mo!7>)VpsyBIr3S5NpRkFqF#o+`91;}vSXw^oe)L``=-C8AAO3^2_$TT<%NEqe>MmkR>rkTy zAB>{}hI6nM_#Nx;IiN~_Xgv79O+Zd|FSF_^#6|g#jK67|X5i`VZmJ=?M0%rl-iY={ zU2JuwT(+*j6J}4hc`=MXkZx;PswGA+9BOD>r7* z4TQU&f{Q}8$7A8+LKvMyA%r^gj`t4YHgY^~Ju~t{y~abj#BQ3f2PcxfyuN9ZO+#P$ zYxMFZ)F%#IC>d_;f;%E&J^U*0<(#f|DTedR4KY<_WU{dfFR(~)zqJq1@h}3hm4^VH zToyzgy29c^(lxBx6GyUGZ-HdBYxYbF^w-s4;7c6B}kN z8-5-`ap5p)>CehckjG*5IN|e38N5DWlp0Q|wr!otXA~j`XYiO+?Ci_+oX%chHZ^r3 zC#vZZe{2R2NJ3=8E=^n*&!1|@SwKbPN2kDh!iVTyB(JkPdmIfCC3ioVXGZv(zd|;Y zoRdz8t09|CE|Vkd)yaE!-N|6H3kIO=2>Bbo|5RB_@ytDWXl$fGU~1PK_8|k$Zu4xW zFs|tvV=lXP;8LO!1G$W&Wg%J>&=&It zI6RzJFth25=A+lVb8L5oM;y?{X_TEu9Rs(Oy2EgbL5xG+qO|u3v3EGT>s}7S>Tw$d zDaW||n@GXqbozlp%tWaPb%dGzyZNoQv+)jF$>5&L-klex1kg;Lov>n)HSXo4+M+P> z*-oSDaCz6#y6)N%FQGddqJC4yA(C57R~sDJr=E!9*GQJbmM8Z;SMalb@Sb$ z;Cb=m#if))4K~AcLhUjpJ3X3P&>{gcIU3p1mYH_Z<8*|R;=~VPA|givCU@|TZ8kV8 zD#mS5rIEUZ7S%<#KByl*Qg64@iTiX&4Hm*Z%1R?# zuU^?DBT$_|{rbj*lIV*)63f!VrU51yZ4f28Of&9=P}+rVGV$^8(0;l{XpYa=g$hayQjMq2MIIY#X*H<>Mnr+E64#Vz9JWf=Z_bvHZBMbfo(R?sRO-D`4vJb zPWa11nO`3LZ7-?}>*=-J<+4iG!<|z%n_PyCB_54hP(A#?ms%YcMih1+#v<|e$)Ptv zuuI<0s7BS{+9@g(@_mJ5CunT3-dk^@dZYBoUuEu!+U~mIvkUpY)8XhlWNe!%r5^E^ zNMsI!_Zqi|a6%Y7_+&3N%=W!_M4_5)SAD6esZQYPXw+%my*bz@tg*MZi`Y~WHulZ^ z=luJy@E+XcyV8zEA1hB@$(^_vSdJdGX&(y#*w{zBjAEI$iQC4BI3-ess!%6kyLew+Sf)yFNj-3Tkmg4)#!FLq%`U>HNZjNMiFR7uXoJVBE2&jyZ1Ntl#J5Wk!?7iC3DX&uJqO z@~_jRLmKR8tzMHk6NwTWg4_fsqU*hL?KAlPvQyR#4874lq$`*p3{c=MTBGef1!hO%f84J((}&Ov!tjTd<5F zc1U22YBYoJbBWpkH_fA6P0Dla0zAqRi8NPcM?@sdOx-6`%nnVo+spejqO?DZh;@A) z2nh9b_Bp=g7tS;{cJE6Y#30#|f7yDX>;oz56BZSmOGcs3YY^!0bP)MRK)08a@hS_s z;IrLO3~OOFePV+jP(|7bCPz`HxAqT)k)ij^I+nCfF@ty=H=1cWXmEq&f$=q<^xZVO}0E*UywX^VmX;}Atx z=fSQ4kc{il-J|;Ok5rY2hywriz!Y@NPe_TM zENq*Ybd<9lFVOOljH)Bt9ATq$uZd;sqq5%j{+yxzJK&E5y_jce(2M2HEoI9b8A>Oc z?=CmOZo+b|$tc5#h}c7R`(N%Jq-|f|WXIG+lM)h?Ml@5D`Icx0@G- zs)l!}V1D;sThwLU?ta0Zo|&d2t)iFuRKVtl9I5AmB%Z&!`SW%QsRn6sWlkWI^u4?J z<)A=UlRsc+TR$j6J)J7;(y+gYub-#=&TI)m(MBm#f(#kYID{##+0h2UU-m(wBAw!p ziH>!WS}4uzM+zR!3*^P3lxMezbg@mjfmGZ}AZ+m5!s+QVQj&5N^4A*;SSCSv9|ImT z2P8K%8VJHWEz>1)9==fp8_>FiYYMucPwo$6Y7MI?vddijWzvK4FQl!=b7c`W(Dly_ zAj1uW{x}kbxR=5^UU#7P1b!T7<9)8hxaY!Gx>CL$Bv<|Rmfwy}L6BhmLs%h@8|J?q zIEz8k{5askn|LdCYwc~BN^{id9%?+iJ^uo^Y#hxQ zxtkg#C5A!Lv-bQ2t_^glL1KR0g?VmbB_-#nS;L#8W*wrOVQQW39O2V6&OGxf%p@)3 zCWpiMGTL1}y&MKyd6y;pfkxTjmDYiC|acL;p0UMat8Q1kSGW{~X2 z7FpIngK@(px?XcUsiMY=$4s2luGUdZbTN~N?)XkQ8gWDIfn@!1s>quOiL{Oz$>TCx z>>^=hiZLVCFXJ|dJWxGNi8Kny-MD>BuGDEz99nZpR5WwgEZh8TjDNgop&;E&!Ital?bAvKA)Us{JyA(sCcrq}%@D4f)3l&Cf+CQX(G4sC2754)^0{bA6x3 zFLh-;J+narCZ)EWM$fk}5Y{mExl_ugHl!Jt2#243UA2N&+l`oay zVbMV4$MSN-=TP$_M`piVU{-yZ9SKtzR_8twtE6Es&(ZXQ+(--FYpL8@hHp^3yia!H zca@1M;uO#y66dI#9z%`7+9rpKLKgDgODR;S_1zCyR1{p7f$geuwxej(!A6pbBRl4Z zW>5To3H0>~asC~7`2}o~VOD7_H2EysSNcQ^)E6LijkZLGb{q4ejD5QM?j*lvtZand2Eyx+N$OTG_eki@7mUh zKO*`HW|mn`Watg2o2TxXDQ%{7*lp)b(M=NW(l{&fvXr{#GHgF(MJ{OV_H>)4A^|T% zMRT3Y(jquHHQVQ3n0Nd<;mC1rI++i(2i&H;bf#gax3RjHFCH*`y29j}T4$tm81|Q| ze<)Q&kJHlY6QUA}L(@-RwdX z!wehYt6g&(x+JN;IV3m{zq+P82yb}h&bDxL;_N=_M?o1Pc(S56{P|lGSd_&D`$^6t zg5OiAzhZhI?=NdVG%3uyxw+Tdq<>r(-@!(h`84wxnY_}>jHho1USjhgj*4Sb6siqq zvoZ8N*d9@z=n?L&A04v4MM}TuZ8QsmEFNkpKv#Kvf^{fcVPBZa_ddL#qPU^-@Ht|; zS#MdG)roo!&tGY22VM#G_=kL;4tY0*aLWxgRtD@fVnOvXtZ)K@?!e$TVQZXQYo;IU z%*{(m~R92!%F|) z!_*zl>-+usP2<0O)8iCvW7$cntIAoTkjzgj8o%~Z`rk+mRP=5%I6$M>tjmtC6{sGb zZ=CU@$F%uj?(4(H)hkgN(1CoAJt*X%h@wH|bs`?}B6N2i0KyMd_tD^6wE!FDsrrhUX50;qMJ3i=r_Y6D1%t1{s`SrAwu$U76F4R$Dav8DN2cVO$?i(etQ zfYkVu0r|i28&z)%O5IuR+VzQt)J@%HJ~p{>a={$84(mKd;C9^IK95mP+@B>BH%5Vk zqIq*zl*52i83cc&urIXW(mFz1b^Z4H%6ZOyg*;7Z?uCIqaVSC zp~#b^9x{7s4E1}7V-C>KKr^}w5W-*tlGnICNf?WT9k0xj$BWHr0-^)jUi)hD{&kY` zXNc`~y4h2^py4703ueQWBjJdTdBDb-3$d8wv~3Ur5U_~GKH((=+O8H%&WD1JglS@- z7Q-C;*p6L1`yIQ;53>g!Q+40zdY5%vxIiGLuDplN=F#MhfrEL1VC=5;_&}BN`vkbo%M&8;EFh_`DkT z1$L{XTfgCKe-L0@AYwan;0g-1RIlXH8OF*{1~|WDe+KBEhf5m67-ixqbT(^{-NNiP zKFNTF=)>9d)NSdIZtkeL7p4@)(}4la2G)){T*D>o)1?|5QoLTom!zPJuVa>m;m*9s zIdDm-%P>m@*kTkSEi?P7J7G#Rr;JGO&?y-5-_D^lnF`FMF8zKYza6^2as`~B|1|2% z`vHE1)3PM^%&62o<8*96aPl7%1Pg-2hU{P3;~buTVg?aZX=KW{K-1iHPHxq^rqX0{ zE0)>|MegCdHCuA2*pP4qG>(=S~Q8jiAizH zJnnFku-!4En0Q>d=8`-k@grNsHzI{whNya&14y*v1?TsA%%YrS`&+nF%u3|Q2Xqe}eFQX24fSzC6HrMKV7w>w$97+$V@>Py;h$ zxXz=sB9VugT;GL)MMNIfC&L9-XZA2*^qjG>d)ar7FzQL;d}CwUss67J4S@{U=rByL zlan=zl9ID4IedW#^S1YvT(xjw2Qr9wz0OR_I6Q2fxX5Hhk^>A*2Nd{^r(l*Ux92Ns z@~1hUJ8_OIFb*?iol>=}j>tsutJI9$EsYIxoeVg{K|Y!5fXV`$OB5|Luf0bsv0^-y z4~(V(=hQK>Z#11elX&MbwO}+8h5%L*qGJQenQkHskqrKlJkHy%ghGQdAz)sOJOVbj z@_p}WN}NLppTsN5E?v50*D$ZJ1)xaSy#wQGAcz0ykys6Uc6r|g8wlcm9Lr!o6yRjo zPc0?<>A}HQAdtWwn-Z7*^w6m8Lp%PL0oC5cG9zd6IzhGPDUz&`QDu+h6f5)7E0WZE z8R@N^@oFcRLY$w-bQ%Z0svC0IldawBYHixGBQBg=Zes({&h6cQ%NNxu6&cr`ucs2pLe?d7U;^Z@L=>dQ5}wj#tsHMC`7G~daH za$=-va0Ph_z+72(Rkj)*L>X*{`mIy+7`uK{k(w^Jv_9GKVnUVcF)-GQeCPWx^X%nk zj9eKiZ)mRRr7p?f6)UQ`Z?2#x7S+0+cHXs3&bWfzrGM9zm9e7TnXQT1iI9+xI%R1d zJr7@5ga=w#6+XFE&r!YQh}o#z-mI(-E==DBk=Jh)ygkTna4`XmL?hOY7>&l7_I5RU z56S-a=*N45)M3{2p4P6>ToU>9Gpw}4x^Z#+Pf%A>6j}>-%kDP9H|vfufaZ`_N#J?m zm{#l0U(w6Rvlg4!x&hyvpaeEtKhCgE-0E4@=;hXGq*EmIj*lWDIHYvw~VbM{o8l zHF0wgg|nC3IGuOi%@3M5*OqV@&gyyDl1tYWVwU;$ROKGfibtQ29#3TC7i1C%u#;gU zJ2J^}*reso6p6#UzZ@`=N5Ql}@0(-e#c8%Z`;kQ>sw=); z$vx{?x{Inv6&wfMG9gn%f#gBjRPRj%ZTT?*)uyUcpL`cwx^QT%S>B~ROg!{}zFJv{ zqlTO};^Jre2a~WI-9+5P3ZSLn4Bnd=YxX>21vDifhbpaX{;g>gdz$(t1Vc_#t9U*k zBmK*ZXE&S|kKJBKerTUmX$1BrgiAx06l=eA^D)C{?fmJkP9h9hGY~$)jC1=+8 zUt1haz1o=PW%syway?u3Y9Lp5`8i_^KJkVez35UiIm~99qn6O%MT1Qx%zPHE~pLo-1ty`WoEh|GqIgrzUvCkn&k5g zJ|);Fp?~>NN?$>nmx+kxG|xQ_>EC(&{8=v#97q6Z+>;zbc*Qa6O%?HYwbNUdU_KYW zLf&A*2C>GJ53AykkKVEqNoulxy<}Py{1^9Js+1P^PsDN9D+S ztn9u*<|Q$%f-{wqGO_lTtNgHA7167^%ye$vD>vkJC}4fTuM?3?AW9gz2y0ZP?Hd*w zuo2rxf{#w__Vl?JEI0ej)kONfh^45Q(mKw_UYkUpxv0&z-xG8m^aM4HNIB)d4ReAm z0+r?ExYrA|l|ESR9t)2%_@NyESsRSTSMLpV80KKv&DH)2u@gt_!n%D)7n&^DwF_NU z;!kb|Z_Dg-)*QVN#_>ow>m1<~6{WS7qhBGfi!flM>nU&1>Q7yh;y?FI(aZ<{nP6Ag z$l0_XrgpgBdgw_h`8=n(`zgiPe_FH(d-}h$P&^V!UOX@0-)-g$t1NlTk;atS7HN^!e~DKf=On<@(*y&-1UP{KrzW+k~UU_-IJ zqL(Ya>pV$4lO4k&pevs!TgZwCQ=nQ)zl5Php4iwfc0Qr0LB`LCt42>E%HOk^W=lzPer*sixU?h0*)mIZjITf%V(Nv*}_H zdPl~Cn|zqsoda&AX5yv*(V-^q-Z;pB$v(WfgY6xK&HpL1u7d=hej~vEeLQ$Gz4NI0 zzRS?x?JbmI5p}(_&5HCEb9hOn0AfHBwmwgZUI!&>8o{VNYyi-Ojx+%Z)KK`C00eFZ zhD%4P!FC(;FPwSmgG7b~6$CWI`ZMnI2iJiQhDrd|Rp0kfaz4jwYJkooOdb+(7wl zi$EGDd5V)A228>PrClNsaLqxovE4>_LK!KsEeBiimKnri5AMoXfpT?o?dS9NY{lNH zK7Fht2cD|(p=}h>9$y%tg4RF3KGhF!&0oNQLo5&qeK4PRV?nQ-;fadi9L4fTx;lT3 zC#QfW$)uJR;URE0g8)?4M&?FRy!E}sGTlVKfj7s=xZho`f+s!psn;V_&S5lIymOzT z7A!wzzQ>RQ1@=CI>I=MTK`;l~AXQV9>aZimiwioTT!!H<|MGcH4Zy#5beIPv=vzvz z%r9FQ2S}H;%T0y%#@)yt6iZn+ows>xY`E4#M&P{Ur>nhcCyChh{kw2zC(p@>s)Lox z{!C+fuj+!qz!@n%z;1IYfSZrCVpiYL>GH*J0D-mI@ctt5D{=B$7<|w@SRI7qKWemt zB@`TgXO6}8rvqNI!Q1{_c*&wS+Tyzn_W$WN_4xY{0y`TdMF3Ktz=G_i-wRbi7XyQ< zdXIqPpz{gzj$eVvh6FqfY9-ml0^4fxTPN4nn-l9+8YzjuK;Zl`2wv1)%T6TNo{jc< z;eED&QXk6BO*H#xBFc}vnZ>w*>kB9T3OOmgh}Z?4HBqn$?SXq7YfGxV zH|Jc%v~l&vcfK~gOW>| z83mW;@7C#A*D`;%O`A>1AQz4w*T;2cT6+$f`FI32f-5cZ5g5QAvesbrDaIwta%4)S zRXtfnEOX>OR~B#*dCpazbP80OklQjZr-xo=w@)sMJGs<^;-=pdN@=p&z8wM(RMqJv z+L5|}bMqYgT{GvE+lfb{LEcG<=9q9|W^HcReHD~{60=CW=r7h4TtWL3i}$YOCfxpT zviZ$td4T0XClTRh*vdS1F*~~a<>Ay&weu&RyVuF_tpCsA< zF2_sNpgIMRLjqgjUmddtSsozXAU3<;&#&EZ650NeOii#WPgZrPoqQZoAM?s*P~0{v zC(Djy;1zu8F$J>`RRL0Da zGEFeARxsrV^dT#{N5Dw(cgXl5ki3SxG}r_ppAD95$NulejT~vwD7P`*)GCZ!+J*ds zh82Iaoy(tr^xrUh+*1(KkVBv|eeZZ1ox9+%PK7WD_gvTnnP4}F9f`y`XP1ZM-P;M* z1(tYhs%P{N82lTJRHZ6}7TC|rzW)QBoL2t3Hbntu7!x;`b zmQ%vdSB{1TZ>B71j*JJOwFE%N^83|f=>8CQa&=FfD{{>H#!v^X`Uc1!C6_f5W!?o^ z<3i3y4K)vl!#@)h2AuX9ON*~}y2z1;MRrO$e^LJc0V ziPG^#l-{8Y5)ZmE>Ore85+hntdbedF&)cF7s@Bx)1a<*k8J=wTArRKg&D6D&`ing0 zWUe=4q$o35acZh-7C(9kx23A5oS#<;V{sV~0=ub89)6cIUhg3Yj^`!vqGP|9J>dfA z-Q;~3?W=&j?H8{0tb1jG#4@v+X*PANU4HRe=sS1bO@^v6We23-ie@NYJFzcu_)gJE z0jsCJC(sqfl3rDd^XWziGrw1dzC!K=Ps?qYL7h^eU-;FUNY~#bO_d@G8^sc#^9rx* zy3J5(K*6mLrQhJxAEcdbD`vjU-W*TreO2xHIOa27`Z2*!?_Kp#6_agU=Jm5Hhf#Fl z?co^ru`isM3wqs4oIDe=B`&5Yzn!kF;5{=|^t#fsM!k2&?x~;>5x(NBw;o^aZaJaB z8Sj#H-7Ujwc9|9JXfVTJIq0KgaXS9e8?kzMCgvy1_2c%JNn~L$soEwgfn^Iq%$tjS z#jk`SrmYUs2M|y(3+lHjttZ}SC<>svAJzav=n5&LU;1&$##D*WuF1_Hu5pq~jlO(g zqj_ZZSkTzHX)Ra{yW4I$bZ+&t8cI=SEu(zkj98nS>V4v%kpe$Ayk1_lO;LEH;^T~R zb%UP)&Ocb42+2ZC7z)5L!N1F}Se{uoACy*|5>c zUkdjRhx}pyk*whOyGf<`r@?~!$3O|x{a1n*;o$jeIL`kFJn?NN|FYz;NUzsH_nK5Z zULL}=Wi)-sqgIdnx1gBw_K4Lh9;l24+|iCz6d zIo%hd_t;d>Y)D4v+wPJ+N#J71YbW)*RA@~Zp~`2ep`qdfA-0rMk#!>f)foZg1f&aA zH02cgO2q6Ile+@Ga!f42YNf$b7U_o6=x0EqE7F190*$}6tkY5Ju_+02fF=D+H zV3yVx0f%$MKb;0Ew1&-s2>9I)%6!J~=kwsVK&d-FD1!muW@}CDr-EXCsZb_{=p-(s zk{s>Sk$Up|U@>q)TB!bXudTV|zTR)kY+u=F^_IJ)B~=C%BT1esa22R6d21&sMd zk@Ufqy2%pXgK#Y!+^&O`Qb&{(k15U4iyXrWH2h<&?NiG5fH%O2D^oO1s>~q3`>uw! zl4E_4;BlcSx$EZaaypoivr;WfM`GO)ZyYM!*v?T`*9dKBT@aYg=r_H^an#Iqcyh%s zfQIbz8EsDwRRSDBQ2RWS|6F*q_U#w)@YBBS7grIp@@L!m(yo6_Jx4t+)wJbd%w1(8 ze>wB?!%I`D4ZJaRZY6rhrVG%=1*&`GM6ddx?;K?0DvWo|YS*9M@x(A-1m2v$Y(7!< zRj!&M4OLJ#-Pn)TN%C5pCy~vkcZ0uVW-`uVOPKZ(@QlQ{$*zv|j!nQ47P1^@K+-_+ zpA$aE!QsX=R|}^&O|Heh{AZZyeo}tWNhMpv^latTF#yAA5gjZO-Mom|!CFE5x6jJ%`POmu-Mb>*#3BRDf#}LnOzIHgc#8B|-?K@l zvphL>;u^?YSO*_|g=mrI0rq1EwJH;9JLU|jTzLl+LQi8WLafVdUP*g*GQe^{YIECR zdzs~~(LjW7B13Iuy;b8^&ef!y=osvd3aM7+37fUWQ%=rQPq>q$n0YJlC!;k}$;wxurB&Nlqn{BkV703olAUJRX_BT4T9R&!UBnJRhMilU8L);1j z@;!*}E7Mxe{rHksiZX$w$bmVT*=r;? z+s|WGn;J|KYM$agkMyIezB9E+xR&_-=xsy=qK8~t-kGNBa{&HS)`Ww~V13t=wW)#h z(Rctzz;ie)b;G7Cf`0<``ra#jVl0`^5oRJ0dk)W0kmy(2@$v^H;W)<--0!&;%ixMw zvl>vlNWZ^UfNf4i>U|;c)GOVM5 zFT#YW*S3%MZ`K`gz-wGh?J8{8?mfo>tdAiw$2U$k)=-;-UAR_%)mBDLDQIC-yS1R> zWc>+2PA~q=M1r)(0{8*(lUSFxO@P9b|(`eHRi)K2`^4dg}d4oc-+ zp?dWAvAx@UDZQyrmsAO2l_OZBQ8we_4?550a=%U`7-j78Wx?5fXEVBKp`mUhj@PNo zLhb{~bpwKRaVJXe`(Il`PwaMbCXQB)LZ7o9cxb#Kz6b-38gjEB2@<7TPvr5&dM2{Y zuQd`1J>CCT0SGq5EzBOB3{Ax0_*R+ z67(0~QaSq=Vf7Rf2Ok3=1d-SPWh&sjzd~xTA6YDe9;jUD0gYF!t~Uvyk$1nO8_r(Y zN&;a_8koq(rEP>@Wzm@3mzFssy|teSF)j+b#H%SCK;{#@0RocxItQ`p*-8{rVK)!h zg3Eok1=qQUwE(}Yw7V6KrA<=WqA~76*rVi@QU`^6*Fty)K&;=@(U}6yu?qYDj~i8pq5;8;&@DUj;VRO24m=Cnj6R#%s9d0~=vC5{F;N2y} z_6kTjq&^x>N87H=g1a+`*-2@BhVdW52gDWD|*LkOaMZm!upcoGpkU0b2 zghIsb3hxZ8CK9~hUb_Tx;XVW8a&RFpY6CFIG(z4XV$F!L15$YlAh;F0Xf%igWBm%R zY-v}{ga0#lv{Z0k5WNKlaUoqh!;#D0IY(WgqP{21XU3udkyXBLNY-Yniir5;@w%*Bbz2Wb!yn?hZL%)Y*YMLY0 z3BM$MTe0xZ0e}>NUd6ftfR*e)s0^mqXqk8pR+IL^3%GoPvJrei5e~s^Q?Mk+`X~| zRD)8ZOYhIsYRYt4xfph78M&!23mr zt2*)P`#za4wdU8i`X{M8J#oVI60Pbpote?~mu&4_DE~TNio%b0KsNrQYPqjAjnM6|E8{`}ig6WdAruaJW62c3APuS&zH>@#lCW@wbU)SeI;PN84z3B4Zm zv8gz6E6e9K8^NddPM`=T@kq|n=eW_cRxVH2j<67ls3Q)DSP(E>pR%V%9tXZK*l9&1 zRtp$iu~i@^c) zGUz%~#tC&gUAP^b!+;wG%oK4OFXknpGHpfKj$#Yb4vJB5KxUkR?Y?FN`iR@t{Gd1X z2iG6|`JT!IB>7U|5}W92(m!3AfPWB{SptP5DQ->MowA~8-awL+Q5aM=qF~n~V&lAA z3wQE8F3ZuQWUQNCqy}*PBPwl_F*s_kKSqj0@@Yw4Z)FH?y(#^XmT!+HD(;^6hnOE0 z3V<;jc5cjb*jB^5;a$(nwnNA8u?96E@t_NzW`qC1%%V z(g^8EN3r&IMc=pz4yL+pWD@!?Sfv$9H~+h&KRFVdmir1^MU&*x+6<#PDVZs9AaP@21&-g6!Ro5+RIXv^ zdyU(~D-0d;N^&V76WX^+=VT@%qNR^JNzPj~5y?aRwHuAN;BHRPQM!noVcDeUq)cpe zgk-S%3^VXV8dK9J59U8pBzr5M*^^*U688juXOA=3Y(=B@8{I5g@jsMj*GU|Jp|%W= z+t|J~*sXd1zA^?pQJ$V(m(0I|z&zkZBf)0f^$NZVgmn8`X^g|4ydvLG3SOEsG3C)I z;g1gwaBkSh8NWpVI?g?Z(o=^l|k;^^gbV|CJX6wMDFe$)H?^`4+vqoDm*p;&k@`jC&np{#vh zSvku4-H7*>z+iHs`R#}QpFH~6g85+I`j?~P4_beM=Hv`Pl2IxMm1@*{f?g&j_gXD7 z7nTE-3oSuuI#;F5u2&C&W7Pc@79$L6duc4Sy1eyOPNrO~m#yaT*dv}1T}*I@HWszA zq`4RjqsyZzV9O0}`fXif^v3AI-&yLO!g6L_VA^n;_BdACEr~vUM#13d*<>%UT7jXJ z91Z|HRk*w&R$9*oPW!7Q_P@ztHIX?b=z9i>*KGbTx`)a*a^i=izevwI4-0NbjQ5rf zTNDYJHf`(4ibA~sN5E}Lb_YMv^hTSOl*J|O=nSwMAr>zOBsRrQXh(2 zSFo!WzTDcdY~?79-x{n@y(rXSbYdUt;Q%|#AqWjrPS}8K(FuZT zN^J>N)x~-p1br_dWt<@Ry`c`G>y-z0$a^JnwHl{l}g7bgV6J3 zrMndzEN=?Bng(x{}!l4M4$vB!WNKAb!l7|K#Ccv9SA(JEAAsy&H<_ zLGT0{CP$dHr3`0Q*Nz5NOL1Ou6DE$kAjS=~P0r<0?Qgb?pi5GDd$_F}AG;`j(ESt; z@6111e{H?BUBlKEXS#GnD{S=4Q)J8@+)>jm*x^NvRi2|&gEbwVM42dV17eE3<#>7S zv_BtgghKNM^?L8?I;03}y&i^~Ql>8vdaptYf5pC*?4DY6g+O*KrE%e+zgWk9XYE~b zpzseTF02K4v%i3B&ZGBY35WJdb$1ccRx*`K2#6f+ju5H8T?K$)teRP66Y>hjlOq6mh(TZ}+D+*R?-F z>Vu*zDF8G3i+uzbj3`KP-}%tKyxGmLRSpt0#B->XH|Bm0?Mu&qkVp@KY9&+HMh^xpxT7{@yj4K_x&aLmz%nMU^dVJ?@?yC3E>h+*t$d0RsG<4xjK zISLO^N65ULWcCiYx6=3UW@8+Q#$lmL%*Ti0Z#{Fsrm*i)XtIY8Ko`#cQ_I0E-5al4 z?{Y;8LSobOxE?|9@}Y@(#n9&*nd(*a%IbOHpzH3)QI65|1A z-}w}z2)yINM>HDfsBZ`F?t!GY@6krj9i3^(PXfBSDdh=%Z zvGy&se&s{u#=3)y@57YIl)BRr@n7~8#=8c15(Gs0Atr=6)&ZAwS(fMM<6gn203Ta* z9-K1|X7gTOm~7EM#E=|Fl`G7DLS`4U34txG4Kq$_o@3}2YGn1^wcG0%9kqyWoFGBP z6EGWIRJxQ%h>k_QD%0B?y**JbP@|j(zi}2|G3OCZ2a2L`*vsDWbOCB9aW-!@?`v~q+xvM^D#epx+dcj)}%~4K15lbC+?rznDOLJUXoJjl4du@ zvDgn9EkY@?*-+*b^`~PfUv>rWki5XEay^*9+ERCl5->?u2E{$R1>9fp?wNap7GNTl zcwGDjdtS-IKZgT)=^JsIT-^#a_vq_JAZJmQ`~sll&y!(4}vB^!v`Xzad0Gs>wJDeQ=&-Hk>UhgY^ma_HDdLuo2Q>DAH_*`?hHa z_p`lxe&NkUjfCzGhbZ{c*|~L6tt5CBn6;p*E4)a*T{W=aYgS&-F=DvH+Uht%!Jtz2 zUe%V*BEiu^>sk3!y@UT!*-S=B0jsXL8GVQgA;Ci({}a+Oj8Py{TohAo&R@>Z|?&FUXoQnH-DX(xTd5WPtr0pH*2(@U|(gnbXL$NCj+w5Z0-7`(3#YlQ6}AI(1b5 zV0w7Y?+_#&F^w9(&}2cHqNSlhq~YtlO*k6;S#8%#v2H5XEsxh?EPhg`U34|*`5cb* zY}vghQ|ES7!;&{dF=2w9(oc~ z;;kJUh1(M!m>E=HmY_gDMuay?ywR~|2)iu7TXIYQ=K(4mG-Y;kZt2)v1jIt|ZIt=i zGB)%u*q+0hp&UvZHsG1Xc%1wa3}{uENIS5y;_V-cW9KG6_<2oWjvS&>99c$u(EwjS z2pTqTxeAZS!w+G}>DH0i2n-X7?S$5_ShH{oJDB%zVogwI>`c`JQ*xhIBDS4fSc2#9 z_J2mcPhV`~^kcsI8}nrQ+SAeZJkW@c>$yF4c|v$qWk)UJjF&$Fm^~^9FAB0>u^;&> zQ2ag&^6k$rIloDf2BFO8?q5V~g(gNC2a zvD%aS>9aC?#AagETN$v~EDy(TFVQxNM$~>*27NwJ3;ZmZ?)571v!~l(JP{XTReWTZ z7O9?$pPEs(zjKM(QP~me^YrL zBkpm*{u$)|dfe)FEt1KVK?x`b?T_XsdxC6HANYoTUy1&aZTS$V!N$|3<@;G4GqBnf zXh-nQas3wu4aEO$VZ|>Q^3P-X&tLf8w5|in$)>(sDA`G-}@^`X?9$ zmKFL5()jW4yUgNs-;Yh}+dcT9jK~DF)Xu-76Te^TpYPVebASJqCn4db4eY@aK3wlT z{ml2Rt%S)P2q1_Lq_)5I>U>eO)mlN1z$v#BENG;G+ zO&xYy{mO7$da=HE;KW1`W_}`VZ;!V`O}(i1Xftkx284|Y;z<6Q{`(F5{|CljSqM+k zC+E|%C32AmIA@yl-}dJbh>d$vu|2ZB2?lBHhnu-XW7JJ*pE$*mEMKZC zG8>`Jd(Ey6Sk|MSNlxQy8y#P9^3mlJqe@6oO|kelP?PXgvrIp_NGmG=H07Ek@omwJPT z{a>}`&#rc0-+kGny3*c=y(~|k$a(zxGynTl2z7H!rRQ^g)%v~af4^mX62IpE`v-6j zoECq^;S>Jhz#jkYKbcajx60m~vp7A=GC*t6&dDpIboVZCx1Muq!TbYP%+_tZbL?Hg zs+(%N3obrgp1jomR_wH}(mqf5vpth~#FLWe-EGy}!?Qao$gyE1yUqTe?_3PvPaC zQay1R8R2J+Bt}>@6rQUNObC?7E9;miS++{!Oia(be^+jQ+BmhzPPFJq_56QZt$B4l za)A4`U36ARy66<&Uw2-+v=n2Ha?NNl6gsQ#-zL?m9MJ&KQ7fL-vMo^0NzUv+)5-L z@rgf6>t%Sx!D+8ll^1fje_im>+{e@0P^fBB`=5+o$0t+=Rr6X!M=v(nwD?aea7E@y z_UpH{tmZsD^Uk@TXXRX4s4Fa1D!q>i{?RUbGGpCh2OLc&JS#G&p`!zIgiBY)lyFN& zA{t13ep?HEOqlU2>NT)3KxwvPIaU=#9!)uni>nU`9~uCiMg-aTNMMaIG@M3*bTmju zQz;RJ#%RXJx7dxWqIEP#sU4(3GXkCgXVTkd014x@xtBLcr^|tk=9D2Cn z;)aWFX2h6DnMv7B=59OecG!JWV!@4!8yVkx^rU&EdF4*F9!^}GxcH_4iCVQ*vdzid z@=jddH4k!X4y;9@%D}!f*=(w{q2lDpuj&tNY1!!)<0~F^P58G`{d@PH^FJ(xG1l6y zviP@D@8REx_TLx(IS=e7!x(P^YQ16)!_>hwEWWki*OcAu-(3DP-0S}gTx^42ZFT&r zSF=S0Xm z*;T25rpZwjkxp4Y`@JLPb--c}K8)!4bbi*k!e^?h+o#m7_|(5O{mqP>&Zq3IRJz~l zPdPlrX7O8hpu{&H%YhgCab;a`sD#NolQni-Hx`gpIuTJP&`gOCaOnV%hLfO_SR+T( LQ6<4J|Gx4Z)Q9qdR;5D<{iH1q_5^bUgb zDufU^(tGdykKg{bdj5Z(d+t5=-22?;zu(G}_noXYGi%nYGPB+_Z%+G9zX7hPDXS_2 z&YS@N&X7KU(}^?vstO8bf9Pl_t3Fctv!EG3O6PtD034m%-E>qQ+|oBNyhZ-)Pm1ql zPb^?A-|zoUBJthn`_3Hz!1Mn*IRCBeOO{qJ3lhQ_>C5Rxs+=S&EeWQz`4hhV9X9_H zmiZ2Qy1TfOaQ^rXyMc5RNU$XdzHRdhZ2k*u;o|lkKa7MU3Y`M8UWbH001Zr005e=004#2Kgvj#e@C`kq#|aLT+XDA4Zs0l z1-J!J1vmjL00JcFF5q{75J2p72%rEUJNrF-zmk#CxeMpMr;8UZoWF4CA_c{zivZJ>(^*V@U`zu&U~jNJ9m*pcN8~2XHM$@EF^WGB|Ae(f3+5Hf&A>b^JEv#Tp|^_Tmz6QK694r zDkbHmE0;(T07yU1oxea$ex2qwp^LP1^b9xH?~2^lhD7Iy>pgLW!JkLP)OO>0IfQjV zU^jPGQ zGf9$v2=qf90NJ@SXU~&gxJWA1q9)CkvuDqdQ(icGiHz(#3HiG`)YpF#(mqdn_r7aH z9u2#&h|UwY=aC<4yL&Fs(d*`~iNY8-#2%QxK;y@w3f4IlK;#xFbrX|{r-OhiWTfh- z$*2MHfRn6eKkNJ#^os^=v<&h_ge9V%zx^fiU*Jy-oFOSEj-;jAH-F~+3;I<9|5HQg z4AUU1Cv>2gPt3?0otvEzf(Z$Jw?!?c7My{>grMk!a4>DK6-s0h)J+G9q_Yvp_?XBu ziDWwklrGnMLQ(t#5KOUvI$`Pyb}5NVEPe{(oO(4k-|O9=b7WTa+ec^C*+PU&HRMhK zs8axKiVquMN9%gL#s*ltha55>qvj~y0vdbB4G6g1;4N}^V)HMQ|9kY}T~N70D9pAh zQ%ZUKM*~YUCUXi7%39X?CbkzG3HdfW;(Z>`3U<24*ol;$PVR(#iihL=@(0;-o+ ze}dCkq&3Dm)N2_7$UxtIOvy78gUSScBN2a8QUzP}C^VOFy{EfpkarRVk&{T|D^h9h z-))i+6__PMK0?q(STsWi$Tu8CK=wq_<1ti zZ`E8LiQmo5^;>?<6Mm4Wt2S(9<RcRBWq!59ptcP=P+j5C8l{CIlo7>hZ{YV18uZ+KL1TYKX$ zO8U1a7B|nc8Xyea;@x2?s@@-8jFWLgIT1+P!JU){I&GGeC=)te(}TpjH}jnDx6`a! z6A!X2+YeDT62b6qfd9pwC)rJDrMp5=g@4@rF=hS-0AQz`mV%U46SMp&z;!6}5mquy z_R73Gv&$*qxXJ0adN0NUp1dNNO!a%@krlW8Vobgnq;klo&jskUO-xGcOQa;M6H*bqH$YRF@B31aTl;wCwfG#dYS(xnjw#J|!0)e(`WG@Wu z4%d=%jdjX7*hkK5Hg$hSFP5QUzUkcpzA^)W^%%F7yw|Cr+&S=*q!*XnH}lwPmFh(G zKDI*_mc{)wH?AFjgn5tei9LzvM}HbzbS#Bi*gAvhZfda5)%MI0q7pJW57NwqeG%FQ zn3RZe%#D;YL1jW3BD0b<#bPknLYJ(;@{F~UE|ZxK*=!{i70;8>aW{d_CjNSEJ5R$h zEyDnmqpDVkW^RGQJp@}kYy^4_G0;~4QpyfRajg4ki}NK zu~S~RRK^Pg^;aoP3h--lSV?qqA}T%Mp>+~fjh-P|)TUV6Cf78_s6YPQmxZr>v)aY7 ziA!CwLwa_8br}Al_c@p@uupE_ESEaYXszOTpagR;vnCWb!3W7Fg1?S7NM_#U-GKTj z*d5-?trPIXvVczkY$~IVaUtX9rKvZRcNKf}xs=N=IUqOg%Bo3&T9Y=l_k?#&BQ#jk zO0;)b@lX}>K#{wtC02wwaYBDrO^87nUS5y!i?=x~B_>mzS; z-1_onCw@QZybe!dD2s?DPG0Svcdp`y zc5Oy!#nozasgSnX)s=GY^&$*vZrTJA8hn{{a&6lx+Q<)I!|zjMKRRQ4C|FlqxV5Zk z+Xx%eo|<1+tytON_8s06eqvCi@3ndvaI_Il9g>Jyg1+s2E|aTTerpEmPt%kWzaZsYB|^BG*sQmi*3 zppSR*Vlm0b#|W!C`Yxg)%mm46%ID%6`!MW(wu=&IQeooc$tNO~Er3+xTkbKkx>GRP z9aYqgElK92e7(@y9hzZTwd~&OKmMkbM}0)jSv*N}sjq9?ls+UqX_hfXa&@jvFUDsp zzf%O*DcmVyBVqLI?BwjdA0vXzV3Xykujb`F+Oh0b<22EB`0=uY;5XfX0$#Ty4bM6- zUT{=`jjm`8KL7wAY=6)Jc#jJYxE!K}LNg9AA4(~nI?4qbaqdjapDbkFcF71f*|NII zQ49VW`HV`ydj6~2Vl{36jz4e9^fc8^niI6_D|OzNVU3GGyyTjJaAx@M8GBP zaCkGJ+uS1*<7!wpZr?x<>F!`#XWiLZ?r3Rcb2%H+vHu}oivMFr0ZXI!kHz79j8T_~T${8p1>qp44Z*~JH#MpbX5 zq@9j8gHIObZJ9Mlvw?lonFdY-chi2u5j0~m2}xxLR9Qh+vYxL&DEN`hqW@K@7@X&UPSS z^@RhWe)a0f&8a)&}2I?a|)=eI0Y2J%?J{MNRTj- z4u7c6)yK)9Vl@N{ZcAbF(UCf}R_R-|38a(pIs%ObL-9~c5;qDiCr&qOh16VE(P zWjCZeDF4Xsm~b{fBsXEd>&2{qXU0QMFO6N7_(5m;@)1dief3*RcsC5YT{>JdYq6{N z#`|C$-v=}BiZPE^?V`j4$Ln`A4`C$@4i$HcYtN5H=HH0c<4JXs3}r@)f<{$rv(j@+ zPXT%@p9Y6K2ziMZ;{wwlaKDh`de-=yvHQ_JXMqYI299WMF72<;wHH|`)77|ae0?2T zE~M!<;1ISk5aVs#_{s)_sMwUY7GctBBH57G^a!i->bTB>5X|wCVZY_?os}W!)+4u!$;hp!ef|65fNB8}HDzX_dK!dE9XzUQD|XmHlA3fKhUJi{a+-AH!u6Ngim; zNX1>D%w3?fvuCt7?E&p|aCn836eF6Q!xE;9tTNoT!NA(Y*oR?R(yMomqXbJGrHpGh zlgi)N#Vk-zy#FojAy*3g4zxEq(pi#u+9OPXjle+<P3P|l85M6C^mifOs$Kba7n4Gcp@%|mEZ58O70>3%Udr+UZngM$vsT~ z6=~?{^6c_`u+YvduTa$n2VoM!ug@>U=<^X?6@aOoEI>9jN!-%hCiZ@kb@Z;Hlef#F zTk|{J5I&;1AZXj|R*X4ZMXbsIOTixoYA}OU47*KXvdjCEEu#$_krz{-n3bxCycRS! zwx6^+$#qD0qvja1_UZ8_cTdg8G|TeMT=+^u?flTO)|Vr8pDW5&8-(7eRC~_W_;Ho( zgucQN=)f?WJv&5U2NV0?79v7GV*re@0uW(djai;()+^#*^%`NJaL?XgurAubh zW;2Fond*{e>~_4hHC(sYU3g~pYX-JUk{HVp*TPbASs&LKw+Gz(V&N#x;*(EjE+j3V zg*gR;fo_zrOM4nbFa=^h^*xFY2eIfX#?bO0)W_{> zw<>D4h#;`y+%$d$vEFghzEh?%hHM$UBpM&%Dx%bk4G2@#6$J|kiDHMH}A zK>+gm8;^hVGFA3IvZgBI{1Jt7pOt_PYDVg0CxKy&x5nUInHG1&IB-68m6-~_;+$en~eV}8Au07jpMLWuL#3iYK58L!X zZPW|nJ5ncPoEwqASS7B_IWaP=q4nX6Xr)q{kdTvGmmmykk4bt|4NINT?^+*<&gHEY zI|YEvTjC$5H02hpG~L1mE>eoq>ZD$8uDp^t%D=puk=6Ptz2NaaCzE}~5I293S}3T< zqg7f@;XZ#7V`}*q&1smYB`m^jco|G*Nc2H5+~7=bTqtU9Y%f;s7?LW1iNzObt+2_% zGoKzvr^zMPoG8s7CP~qq0(SN%6UDup*S$>qO*+?eN=%ZCKeaBWEFa(v%wU<7=GP|u zFMZ5_ai^K9RczY{gF8JYEg^hH^yR|QTIlB}*Anv_V1~pj;$Xri_cr^o!K`4IcPvkC zy;!K_7cuAL@%my$<^$9l3a6>J=f)|E%k<3XP*@>_R-MTRF`!C-BP-a`p8V?B;A zVn&RK;Q^XsxS{nhbp}Au@mDX9g~p$3tey}EPeGG~uCS-0CZwmY<+%$9jw-;Lh%EYs zD)Qg88sg0s@}mCj&V9Sp`}YHhegI|MU#$Mu+^<+J(>6D1cHe9M&+yOk&Jv)dPmB~> zgyS;MXmpzpFa(7PHe&vxzCCbswrbT4Et;bU27|k)=|IH@=|a~w=NL(SVv#4@J_=;o zLb2C+n8Z2_>v+^vRz#hsO%a7-d(0}cP zTwzYGJ7YKf=uOP5jr(>}3vuUGVVKGWJ96pI>~_PaZCt?8lAXul+^JSBpOc`g%ZB zXm>ncbE~s+p7acU>{it;jh6aF%ETW6N&TgXn*$@Vt{c)*48Jt`KhX3`Y3U4{oQmIz z?VpYQ_KTEt@E-#G(1gwRzG?nf*ZgnlnxIX=VaHwnIO0f-XzzBRXc-cst)Z*MXBpy^ z?3V-Mv>3!7?NOPTndLwrkbWS|Ht@#n8_njHj$pUBJ~VgvLE!v?1n@AOam2Ojk%y!> z2QVFQ#_Ge*HNlVAF>j*cIG`zN=8_eXgi5|!qIxG^lCe*eBN+@fRhWN}GV^ikcQXgO zqfP-AxRh6gd*hzp>fliKn{Rha22&(LfP^IDp^c;#KVgEd^+_V>$SF~LnguN8JU`mC zj}OoRQK@%VO{;*8wHin8FHZr$8mHu)Zc|LW_|~e;(R|JAg{*?7nmbQB<2NEdh&X#| z6Xdl=B;+@+JM*UiN4lS-$R8xUKr-dsXcpaVmVYt)mk$4K*lfoNeLVR~ z6rqqt@o+Y|-XU6vx08HKrvjtLmBaD;R&^LDuN$~xkZ9&SYi2J2Of70EsP9v|%XqK#dvwT~2S?-^vP0BOi;B7!D{|m3x&vMth{k|=}=;uKmk&W|{ zEHBdK$e;GwMssychw2wav;1sco$FsxUHwZTf7-at#IfpB zwqM#I^|N`eCjXM^N00q!vj5dh|CQY&c{6ZKi~$^MI-gaHf1xf?ybzh^7PE+^<~3WpodUqUokg3J9khpnspXy zln7+^>q4i)g5Cn0{!{Mq&$Z$|f-HD!)0OXfgj~4yA7TDY`GuUe($rm-N`M0}+uw5mivNSdIf$ok34P8y|dYjdt zky+vQiS{ypd;LGg*O}qsUD|-vM2!@^p<(UAYPeXq?zdH%?OTpekDUsmuAHG;U01d0M>*fQtsK1ibDie!H^Q z5_hG4?4yV19+})-Yi~W_Mgbq)!Q+vd;%7~e!C<-<9^rufAl$bSc%5lvZnD2u4J=wJT}*sfruNDA_2VSW!d zm-FoJi2lp+{^t(WMV(9Hy>wapQJVJ?7Q~VFS)pcAzMNmAT-sM;uq)UK72A_oGqhkoh`pO*xcWUE?b2~ zlbnCLPSOsa4t#C6aM}Jsqu=berh;RpOU2qd~TWJI|97Y|Ik7ln>aT*L2 zfq*)Ub~cr3##R{Z9zEDrQel^rq!Yd8x6wbF)bt*24l&6zSQ04tJb+mhI|{7MiRFr4 zK%~B2b*x>__7QDU-cgQk&XdKd04+j?*kfwWv*XG znZt<@&0$fX90Z4TP=i|$hudOhV`3)w!K23~>C^X7Vl61GxR zr<5^sS$dzDdxf9SqRrEg)?O$OIHy_ zqMs`LNIk8K_Julg6liSfd55K@J!+?YIz%cJWMgqx%-?ug5e&&f@=;6LtZeS@I42sC zVwk@^%$!mY)z;PpfmUAxw)@EAi}b3reV}uRJnH^e=3?*de|hMo>HX~#Fn0B-J=a%6 zqbW#DEvz>-21!osF(mqS6gQ}~w&iG%(MElF)G!Pq^t5qUATkk3U@$B~Qlbo^sHAi0 z@yXus;yNGQvCo0WYOiQX`z{;WpZS=gph0xh8;pFIiow6g2sc#$a?C{NM$_fx(r3Ef zVH;yg4B#@a$u)bVO-;Wr7E6jWr75Pr2fz*gSXBRIgh`czetT!c zFd-+&fkC&)8Yc4f<<&*!1~Wnr@$e-T^uVFd7C^`}_B9zj;Vp zKuRNf^MfP24KCl#8d$mGPMRn??`#`45vGYT(CrR3&<@wPpzYtA(k4rdHw?E|)0CBr zv&~G!TEk8OmT-=N_`{4#Mc_T}m2;Uy;<$LxP2I|s_bmfX$xZ>UUf}kvJ`j_0X+eW- zYlJJ-$TXi2cWP$ja*V^mzHPL5R%+%8qKW!B1cdV~FpoP>gO#8$rR2t)V7QXv)rAha zpk8pK_Qj&Z4Ru-3-m`oNo1T>ut*2T#?rBbx23v@9iyNU`d7hQMta^@yh8E9QTj-S% zBpa(D*5_be3YWi#V+$mVwsfiW;GR*qgbayRXu@Vf+5G#VWRaDn!RkOl-mu;*Ec-)kH0OZkNGsZNONsmF?o3&ytq<3U; zQW0P6hzH^I@Ja?M+RSU3jcv4fvdk?vrU*Fus93FMRgO(7?ES$?h2g;9T|{WuMxO1?Cs#~L?tNvHXRj%e$)8<2Q!%O1>%1dWc2x z2KlC$i6VM<;}0d9i5d$@ZJh#$7Oh%U&6%%vO*$lorxH0wCzmyMJqgI-shKM z%|H6yLhco{!7Q80)ev*2?26`!Bi4g8|Mb--A1U?N*+o}o2)UhuK>Z>}ydzy}V7IPr z8N_YeyHB=B@KSAw_mM4%JE(je;}bZpY^W0$U93LS;lOmSLc!5-6mtI^|9rF#2$tf> zF)q+jmzV3tVVKqL44iMuqWWS7d)-iw-Zwo^NRNGeo<)hpVm$$y#Ea3hyKZZqj>(Rh zI%(ig;TN9A!<%O~z;yKqdfdWY0`E7c3*u7}5#qfzpRN*T{{nZgyvAdSKjLst=l0TEKW9}N(9j! zo(|XN!7d+_zyu};ZA1}Whq5GfWGcx4d~GUh-@!N~QszgyWst_a)r~iGq8(mUD}KLA ze3cO$-|jHf0a?hZ&eed!irSxKrNeMG`~j#^_9Yt98ceEtIg*BoPye<~(<8 zNWlas7ymbXyA>=KxBHA|Y8>@^+GsY~{3*|yPy)ZUI5k_n!1ZVL`h$uDF^)yKrqtTq z)k$jah9Qz2CMK+f<7k}!$?6zZSIYS#6eo7TYxf}smyr=!Yvb9gjP8>WGrexYO zlmjc&lx4(@>OMxV8HqZ+SX6<2`jXJ3O>gB2pG6lj*v*@0?qQS3QXIe3geOVyTtD}~)B0UE%I3A~cXEgJs<`j)(aKEG|byFCV6FaA54|GK=tKa-|r!PtP~rR$~4OZ4Nsvr+TVLY;28 z+(aYJZNi#%BQDnU5TVj5+FF6FCrn7Nh;QEWifjyEs+hZF@FBb0dFI(VSJ;ub=T{Yt zqpz%-dC7q*2N&sW`2^zkKgg(B$WxANQRAPAkO$wf8Ly~*aUMm{mVRPObzQ&fi>LoN z_py#M6Y4kjoK`(5nNRmS#_g#o8a}5Mui+d) z=%G{yL|1qE9pqAfxzuIz@^X;b+5B_95&jxiq(1cNx#|~tM-vyD_w6`7nEPP6bd{&sLFv)_ zMOo&Ba?b00%8_M$7dt$o{S_4wdo!+OPF5Aq`nm12z{^2k<(jFalS{Ie<}8PD;>gKv z7y8ST+ zA6RZn{)4nysq660b0sI}Dd23EjlF5_j#_Lx(hTxaOCSDw0l{@FcYuE$5)E9XQDLg` zdaOTT27mRLl6OXK^-GrkcdnXs=0e>2U5*_@^0(rf624+=)+zBOdbXJ<4mdN48jWc) zFz7A7+}Z}(ffZX)Mqtd}Zz|sd)ZP2uz5jglLYbmBJ*?xK+2JzOCmh|z86x!^`$Hi3ya0sG{Mcc5)1^M?HM*1Gn{nDy|n%-m>@lh4C^ zPAp|LG7&j4qCYstnpx3$yw#n$!WXCuEjM&vuwRNZ(a06ZOnp&4t)M)Zm13k=bVW)3 z2~td!`MBQi5ds{HUc^TCKwhD^&8>w4*(-^ZR&cs%?k+Qf^CC_WZ;Lh`hC!QmIrMwM zt7VG)eou!&-$(UPo765y z9}#fUCfERy9FucCUJb7~W)Xh6-@E!EnLY(&Gl-ojYI1_%weqy;m??+%Yqt9jPXR5D z#`fO13@rKiQ+?7}fK7Ej)jGFXP0r9}1tV^@PrAxr-Mg>?EwB8YBzygw8yr@(&WUHy zJsr$|K2@DrdczmGSRtPsrB$>zpLpQ>g!2M-LsvWYSYBNyq=@ZMWSh91@~C}*v0U$o zB$xPW??Fl3Q-GQZ>rzLyeS-|d&}wzFAsxf1wVuexvz7SGntwFI%6qG+^>KVZbZ7AW z9CnsY!m;yH$-}oe16xb%DFDJ{>F{*ZIJ4#}d>%8;$1!fZfKE(qM9fVcW!iAMwl*O3 zM3+7Jj8W(Wp9H>Z*r>qd8^w2OtQ`56*q??4g&uR90<<+rkw01C$6TghS+KvrR|yu* zLGGDx&xb@5tp@66y|n_W9eCz!3fX2Pa2^q z?Z-xV3aW9-YesrHuG~HzlZsbV8>9a^pLHV-VnJA*?9NRm#UNu_r~HCXx=I}cl-_lp zEIf|B%kI`{rHtF@3?5ozbBv^luhCMPGfTW z#PBchDd4=e4X@(g+UXa6Aj0v8dPDna>O zk0P>z85{VbX{&p3_Z@Zwgz&Zv5eY z!#&DtJux~!jVgt4SM4Zx*RM|^o%CM=5nAA$@4nU?p9Q;1dy*?=oJbK5b z%+gcC?ms3R^5hh-PrD7-N_!mglgrgeXIA0-+?M-WPe%AQct$q=x3Cl1f7Rk1vKTqA zBHlWb!e8`B=^VlC`ol2)J32tY3ytE%zBMm#s2iaLX|#k#js7gs16VS}LEJR9kdSh- zT@g$Z=`6u)i}1{+57>M30&h=7(N@+EbvFx;70^{N*eyYtl3Z9=O%EGv5k zaaXV@xHK#V4Y#}#lZ2Lxueod$+y%|H4GHFeC{2@n0k+}vWKd&PsW0Nzz=Hy@`?M`43h{LR4fw2I{oq;dlIK7Gg92FA#e8lvsVb*X+ z=Oy?Ofu-t*MPjcssipX(+HgR;{Ge>iwoZdiQ$+&e)Zqc5y2Lm4w&nbyL@dsFz10+%PK`_ErRxo&8uD3H)DsId_uYY$|cc3Wf=ZGYZ6Q>KjxnzBR= zw68wzw<)mnIu5CIZqM1K20<*>25wowyTNotsxo0CzNMD1ZNdV=t;pSD;kSWCkH@72 z>(Eg6dX~0%aSpm#(_K+L5h$)F+ETMEYKfA?VhdFsj!27wF7*Q_VxbK2%JRkhaU;1U zYU*%Wk=@bj=@{z<8u5=AQ0Od>9f}D`!hGagsL7u`7=3CU+mF>h1$2WYZg!=_wAEaw zAuaP~Y;J~?5mxX)s2U9BeYmW!Y_y6w2f^MZbh{FD(?8^<*#W=qCZ_sYjS;R?eM!%! zMP8YU>szP$iqi0Ua-3G4yy0(z2cJ)-3#OylyhDc#Lr;Xq6;C1vS5>8B&$MN%J?&l& zHS>>1t-LZn?8yu^#^$lmP7jH)%Sui4?8>#|`%8DCFhh(1g}9UF-8tz5PgZi$43LlFu_~+XUo)@r~3nG`G0Q+@seNWL1pLYgv@E4wfAmb8$~Y z5j+EWS6taQibot%UdwM=MC)!WE<~=0q)v#NW1i@fFzv|pQOA89Z)iZb?UXVS++1mY#)M$ zJ~m52%HzPvcAv?lpBr9{@#HYw}daJ;Q&_%MI+-I2=`2CGE+2g@?N zS1$3z_QBp)vq(}FTB&&{P$ePg>@*k5p=}u|GF9H()`Gt57O4@-7L2H}P7`XHI*g)} zewRRS&aN#o#eAdIyhKG44mck8t zKelcd^z!y>RKNf0uW#4M%P$xp zcwOHmEPpWcT*tZ-aroyq%ziopslu4<|; z8m<|dF*U1?2nXq4qR!I!fC>b@W87eLAHKbtQ2uJbw0(QjqicPDPI|-Wi4W=Uh`@Dg z^Qw5z#w^anxqMANN~M5}=K@ReH`0p}`gIP}^GE6qyfb#jQ@#{+j&H3cm;IR`ms7Vy zqjW^qir#JAaR5dXOGM?3LPe!TCy5B^v}PCB>L|C$vXafV0B0Ve-Uth{PdWrG&I}`W z&pj6GpffIbG^go`xf?td(>@vRDXe8V`r6BR;<#elwndw6K>VXA(_W3!vEf~iUPW6{ ztg;y3nT;f?!*Ct()e}fI6c2VSA`F);Y&xS#7O#IM*grv{&$|I1VQ^zh?wVZ02W7EN z6_1;-IkXkh1C^duj_8<0m|6fV37EvFsvj0;7>eK+57(#DaSu$RV@(Xq>F((c#7)^L zHsRdNp+Tm*_FVaUt=7i#eVQ-~vN*9LV!d24#l&z5M#oT{nT10_%P=7!nH3E;3lpLw zs_|wqOi7Z?O%5e(8aVWjt`gsh@S}wgReHrN)gFm%FY6SGZ>+cxqQ7_qQrK~=GlZIbm{`7jQ7sn^TiQt=%JOxZJD9=cQuq zLQs+MJsNeEU!mm6q!7P7bivWG*};9UDqlKKR$UY~@>Z4qobxP6>|n-DU(_UX=5ouV zr-iC6X9ey7j8qbS&;^g1vy|KHd;awj12cxG@(s#;4xBQ+24_&?mc<|pJH}vNE>87H%b{fJaehb4U7k z*9^Mn2tuswn&D+OtCtC0k1$(kZvX7Us=2O5W&8|uljpNRng)*1+Tg~d$rwq7Ve`0# zLS`k?etV~pE2IYpDzHE`9^f7|w>^AUlvw$&-4ZF8;;ySq%xg(OO%dp1LBhjAdixBp zt*qc{DbF96*a%NH~ zRzaXl8cAQRG+YI=me-86MvWbU$$YBA8Spe?R(y| z9+#YST0D(~SWNwXX1=T8!!H}K@8B7_&Wc>RqsMO!f`hex!a=UARM?`g-)b0gf2 zZl7`1l_Rl&$#j_}3Q@jfDKQm0aC?C_cb7>?gJyJY7VU7=EhWBu2BSrbzz-7%A_6zW z6}2;uaJv*8WW2b`6nJs;9cKnYKuSLlT}Joh8&Smvfj2zFm7=A^y^jw4hD0;IC{vh^ zKxRZ0>l?w2J#nPBE&Z3KZ))+~nN$&5l9ZP-mAdJaH*C+_KV`Xlv5y{qZ`)iRKC~gG zA`mj#jZ}oN1J?y23J0T$4^@5AK2<%=EyRk~lxHq@#emFnd%2>SnzJgn7ppY6@YP3h ztN}4TMkB2;Az7Gcy}1}x&rERm%TchqJs$&{X;8M(QE8fJ0@X|xV4mO zk)h9+_n;|durbwDs8S6D&BSE2VjI$<8}o`(pU(T6Crd!UDKLPWT8%24FGn~2tK?sc*3@*DHNdze>DXM}U^OLI612Hzu;U%3#)EuOJ z#2sgAVoL^VV9_d5$rK}3E#4_jWDC>UF1oMX=lmU{1D0Kh zJ`5Xy%k&5%h7Bc~r=~%QAn+VFoawe@CbrR8q{x-fq+GmPOs<*#aAd|dJGz_C1mn6o zmt2Qe!tX?#&j`+!8V@KR#&E)c!`XR%4nqkmQr=re(FRZssG51!H;(aAj{zT`40A*?7tQ zt%0X59O2XQegvTCD%Ss6)8Z2}r8-!2ik2%o{r8nUEO75S7OK*p#!AzU55h0@& z>=?q~!4*&eLW95WthZ@G5#=iWE*@PXed%3LL;{0+%>-=7nf91D$oJMcA z9vFf_`(Ub!A-hAULo4+Igk)Md78egQ^`4dX;j*EFHiW*%df5f1-_GDox3-9N_Um$( zI(f6?{I!Dd=uGlW;ost!wgeh$05*+}y2Kj28oJbc%|4Zq?P)UXy9c}nocA>Tx%@~B zh`Ti`C0|dBLPUAqF>P7rZ5z+MR@S}#+7I$Piv_@HJ^mBCFDrEMjO+7vBXEnS>A4Skvt<8n4{fx~FB!fsSA<3QpkC}{)WWBrMT{0aW& zNXkDsm?GPvhhP*(rvRavK0}L4WTbSJgRm0gqk0Dv#}nu}numS&ZQi|qqo^~@&3Bi~ zXkQmhl~I=Ww@9SSVq%o@1)m3Dv9Z01VCtJoc5c)3S*VpqiYhV-Z;Y>{4YG8u_CL{Q zSy&+8J@TvNUiY|W2yD$oNy_Ry*fP7c|CKV`OxI|~Ue)6HpuPIzR28-0F{P|b75i_5 zJfQ&oLbt)Jrn%hDx}sakxlp%se_dY3##zTg9l7ddmvnSmu&Cem^~0N5kCVwhu+6ysn+>?Eue z;rU8rt(`J5)m3~iAn&dM?a(qKTic!5tQ`+^l!_|;AM)NiuBokS7iH^qyX_khl?IujV#Z-fgOH{3hIi^KDcM>PC=@0a|LP@C#ws(-dds@rJ0< z7ZBYB^Oi)}@sUPv=i)r-dxqR&`N{crdlFQXT&|d32T1m-uX@4Bfl^Xetn$xx-$y%N z))wvW9N(0fC2LncW_2x$VAy70cMtruf4F0*|B_Kq?}-M2)R%h+t7c*nZ#7{&5AeD5 zty2VAE*>8if#ph}FO1tI?wTr0dY_E$wk~N?zwejSdwd=Z2biGY>=pdN^XW)|a&~Z) zy5hK;!Yo-&*f8+Rd}QA=re8VLXkA??Q&<7d==ji{>_1opO6bo|c9cNdKFT;(b$~Q; z5X~#0-8WAU1Q+J1w=`E4Nr`13l^uCXzqB~MYgjDl_WF&SY3%DDU~Qn**C|)nrbaW4 zRI}vAgmtS;{K4y%#h(ky#>r29vSuQ zDji-ZE%zGlH8|eOS=a$8^1E3)^~Th;K}D`#pqqaWAcaLGZc61#l&wc-^cmkHd_a3p=2Z_Cvx^x(rWR7`LbT^YS6@5duUprKte;KKRJt3K)b&alxG4#atXj+Jo zLxX~;h^Dy7;+%K555vxhJcq|i;j>ET1-)^f>I)()z#-7(%Z2*u5BIJ}k!6qUF8j)y z2}5(bmJMeV;&Tyb1{$(A7uY+fW5`udywfgiC%@!n_a4$EL+D`d;`=-y2r&n$>eZ>4 zL%1pKV(({F24Cf^ErLxoQ~)+IG?0FR|B@>2YVe8L9r4Y9)G1;ZK4q2|-kAl>0&iT+ zNX`YA??ZwXfm{WH#PD?*K!b>v#l@Iu3|)4a|71?`R_^6bok2+YC{Fo{_O>3LoLciA zF5ff$Y_(F>l=7K@sVLRavy7H`QFy@1D&N9B7~Y?w)0L&}#`)}6SLXMbiPdzTvT9NP zYe;TN;tw`cnq!Y@cK*z2?hIk08S)eBz;#_bw$NmEspwaN6l6uWgk;dwxI>QCBwbK?)8f^( zYW8_dO7CE*)Te-~&R-Ijg%zh~m9kDAIS1FNE(zU1Y|7SG4K)R`4IRDpTi7~*3f6XV zHgj5eILtVws?wuvu%*%7y~G$vYv+&f$6{3ABc%18@^ zw*}l9k6nN|#(KK1rh1hvlrH$$eKzUs{8;?_(dPHV#yZ=Rtu-z!?>AQ(`r%H7?|2;6-OsqPx>s&*!!g z4r@NSw-753Np&dr9+e*bT6PmW)O|2R?snn*9NO>fR&Z$3yfiDMxAw4hs-Wt91}AL) zQ|p=xfri0Fmqk|2K97vkIO~#R#8od1@JOfdi@b(}c@}1w?kuON8_P*ums7Ha%wnHg z=Nb)FQGH-F?-K$|B>jA)W1YgY)(w!wO z!lBipLuFAty-x~3cDDhW;Xx8Y5@*lmFl87sIfSF4g$1~}H(BN1ZgJK+g(`&#Prsrj zxL|J1r*>xMUlP4xnzWSG?@e=wFARWd%UtZ&o5QTL)35F|dKDg=Iah}XGJC^=$|1zh zC#Lfq>QslwkYc~Fj4SBwut8b^e9x*-P?bD$(SGf?d4j_Bv*XZz+2H&SpidXXz5n)` z$4UoJE-f+RlDw#IEIzQLyQa<_MNMSrg?<_9Z!ESn_mBg@9))1sLK4a8(br=fAOG(7 z&)?@KOUuyPfpgAWs0&@lGrURSr>}Wrr2P_`NR*nJ>-pl~f&&x%57eaNuu|y+<6>*sGZ!BQ@ zQQfoD;gOGBtW^vjQ38=d>^e%GS`WMi08XgtwRNxj5f*)!q&UUsfEpg%;)cTd=T{SD zhe;~3X504ti^(&px0qm+UG-&rb;3ZN-mf$w;Zg_MLxCyUbg7{-NB;INRD7hFXUEQ> z&DEK5)BUV>4Zx$DSrnyDS#N8fCJB3gUGf@W>P(SL&peOT`?Wu7ZA`Uqr~2-0zyHgk zl|PVW#u7W)w*(I2VY8i%8Z1!%5PWTaW?HP?JS{l(`+WGe*VI1Wvmn2`2W$XtsNcmV z3Rr>Z9wlnx3t9G8q6P?8XM)V?sn05avU=}H-FlbWALOVx+Nfs-1~gabLdPZ`bOWNm zn-8(-QTpy8hJ!Glz4IME2gQtPmyS&mC!x~pcGAJMwLZnAdu`g+5O!JS^{Q7ytM7r) z>_?Li+jiWzi;XLy6E{}pm#$Nrmfp9t4Q+!WT}#zwHWlaRmNe^j*?kZ1XNB*Zy}-V5 zS}}axrbLs`*;X7AP`6TM26DrCn_D!Hwg9`HuhmECD_BNK^wl(SKqj9h5*N{f$9v8a zBzRBHg=c^>IO{yfNO*5D*^O7i?(QPYM)%c_cxNUl#yc{V;}(HG3 zQM)}4!DF!x$NSicb(V3n4-cwlyrU9~Wf+;gGmHwb|LUxILK7I2WOTCF< z@WyAIE3{n22FsaZ7iE=g6Z*gDTOlgv6~mXAv(IprGb;l4Q8)o*y59 z+qeQA(T_nOmQQAv^H~6|Z;9gbNHF=i+26IwW`z(xThAN~uqU=_-10D!*KJ}~GV{{3 z_I6a0J(y+3N4@o+7_5Mv=eGX@=v0yI@`wuH(*-Cymkle~qHU@=o|Hc9tdlz5D2lT} z$Tb~!I_k6X&aI^`!MuDJ)z#(tu8sL{{>lM*0W3rw&`ue#*M$U?7my* zu+>YxExMyASb#AyqTp%@6h4L_w>Q;*bY(?$$){CUwW7DCMw+RVkdM@t`zjF;@?l-1 z#+bwXtEn1HVei8;-a~i=r%uyXLu1Yw=NhTiS~FO~(`FkQC^-DZ_L!;6x0jpW z9=t(X?r61+iDz(absRC;jv}^HSyr6qe8tb{(A5c^AxkD%OAWWWYuslr5^8-)6;5`ZP+)?J4yL2>pEPbhMXsli4MTX4y7M+@t{$ zX)e8;7&#^^7C9wg#$M}4=bB1?w@*0&Cv+*;DH2e2hLy2~4tH3pn8nDLmB9Wcpf~-^ zNuONl4KtnD`BWwTu{-+N1(~Pcr>K9m=u1+&Ag$}nx3&} zeb2W2(C7aE7GP?;AOHP_&t#90Rb9T=v9tM_DbK3yX2fuYdo#VlKS1t|TD%Clff7-T`l(+R_(pkrL(YutkVGug0Z%M#D z>QVI1by(aun3pjyyZUoiH}yl8-z})c%_a)I-?|z1bujqO(ev@u$%iUEX}aqeA7y?T zbw6I$b1%YEP4{Y4FfqG@c*{2Aaa$G3NL8rf4|ig?8%_6qe}3Sa^q%SRsk#|olK^|? zTdhfFJeFg18hh*-KoVpJd?L^6m0E1x8;!!;t?iMKrgbMu%NyI&{1#Ol8gZu1`Ncr3 z@tL4=g*a$U0}KpPka z8_Is^?h9GcAMxThD_$V>p&A~@B<>7eC+OQA@RIt@q_diANuds1Q$DlVcL0Y8TVnLQ zf3#V@(6PW-`jLD4OM|IP>rqWw;7`>-XV0nRdOq=PC>H#X&t}##SME8Fc)ph6P&xw;doYH`UE**2y0l```60)U5Qf)1ih+YC!0i6q~eyIO8*Lpag?QqimH}&%atUn(v>MZ(*z904RzD5c4gh_dB;} z)_YqtoYCml>rSo{BeAt*oSg}#_j>j!DM#5F*#VmxOVQo#et)w!#YLH4^u_a-D+d)m zXD}f1%8e|3;t-Rpsnruwr2VWje(6AVZMJg*13v^`OAip~NAtzCyfngRyK-q7Js3zv z?dW%+llL@*&QV63o{Kt{$ZotXjg#kha@KQW{jKj8VOwtu>2;x{2T2V~W95Cu^6BXh z--dsh{}U_UvH`4JhLgY4c{|AFW?Bs62ym}KJSxXKK&xLcq^^;8@km=DAY@#)usIV! z70Nf^kY{=QFRSc-40^o$FW|0v{$J~0K5Wgfh$9VK#1p{;^|PGle*Dj?`{{cShGX=* zeR)T`!P)=et}FQ)OMk2D+T225D2s~1&JQA_%#T>f&(AJ309jb*^Qr)3nL8nC@A*gd z82qI98vm(uQj2UCKnJX2ck?hW??2i>*#Q704o%y{nR@kF5VRdSrlxm_)p`0xE6LPY z_|d}hq9pz8N+RIw^6k?;_EGTdEGecuo%F-r;z8_y@?!H%gaW6Pe$>T89wIXJ2e+J*)F2Q|7o8g z&z8DarnJ~O$}2+`3?-2Ty#O7ciJdaFpU#bLJEecA<920a@C|VAtL!|49X?$01`|wX zF-x*ob5E@WbFmp3Z+gG~N|_tKM9a+guWk`Fy3+J}+-7j;xQwZ|!!-;hv&h8*A0%5$ zxuxDy{5q;hz&LHcr7V|#;wK_ejk{wPiZu=<6iQnpBKTiib3trAy87w9go zr>3IP0E$U&fmh8uS6iSk)=Ur1I;bPwBXeKUw?ARA-7c%G{M^#C5tz5AMR(9fasvv0 z0t!NN;+{S@0}+dtZl6F_FT-$I>j3H>tR>RVYSa(LTy^+@B6YL?e}C};w4(7AZGfmOSF(S z(I}$(%xq@U-PhrffP;gSL(d#F82jPYR8_yh5n7kY-1(kHZEJ_}s-Chs@l~4dRmc$e z-=#mL{z`w61YlRLhDMlBz( zNQwUGL;inBEc~Z){2v(qH$3|}B}S)`5VC4rRyR)Zv=KbBey#jUojb~L#O!RXox+`= z6Gje$zjy_b^vxGdJN#a4z)t(l;c{m3Q>m*Dx;=Q&gg@0h%-C52g-0N5*-Unu&gbSW zJxp9XACo{Ipug^zbLMyU>K{)<6Hqobn%9o zR6N8>DCrxN-|`xdnr|*#LfPj_KF%{)qMfK~ws3o}*jys@TxKX! z+dI$3tZEv>ZXmm zriTS@&ZU-QP0XhFnKx~8X7>?PzpMf#0@Gxc++>P*wz1mr)mlM_jszGPB)FY*u-}}QK>8%iXB?k zY@mv8t&?tUC-Q9NMKcMJzsSwku35mKdiS*f&ZhZ@)4q)BMM|-ea5%oIh(9(XmDVjR zn|k6Cd-P~*`+l94f|9Ucg`0X+!)f5vomZDb^6(NKy5%#`t`@c~m|uKJl-25CteC?F zzQbbIQrJo&5p*+&<qiv@8^Q^*{tOmhH$r_}8`QzmEF>w)80^b+yz0be8J|ZQmEI3Eo99$08;uMx~GwD&wK zn;EP8q1vtIB)NQ=LYIyPj(x~moK^SrU?P;832qtr~{%A3*H zQPB_P$604I4qIGjg8wO9%9IqZzPI4G@=Ks~>)L@`r0E8hv=4r!`f4;JS!4DY3(V^y z%duO@+ul-(gQ|w$JXBd`BMH(C|45s zn`55*+58U=^!VwWg5w5?Kh<>H+%r9So@xv2_MmqSh-N^q|0Zsr$u$gdSwk`56#6O< zpidCLZkE@IE5^NmZcRVL47SN_ADwUJ*PO>x{1 z&%`Nd9O-fTBra5gcn!Q`4l-{pi}wd3m0p{S55%OtS1o@Xd3qYJ%iIOT*PBfSNHP6h z2Ab(YBdN_>7MSS&@O$=pOHZu+{g~)7Xq8ItE|P6O<T~% z6sZ}3Disk?NMGsiiys;Tjr+L;{#EaTwWD_xo z3Y1{O$E6l^m|2|Q3Fsu4m30T*HziOi9%P4LC8~U*KO8WF!_V!G70$M}W(wq~o@1M_ z`mZ|ip~P9q{%rfgBXhT6rJ$(tpP_MJsKJEtL2k){Ba_tRV<))}He1@Yd-mgV{?GRR zBz`8W-OjCa=!O%nguQ!H9ORt;!aCHj`bF%AYC|R9f@#KvxlDkY3`E-)A4ZoUng{$l zF86z%WR>gnA73~}&zC3%T*Niq;GR;tw{I<#i4m`37M04?mFOvC#zDT)s*v$QK5d{FF9Zd z1-^M7TjU)^~V6O&SVrD3LXm0MTO^MIxnQ22Y?WcI7i6GO(uR9~z&hF(cWy2fY zbqExk=(W{hh$+tD<~eJEyl}0$XWV-i^Hr#P5bnBJ)a|r%sHr=k&Mz)%;BeVnM8qcF zq!jHP$%rtz65*sx;xSID>afk&7E6m7%j8M|Iu`eu3OtY7iphNR*u$Z3ve#>U#eTvu zc}KF#kT-P&(hWJ}?oD4clFslOBo9C6db7AwRXX5bS;{)D@yw>|a0xLUHpPL5D~Mj3 zm69#xzMiOy*Rpj1Y^>eHNcy-JLN5mu-wH=Wfp{xPO`m%eNx^%!&#EUVbxyG7b<7q* z5PY7<4wae?hB>RC^{RSU1Tl^BpmNcxD{_iK&WRo;QY04X=bcY9B{ec}U4}yh;l%ER z43qXRUz_238{nFTnBSlVo`_X1@b5wPGV0+S_-96${h%rN8o*zy?d)}1u&OWapHeb=N z4~|eXZ-jxu+EY5@JF>8C%t_^E2a!9+&`B+hNt~x95 zZeMd_-FEHxQJe+?{wMF*Xv{lg_mY?C-bM8EuH50hG!sN?na!k>6E>-S?gF!*m-xd5 zK;xn3qr|Xj*R`22Dn6njsr2qv{OnZQ#K}X!D5`buv>j;R=ERnH^v(G6&fsU&pmxyW zuwPe*7nC|gtpMs+a8l7jmR6#XyGqIfThxQ&$`@Xwb$tSKnJ2Pcnq*j2O@%Kj$aHjY zs+-QsvzotL6zOV9YrL@cVCHsbkaB;;vu`ZfN&ETcYWr0#C)t?AwHwj+=`V@L#J>b( z@A(z`{q&7RQ{`z|&Qhfm#Al8I$1@Xf-5_LU#$(6+kN5c{$I1sJi^SZwBkTH+C?qbW z13h}P&XujjhVz5N1KDLG?kA9 zNfnMaqD?@Z3lqIRf7cYA4;JXFFF#KNugq${o8-em~c#Rf&`W>xekP&yUAm?2zo-G8Vgc^4<-l*xgdYpP={D5F%VwZ8X01XEKb(Gm$4L= zDN^a>kwS-VdNS#JhU1DUNL#te)6& z9dAghyB&S?(Z^#P?|$&6r}D45-(7HC=WB@i+sN-*fo$BLnVI;=BINW#)BghVzgbA} zbOZA0cDUVvKU4E-Td1rU@t=;Lv9RPXn&=Vd(1}mVe}>5R5KPY@2My{gi&S5};DpD) z#1jc9h+004yEeMl3;?*{{DG-j35#q{EbIjrA=dUDh+Zda&A$daWHx5Me1*kYcPXk_ z=WDX(Gl0M`HI=nP1Taa@12>zAdSMbZmo)w9t`6P9VGzU%0P!!2q0^Ml#Ud72O+LXh z;`Mcd{XY1~oUw8K8Ris>QluUvmzu0y4?y*##&$2f=Ff~0;~z~#)CTZ=;s*>!&f$N* zD4sd6<>yEqB*wwa<_5hnam2VxM$C{ne&mv?qo8|d*T>z|vTagyjvjNI>Gax4pK@B-np^g z@p0_i^$MAqnsRR9m>dLjr4oU%PnxDp8rWy#U&lZ!YX=ivY zZiiMISPI&=4p6od91Lyg7hr8Oc09_(;ibBN7lF!Sq)hNVR^GVH$x-`ppNw;8jSMjB zmGbnJO>lCi2w7N($0d(jXcZl{>yozB06mP~CZ{2kmR&E+Px&q1ZrO4G7bq{Rb21sE z`#`0N1$m$Ic5M+uN7cnth^aqTk<>jPg{u+w+&+gcU!R&D%H#?=B1-7#rUx?234_;< z&eNoOgBI(B*5$oS`w?5^^wg062z{M(S0SsA%h#93L!i}-p#&vcv!65EAJ4-3Po)pu z7^uTFF1R|8)@z3!IF38!SeQFpwEf01%h^1%kmz4%3UD-QfwYFatU83!WV(~QO!`Y# zJh(loHs`9Wc@4?ll|+5rWhVJ?UG|N{psW1YyvIAlE1L!l4)O(C`-@Rvve&0Br6;ZhN?bGG z-HFhS;KB)6oY~`wFGINGIJjb{PRBF=dd`+#uJ-6qd#muWD;@1}$fi_ccROEs=sZ3J zv6Ww4y)4}lQSs$GUVh-vr9Vk?yDXziueoIJ;#Vt0pX)x#c2nR5y`Hd5Z4!0CT%DIB2{B3&TI}?+-alSw=@MN(7i?4sljL#jRyT!=Qh1iBhV?yx_CaHx z!}YL+qexuHHx?z0`&%W;2PR?6rIHk+`pE0lQ!WEHE`>S5AYt@c%subCr4faCwq@zm zt`1Z5yEI+%L3<9*{Z_xGX`F%SFA3>?XM^8yKQK2#Jro)4(^p=2Z0_Tzjk>UQYdWyJ$r}Z+gvSTeu26A*I1xW_jAk`WJC-@K* zq36;5S|`Zkigxi4S2@}nk z)Ve#xV_QjE=vwotS}Lxp-b*}uP^#7M8aY@HKT~CmlH3;<02iN~R&vpV*_V)$a^fFs zsrM5Xqq8&|&)UbLdGgJh^e@Nivj+&w9eyn0g=F0P7mb3OIR=fgTg|I#)sVY{$c ze%*U&+N!F3RC?1GzX)Z@Nf{>iY%YeSM0v) zqty{x%XGAm#_eTEf3q28T|v$}?mC0^Pi?)f5YN5nE08u>+~_^sw4`u}yz7b7ME2b0 zzBc6)-FZ^VPS635f`{WV3*6@Y7JM3s&G8{K{o|P&^eAY z<9s+ZN}e>SU?hZv_Y7@Og+Au_X4EIm!?WMTZU-dR58P4pn(MEj{?lltpT*-1Vf*B67zg+?4l#A#1r5n*W*)o}e@ z2UMFrt06I*xmBJ{pXAzOZKZQ_3@K^#FYG$IoZxV^^44^DE{4xnKIDSdolhH_=b#Se zBA6=k7sVWzt%e%EkximPBeX`Wk_4xocU58q4- z-e_`_?LRN%YEu-$+vv6z;0_h)#EH#dpGR9+sRP1hEj^&D)|%t7vSzGMpZM3&PA{cN z#@SR10G`t%Dk+<|a@VBfO#5As+XGGk6CM)a%hQrvdg_whNuID?0n=QHy`_W^(xbyX zf23-te5*J^^H6wT>%JRxaCP6js}MezGaT!fUy`tm@M$tRY1jW5y%BpGD*`7BDEP5L z@HxzGaP=vxCbM40~rEWu-2pYyaJqCbPsmu28VgEpavxB^jUr3ZxS z!DS}t0e(KrSdcvYBzjXhePY66gnKrK(0-%_YJmUP7~Er-~1#P(Dinp1iAd zd24-Tl0(%8M}g^`$v-$N8Q$?iuB$Q8sZ*npKj0m$u`<~f-wGtiDCkViM~@5#4(d$W z4#`Co59;343^((r@J8%fh@8-N%B9@pHC?7%_LgTVZzO8~Jk_A%dZ+#nx9+#GlIS<% z+oTw|CTj;du|0^WDD1lbpmr4I194Z(m}A_Ey%iq?FuNXiCV|Gvb#Xvu`cLUOjp8%T zW6a{PCFS}3JSAs!I^Pp6f`J0ip-GK?_(X42cng-*g`M1>>MfVHv#h@t#af}yK0p*{ zE3#D>_kc@+@MC!Q&00N*=rPC_ zXbt#GxnQVT0F0q4&^OvMDqrWcM3@1K!ZTXHYTIB?!E1|)q?RQ-l5wWhX+9sddu}+R zddm^*Bea>O&lMccQ-zD3_l`E>tl#NfO2-o9XjT_|YD}AbpqyShc6{ZuR|%~3w%rNt za#(ECp%yS@N4|4bDCru%XIFFMxTSddb~$Ul-f8^W z#auO=_J^(CqZ{?Qty7fh=bsijD(oqWWKE9D*Hyg2hUH8=x^M&b^~0DcxrHJkmTQK7 zgiI|O9<#C}gIy>>Uu_r4jG%)pC^7FS-P^jmx`#XX@Gs#RX>!gZirDVG^XI+}GK&Sb z3+I+9K=F1}6YT?*!nq?OYIdz3#OEKAzd(lIr8``YER@qCVN|bts2Nu}bJxr7hC5q5 z!C{JwzeMSCxzW?v^cL(O=+X-uN)87nUhX!RdGGcqC#VYNu)IA$DS3TxT!^auvrD{} zkABPfr7!}9;)59bT)0DaKky!fc_k62VSyOyw(#a=Tj7NWw9$dk*kbaK+8?!yT8BDm z4L>D2738?ofg%svi?7k6W^=1-jM>b!3|^>Omto*;y)kvR#ZztF{Lb<0ooP9f%}cNu zx9OYazQ_|9d{MgRWT7-XWxgUe1_DyJvh1TCNCr}F4?5IKZrk1!y9B1Zc*?c<43#d2-Z z_VuCPjcvg|e#vN8x{cKc^+3pq2RVntqfieXdmt+1ru+!6yn^ z1hO{OnU|pfFwLdrxl4xSR=~r>g^Fb$c7}c%Hp%Ko8F2Z1??u?9fiPMNq|T_devi}+ zo@%~1{R}aBmEsptx^!spCwEL>TTg21a0CxNlTJ~zD>C}zOBSHT^lJUckDAE+AplhO z4-m+W|HUalK|PsfX@V20hFha^LV>3IAi&hgN8~vS9Q(QS8mVSmxIB#B(REI;zdV=$ zF~-0%Xq;QJr@u#m5;oSu3wjEkwk`ZR8v?w9-YOvV6%0zZuk6>IJnm+50{lBNBl@eY zqc080+pkW=69mOImKxu_?( z(W#P76eYhn^@Mr{5J!g{$;QB%!)clSeJKQTn~1#{buG&k>4RFXHWFn#Y@3$cBP*mZ zCVF*mIg&J=_0Qz(9L9+u>t1r>Y@h<^TdtLhR(;|8OEb9a=n1undjinXlJ<~LF z1kfCp)Lo)A5h}{bgP6_1*{HH*BE@aoRRD(KU6Hke)hg*jv+}R{2TgLs! z#$7@o1^&8(TsT|PBJ(azE}L0sh!AjFg%01#325Ce-e0=lUVi;b&N_E-FYr^3{&4Q< zPByaCj~aJx|DN~+{MIXtD!fKxWhjDBHTf3ijBK$>BHXAjWdI{IBK3#4dBIlC7n0!N z0%`%7xsmQO^^)tfCGyD_5k8X_(wMZZ^(5(Is8P{Hv^Z zRXx7cZJFk&;ZndV44W;5*iW;OnQAVkV8x8oEeAb`tx>lavC7Z()a(fN24q5XX^*C0 zAoqlO)k%o7DT86aeEcTFCH$n1VwRQc1#B63WId2s51_+)RzkL;Oj9emwDUnetl`4( zpY12j8aD%*1bW>7?yK`R8r)ASXZ9sWc!K4UG;N|qn!9z`^I}^^xlzPC@1=EE6&=_W ziRd5=a0Lt{&E8muf1j`|SOOWjsAz-25@4iAtF+G^pU~-B!uwA=*aC_?JiXs`L1$CL zre+SOmouU);r-{^@4qm)DK}(@s;WvdiK-I!Z_(Kj7=4iK8Qa9S&XYE??bt7nR*NM0 zZXS@nChaK(WZ!bk2wKx-2+AgN5_UK!Ifb=_g!Ddvs3;f!7T}c+f`xN81{*9MYlG>* zanVQ;w-2S;_;(FyB-!53+9RXiP1=vKCkC%@9@ACfPY$*>z4tk^TDfw-C8ou%{^3v32m34V)h#PLjAv!wDm;bgufCfnW^HPG0CNh`iB&VsORc@ z$?`SY;U%w26yMDOp9K3Ogwe;-4Y@g84aBYrw8n;hx54aqufwoDdQbEpx+2MXd{o`F zsH-#$eQj)v8P-odW+o?{CC?vWrtH6{)GQkUpY=FG+s5& zShKm=350BFSU)@KTj>Ejf5@4N*NA^S=;K-b4S5PeBJvX)#@vajSG)1E{o-J{n!9Ag zTn39AfQWDb%l2~Cu4`RfM7G$Qb02RZk}r#J8MFuxW?Yk4}c>c7@g?+Wp%acQm5D}-MxkyY7KWnyPHAD0QJ?R1DFrW1^~~a@m^0*GgB%TA6SDF*tsUYbj`B;{sFUfF0B`=PN$Ri>r1)Jl-e9KCo;l^$71#6 zseA%#tY1o9S;G*P6{ty>4z)=Yu!8@_q2`C*4{uwnPB0}f1}Kk^6p3b9rG+Mj;;N7j z2VHa*o980Q?@LN(0^|QEv@UUY+OT}dhs$PcR21VB7V*{Wa(EDM9DuatxITV;gm5pl zIll|j{DEz{5b;ap|;oEH3anA0-&;nc&Uph>_t>6#?w|P{LYq9l4bXxbgk&zO%sSg-ILP7g&=EZ z51xbtAP~ruA`Ga_!d}1M1(%R3=v(IC>?z5l-%jr0GEPHIw?#h<}$10bMmYm%sk(J-^xl7}h%9g0~zXAEL- zYG@8nbb(#o=PfSe@$w_-bXRtC5cP7yBH7?Q3Q!H`PYMeoLL9;7W~|D; zc;pBofoOZir98*J4a0IGNWZZn7dIl{S__xBU>qqq`DIvT z`k@v*F8qj>lUOK4;6nKtXQ!~576X}eo64s9rD;mw{@S6!bbUpvlWtjNN(OjkO2gir zj=+nX>$`YmlA(<7j@YZ9hl>jQ$>B_H--*Uvf5d~B({rcAGXzU6b3I`4_gofYwQ4;~ zGfw~oDn{R0I#$~n704x+ncbB|c6X83j!+s>bhd+&#Hy1%VI{=A$?fjt>FAWGN@;p~ z*1dZ1n(f4;)MY!AogEOIyhFZca86uhjuDK~ns=HP3}|j3wHa!%b&;+5DxBPX267QD zNuqen!B3%?Bzik4rETHu6~!N1tWspF0LD{8HB~TxEklUal@EkL?q%$myt+f3!2~3 zXK0efw&w|gyg;C$6bROOpM<(=2MSp0W=lEgP-#{^Upzke!u2=&@9Jmz!G`^|Nq!f( z;P%{=03AYO{jI9X&1HUmrZy-KBG6?vPG>OMqh{rLtRSXXZE?=GWWp$eDNDnwC&X5P zsIaBKs4?n@h_@#2l!m9|Sv#4{ory#`5RLuT3U?1{QCjv z8w(Rz`{u>w7#da3C8~dZ0BFNorR+|w!gIlWUAx=k95N%V*xYrQ%T0bZws!m9bKy5p zS0>?-xiN4Bz{+YG1I3&QKb_^>d)hloh1juX=BHUnDZQp&VA)uY+10%;!259Jf}Z?0 zmV~c|=z=dTu0wmSey)v*oX-1Mpk;~ObMBQ@irA?%?Ux6LLws z-+$%Hbo<64TC=ZV@jhv!d}DZR^)g3GxDnm^RRQS$;)Pm}exh5Vj56L2Z6}h^J@@9BzhA=v_T=LET;G$}^pNJK z!L;5Po6@DATNR}fyl2UW9hmK;gIB5MBfQ{s!%k*qpT8QOmDBjWC(mI<@57_pTh6Sbpybl>Hsd}j&CIJ zvT!aE1MsV!EE#)BUg&jc1K2^-98)sl+1hkm{8@icu@n12^Tgwp0>tw`i1=R(*Ersc z$0vnmYBdj};J&`b?+P(FS<<*>JfSwsEEQp;(1&FO=<1W^98Dz+_d(+G#Ki6m&(*EY z4gsb(m>2X*l%#%OQ}TceZXxA^rcL4jge)#%=E`b(^qGLEiC$Si;b+&1{e!iK(3aM=(%QBSE1 z?B3g-Su^KVZt%JPbuN~kD^Wf%1J*bcW zR(rXjwn4;^z)+srCTniy`(4iukMg>o7IoOXd+&0D1cPr1b^(vX{t)?F5ir3Qc09E3 zMY$Q(vv!iqFEhxq4=LOk0?o67-6z4^#px8XK+auqp8DrVr(6FQd+#0BWY+HeGM1UK z;0$6!n#=%#R7D8ASO|y^5RwpDV5CYyZ=nc|4IvN^kQUkyAR!3^DWQaBp(7wA1PDdx zE%aXWWS-}l(f!%aK6}6Cyr1`T{y6z3i#u!GckacVwXSuo>-zpQ;u*Twd~&(TC6G~6 zy;3I}NuDVZSS^zL)ibe6$?gviSGG|-&&qi@Q(IBa!0*dTM!P5!zbTHaMW&X5AmCd%Vq%ZSp0wQBX@8;2^#yK)ACD#%YP4rs&f<3|bB598;DW&f>hRG>y{1^gY z#G{#CV+>e-zY11zpXxgzSJGQPCdv{~*Lfau4ws}?75nKT<(+tp2VJ4VSgZoOxYQoi zN>T97*VJtS7FDep_fJeU=M$O5Y@1^Cv^*EUn!`Ejb zfvJuwCeO%6lBp3;<&+?-I-oCGqngx9x zTAL8KFWwK9VM;Nm>N*dr)=M*BxA+6}v0zVY-v#;medQ3AXkr4b;lkpW0zwn|S7<{UbnuFA#Z6%9hF@ zW-(v}{@Yp&-o(CZ`@u1>8KQ(tr+Ag6;>5EBcgbWG<2GIMxweeMpJy6rHpapGPE-N6 z#7z~8L2)A^tGUBYCOIc)E@3 zZRO7M^9F?gM#gQG`hgsHAgGhh!1mtoGHl!%-kX=kpyWc`%aumWX-=fu7X1<=a&DB! z6DZ8167R8qb0ET(3$XGo>?zNBY_woPbO^6Dg?Kl{ce)Co<5M$7=fe;3&g# z5;1rwSd?RUM0hY3JDKugsK(2la1?4W*0G$GCmZKGC0nSk5?Z}Vmz1V0BWbHum>8%z zsqbwGzfZJ1W*u_$7jm2k0BQs?Z#Lx}5h_F$3D7P!yB1x<3BR*i8pf2QGEakHE`^=V zZ2x|gk@7-}zIQzoL_G|Bs~%t?PbqSIxe7Y#+B#6Inh*<{Q2&L;Xhw~8lH$;RN&-^6 zHyk2f)?>p?+#Ze>Agfne%R&@9VK`bxKz_bep6{!lZaq7&Z~4MC2FvX;Y9ytM2`4JY z812R*lNMt zdMes^v(tPB4?mIcHf(hD>8wvxtzh`Yx)Re4;#g(LX}e{D%ozWH)~++WNNSYpN2}le zHfH{Na_Dy*EhRD%lFp2b9F~r)L zs=`M*y~X_u;pK8<3>Ge8gtDJ4ehVX zjKOKCOy?&SH;uq}fWC=5K$z}k-=zPo*IJqmpCM1Set&U9=T8G@^{WAN;U5OjAL3lG zn}1h(4%Ix`+oUt4s&oGYm)PN-cG5qqWq)maZ?MyfrZRpqQ)5G=EV zj0jYfTENHa&tfP!R#UKU9(X@Uyo~Br#xZ@>udCABlV@o<$@yZp^ z#?f&ICD#3i^Q}mPdoDFpu2U<}(B03NKyk*+*PM%pfsWg@(rF=WxzSUO7s@pf&B|j% zOU;-~jia&8oT-sxO%B!08c~U4jDukF+Vg~KJ`I;p2tew|(_K-hWx{_^~SVsX=wk@4ewy7}7M0?M^=%blS zlII#mCLanQ`vlY$`}MRjlKQ;7y1ToI-R7MU=>)XI^`o$rzy90*gY?tCs{WgIA(=WA zamI+qE5@bcBZYcZ^O#o*nwnTfBuny9>!3;v9T_!e-zr8oyj1?__P+m61`vmVi;^o6 zo??gN^=fA%3-Y5H0*syZ-WY@t9WKS+2_~bxUedg%@x84F&P5wC@JL9c=^e%pdAOrp zyK*|~g3D8FcGUMUAIL4m(rA$w2gQ}PRRW|d*sx%`P8Nxl0_2QvJ_)NeY|O#cQX0B zb2Lv+d=^NTD}lbVIPev6$TN_vF*AUP8=DuLD{1YdB9=c=`g6SNsuML}viE-p$6c5s zO}KgM_BmYW>lWw(^YHe4$kRm|ZuWNY@-DPpn{U_7eBM1qiCl4yD&~hHfDm4K3YnB% zv+3$I+rY+T{(fX(=Ezq}!MDhQpT{*t;Hd03VL)L(Sn8eMk97uemdcJBW>1DrJhZqc zt?ilMUX>Qmbw=VatFiZ}L;U+!c~&cDPz1+9lD@}6)f-?Zv=;&3gHE^_3Px5u$7m2W zo2&>SA_iON#|k!bDmw+bv({u6by9SW9DN$7uet8R&kp^COTLa168p`<=0Ct3C*l8C z<$QP(cv?SOWLvI2d;f1TcZ>7i`HG6|tCMPt1t$d3EYOEHaCY2)#_*_D)uBCWD1i1#QI|Z{{lN8v-Y+ue2eJ`Uh=?{d3w*v>U z7?4l1cWU5?YH^dja87o0?0kCg*2(80&sP1cXv3ssN-D7yTa(Y!$m!DJNuT$xlsSc9 z)%H`jA~3YB9QB+ByE#mfO!c%vFH^fQ_OAA3AQHJ3Xd8`5vjyd+`nws7^@4)8al~ix ze85hE2Eo^+z0t_n;MW`!;N>~$6v)xA=*NwHaa>Voe&?-fmy)4^b8_W_`S!U)drF0v z@nCz~%oUk*N)r_UgC~M}g1un&k|u)c)}$ESP{<4gt_d;9PIpokyY+*B&UhyDP+=PT zpci(R>r51fJo?{Yg}zyEH~_vbK4w%Oa_bufRKE1db~tL76JST*uuE5*5*92uWa1A# zWl5bkV@i2E`8S_jZZpd3>T)H^T(yabk3S)q83K0n1_{Et;+CGZV3CpnWHMg#*Q0+7 z>RG?ABzU0HdSPIB9bi1GQyGT$7lPy>xBJAV6P~A@zf3dFm0d*S@P=UC&yFN7)$+}p z-qqJztoNU-S9NJK1huhy6Sc5-QbZfzz*?qVK2Z^&s5#EE^Gf9av&#p@K*s&1=5mIn zVxdM|qhVwQjN?{L$%DkdFR8BLv|j|;eWwl48d?fE_@#$*q++o`I=8O3V7Io;CgAbD)@RJ4 zB>1)BOR3Jj6Git9&2G3cgn?W|uwnF_ z$+*a)I|0g>;4QqT&Qm0wEG_AlV2m9M<3RGfx?cKuv~Sx+t%pCrd)j2w#_i9z+#&e{ z1UXbX3}CtImRbgFx504pma)2l=}h?hEwSoZ=IugeJs~%`=ihW4$UG4OG|{l^bWxsF zqW^VMrrp(7MuM+&@~@?|S+rUIN7Hxa?`Pnb;jYhr$I2VnOUN>MITrEf#l1QS=0*;E zah#K!`{8|ODtXzA98Zn{Z2}nJZNHWC3Y;srD)Pu%i@svhfn z*EnGy%%&s!ayN_z(B*@d6u^5IJ&4*w4vb+76x;jiReg4|4}Vy$f2hAVEZ&>*> zx_EL*EISbQp}qU z-0x-D=Iy@u+WgZmb9Ve2)ouqpI^VQbETsoeOrrC@aG4ikcZS|+)*7xq`P%;Njh;Hi zxq!jl+=t&ZcX9FCY;IY$X;beiP=`3-Tdl%-dYc6v?Ba7dgVLN)nT2BX5^qRQ3!D?JZB2{bR3qngIbvE3*z z!1JhcbD(z6qj(Qg*WO$WN3uwA^5&blD`z%{&IfO=3?6;{wdKcoR&lIgie2)Yw%3wh z^7CLwY1lo!#hCb&$e$*2I8)xzQcLg$oexL1OMhx;zcPO{=@-s}`9FRgoy1bS$}rzlFH(lTn&j;yU3ukXtHs(;BDz@_N-Oz(S6MuJmv)O6@iy*YeB`eDcjC7uTv-#GpC*)~Lj#H}98YhUDN2 zbv(}-Z-kKYaw^`x592q(TRqc#CJ-G7*GERxknj>5^#Tm>3Nk>D(N?eS&y6c5C8l5j za_Wu7+qpgEggk_xl5uNG43Ywg)t7vVwY|DXCiP4(0@-cI(*g^+ETK8x%(hCh{Lgn{ zW5F;pTq@;MvT-wfyYlrb#|GsS0QzP?0#`$P^2G+|h2|023TSYgd5};59Uztn|VZqKhcSyOD$@!P15fk zm?vMBwl>v22ey=P!1ishicsCd8WYeF29K!~C4luYRPH!X3Fp~(>H=F0sE5DIlliqH ze=rkH2rO!-i3IN-tNadZyL#I294oUU7~aS}9~Mlg^E&th0_dEoKBiI4!h+c<8H5^K z(bK9s$w(#t%|G*gBSR_Ujxo+Jddag)Jk8%&UTJy9z{SvVU%R4=_OR6Q z5A-a>s6ls~GE$GAmk>r^K@<8DP?IY8WBPxv?z;4svUqFLghJ}|NW>XcwujDvNkrG@ z$D}B`FI??m;eHOm@<1QuLCT@X$@rC9yZb1mESsiPR1_rf!^jNbVP!LS79AC?FzNp}Oy4Ua=R zOb{Qg=@E;l;UlH47RN_((r114%^2HrP9!(jiG_y4i<$G>0u{={r&l?-lQu-H!3GoP zg29a)42FXW6CqH3<2?A^k^IZ7mdkh9Druow?!tz!_&1vOx3sjN5V!AX5I{pO)aC4> z!W@OyFy|)mEU{NK7~(!T%c{*>)W@uIb1w%{D?}-JG}rJnmcQLi&0UFh-m3Az%dXpG zQl5RYsi8b>#ixNS)EtaSe?TI8XT+<-e=M(gOqS^Yf`KpAG-rPN-^d6t09%(KzF}gUL8UZU9xr>d%@tRlS2YBiGS{us!EfH9+R)S1hiEu zUQZXDB~oww(kZ`_-px|Z0COvugxC}7duV2l(N`o-W5{Jib}I}EO3PtjWV;QM>J;+_7by19P!4t<$Mb#Yj`lLbig=gW~0ZtmY56emZq%dBswo zO8m(|!cZR*(R^&ksB$k)yT^^!p)DP87P|mLJ*0GTBV`R5>TMmv@FZ0oq5fKOGmR5@ z{bzS)XUOi}4vh6?KBe61D9>^+x0}K}*sYmEl2EP_6g&xoKVe-fRIGK86Q2xFP5jA> zA5tpgF0^KIH6+oT!_G@wzHML4-UEVG343#hFbt06Kh$Vv|zg*UZQo3m6SuyZYHfuBucouDYYm{BQ@ zpJ}XE3vqo}k7XKr%AqnjvIXPM?Rt6XOAseZ4?V@i;?nvj82CB#ba{uHm zS^x6NY*IkON+82caIT$WeQ`nz+n044^?-<4c{bE10e;}$( zldlbGKa>cfOWZR{+h8a@uW#w}$qaUR5LD5uW28&}?W05TJUw!%dF{uE$J=@hA>9!q zVW|3SA`j{SU@NJDwOG2u08r5n<}K>=M6v2R(~_Bze$DE6`@l~NABsLps1Y=KxK70V z)dT9m&@jLho+sqYJ4Df8LOg< z(0&zPW*oOXb9fe4AG9v_+sXm*P?_Kp$YjGt$&r73mS_iGb?l6amtp zzQOIScHMcVI|~2&^xF?)tIY z*rSVj4e<(f{B4*Np#oCS!qJ=&(+v)Z0hxG(Glbh}g;$p&)A!c>6b3T2!qbZRLBP(! zZkWQkX0qJm3$9c0mqEVNg~o>$e*KKMhkjEQ(tk3~_EWvm^v_LizAiHLRqx;|TLly4 zm@HU!F1`=a%sc7kfnu1FWG;4uoSQHwT^3E9VHU?Wo%Hmha@I`1sThFtQn zufE>WzcvKJ-{}k}_srE`v1*%%R~~}>7(kBrvz135U%R{3C{w+|0NQz0k|NaT8@Abk z$($E7GY~SRTiW(3L{K@Z1Y)LYFnCS4?X#3eY;b!{N z+;76%`|n5j_rC11=~BsrbVpJE;kA5HM5t~P)YPasl&4%Oa)1*E|5f?zKkS)@`~z`N z^mye$>`k2|>xZ|t{>B=-==fW2-X(cL(|#sTt7s_wy93En2Xq}HE+LJ62j^0#pGuh3 zLRwl)yFafg^0{OXjMUKZh3mw8|6ZO9lYMWlw;HM&w6D27J+x$5?8{^RjO^^v!Rnqt z|JWGj(glbg^x8XDYjY3%gT~Nd+Z~mMn}lu%^s^XG*9u;ezvzQzjtpZLVLwzzoh)O` z*q$}tk<14JOd*MJOT-|XN%4*Idx9__XVylGr9=yS?|zF&Xe`4W|y;j10w9^PQn zFm6vt=rFhG=E+gVi$V2qXRm+9@cnZ%Ir^6*-r!$*;^}n)tEVzVF2Ff-inw0$8C1C~ zd-Hr+2R*4Syf6v?0z&1Iq%3L*LxeCfpcQGs>+7oNw0BRR`2RTYFtR}KBU_{+CR^~Q zRp65c!a2JoJ|{wI$E1U&$}_A#cziux+$VPLv&1XUCuI+njju0lKOik67#Gf}+{HfM z!M&+F(|s^7&-02CM_{4yW=JPZ@)vYS9dxsmXuctsulMc%{M*7A zvX>If{mr@6pStNZ^mDHS#7?)i2#+o&YWcV_YQO*X+`>1NMaEIz?`Y_+J5HWiMz>{F zDb0`mm-q7nx_ZjQ2Iud2gZ|CA5%KRFn%unx6{>;U+TP|B|nOCa?4o-_F~qQ z^eF@{76z~LJZeRS+c-hr7Xyvh$%zO#Eq~cQ*o$%tX)!;urpfUTA)NG;{CqOBGVG!I zpp0vPDGgN>|tl27Pgh=?Rqc3w(J!J6&f-0lb}2`yWkkbEaav5TEn0$zo5 z{Z>_rO2bQcon?;(M}K}FpT!;K zM&gkv?2@AfYsndlc8nyR-8mx3ig}5tK$zfA@? zsNW)E&6nwNrn93Ae{+1m?OT@y8ppNB(8+ife?SRyB)djENRiTbigd}r0_%AbkD4W; z&r8VI%;=M)MLD8newods$aZk@xr!y0H4sx*UXtA{ir07^lSeK<^uc`S0Tf!VZL7cS zAtt{VtWLBwt>y@pPuQA`+DAM`x)Xm3n72N+d*0Hi7#uGidOELi#ML3GaCxLV&ZDI; zb*PH8siFn2!AZ}D7ihp5E*EdMtZQs$@#R_Vt>PA-a>LrPi~FJ0U7#(;#w_&n#C9M8)6?kHN<*a_ zu`UWh^U#{M5eHT)($k7pDAD5tVn!7D$mf$j-P)KM-@31`=)ttl!#fEn@7*S)8n=<8 ztxqcCr$x#}#K!T0c{+7ry)a$%X9jJOWd*DQ~7TfNU`p+y6@;_M~_y5K6;K1xF{s=c+gnr>FXs~R4zkg#od@!83 zrIj&Ioc3te&> z@5HOsb#uyl>j)kvFxwO>+-yHlCOMAxZ7!O(Wh>QUFD?ATRX6m7(vl3u&#h++FS$GL zsBR;FwNf3AG{sR86WaQqP>@f+b?|pq`n0|I!W6`Mn+-U+%G&Ntvn#pC0=F4l?8;bI zmXy7}LwL53>tVhuCa`Y}O&l#Pzr8N9KPHv4fjp%r|p zM{mp64|Uet%GFSn8rD9Mahkh>+0*!9_%2WjN|8n?*!da&xY z(l`_1BHiw~IxH}kZU!m;bi8g*u2YpIKW^OARHUmvOGiewe7dBzKdetCijg#ll#a{yqqzlpePEJ(mA8hRW ziB)E;w+GV12BzT3ARjSvmHADNaSyU55)*OuI=o-2YH{fE!e-A1&H*yMB_NG#Em8G^ zuHAK&nRe*z6RJZp*CzcAhVx1%=KuFD zO_`A*_pajuZps=l-6D1%WF2z@SfNU)v_cv%Fk89vQ8j%&z&&Z;NDi%=_pZ{)vOYU6 z1dQcm1SNT!Ee@^UZwX+Q366x%8F*LpTNIOA=Sj|PuiiJ#911nlU_zN>DffR__CH|l zwB%%4Z_cJc-c&!bw4&PU7&iy;n8JX)P>_kuZd`glKSJeN;{r0-5RjdAqZHxNnC0qb zRvvH2Lhg=Ah@(VX-_!@i_C96$2VLKL3Xs3mAyX2HgIce;Q)bFp9wwbin|!yWF3&qX z#&#i*yBUIx?y`5-Y^Ko`A!Bn&rluN~*;;zhHEmj}41w=qtz38&5;{6&JfxfNM~m-! z9}_QsLqXBsK^e+mTKej#h&NTxId0mYLiK3?Q~x9XQV2#O z>U|b;en{AWvVihqRsLB|TKA-n38r@Kk8a)DNp(8ZJKG>r=c2P5GWdMlDS7jP;m?09 z!~Q4l-$iHOQ#s6^%lzNgrf#h}wk)R{M`-~P#!(F4@5C{o^$5%VM!7@WprRx?7)?77RPAWMr%K2qHq&aQ`w{CHvBA%7CN z;oL>C^v=^H^7Cm@8AxH1lfF8}OuZ};Hv`CIStF6NO+F3fqy#855L>q|#bxUC=ER57is%8eh47t$h zma1EN_eR$_KBQg_2U@ba0`!}$!Av9br;CCX;R+$0W;eaBxhcO((my%kYCA;MmziB4 zO#L(qYsNX+yLko>*7)J}F6P^VFdnKH36P;pf{E5<4c&h$l7a_StDA(2`0veDhPSs&|z>ayEE zmghu?nVraAS3mDl?&QSXNFoNcq#vU+q?7ohR}+4B2N<`)svgl`5T8*$nC8ZO7XjF? zH*SiO@9_?)eUo%2bzXM+`KmI@|CuZDV*N+4YJLb-b;37+aY^FYbfZ(tteso^kgL2> ze830B&A|(lPu;EU^J{ToL?-I&O3E1*J2z~8b@@U}#Yw;>kGKz5Aeh5?0kVUB2+?-N z1y&2u?I%64Fn^;d?Vz4mpj73rr*Ko1U%2k!exsQ@%O@{jpS2^-M2`8Xi?hdR}Jg1i1^ySGpW8E)BaQWyW#Tfb79LF;2d+-u<3rCzj7?( z<1#O8ws-IhXw+t-vPw^Te@fi!Ltmb7|Dyw~x>B_5_Xs7Z&%=`{lJ;BM-63req$I@` za$8t7C2vL}gLmg7$E!#=Mn^T&zja8^2M)&|Iod87$50X_<{<0yb}>!VYE%6;?Zz=9 z?r+l&=6vXi1gyo>WB{pUO02<}!tIN-j6TR86CBs%Y|%oIOa){3)y>|Bibju4Tcf3n zUTuyIrdCYk^=;^Yl^eE4T~NNXcSZXMrh%6dOO{7spY;uFX&x+5aDHMXyY z{ft1wzIgouQRn>ce|O?B=dmwbhAt{Hn60~muBq{aT@jpG5Qf8p}Aq6Rok(MGA~W;4InMuP=H;@&rGb2P)6 z6VlfUN=8}|H75dew{Dwfz`t;<9`Ar(&P>^MSwTHpUa4SrDM8>=X-tUB%X}`QnWu2| zr5gC^W083Y4Rpv9{*6&0Ix1SJxC(9kRs*~AS;o3;YLf?WTi)))$P(j1Z=nUvQFeA% zK0G8LJ~dwBQJU^Bc+LtZO{LoV+=n%c;BkJwOp5s^+VjyXm8H?BVq>V2c~uHQu{*<5 zQGr+cet+@kmR_@gSX?1ex~h#XDvIulazVx<@cF_3=f7|naWb~{(us*n$*TD!!)HH1 z9O6^^62$vnSj~{)13ct6-1kcT;gV-1mM`X6J|1V?ZkAFgYnSPlfh_yA>bqqG8vKD6 zRN{ntNo2jAn3_Zqg&!D8S5oCbRc%4rC~SSrL1)D=uS=K$o2E|b2x?^8WoCwDFI>Wh zsnA7skYYl855G6>E4QvOs~b%k%FAg%AwN+Ojk?dG$%zMIv|hc|vlO1z_JQEZ@y)o2 z0fvV3ng*NBI9Bv=P|h9li$fNkIxoZEfpZo~eagR8-i3L|7$QtmG(qp)y=h~5#jOUo zcL%ZtB?Y{_iBGG1IOMdKos~NWTdJx?paVb^6{kp`21T~3`wnWmrevAd-kBz(_9caY zwQqfI%3b)vWK%;7Wvzh>1dV(;8#~`J(&5LP58fIMA>vs}JpC*WG{F&tPHLF7_t#{g zPC{u#FoV=1E8GDw#wvKxDqaxd=aNSv0PKEMMcAf?)&5cev9?`Hb}eJKv(T!vtB#e& zBY4eRB{OPSQp=Cg9p*=zy`s84rr}j1h_0G=vKLb$Q9ZocSWU=SCn22Z4ERXVm4do* z0_KxRC(k=eO)pvN7oLY8a$Fk&mVlV9Hr7&_ki6b?9vjrPY}YlyEg6oAAl^(bi7sDv zG4>Xq>CP@-gF0X)+BX1ib^O-8aC!czmM1Nma_5Tf+999GUg*g37cP zXd#l@t_0lp<*SA=M&F`e96o0nmh+6&#ee}Ih`w&#NZxvKk^J(Bi6yXb*Kr%;hhx+} zz1A55eP(#+w;kTc?$!-x58euxI?qS;82P~^A*P&F?56hq;IplE`$0XRX>hgaho-XA z-3;DxC0kqY)P$WyC%fFp89U5fMI|S~b>j(oA9{(Dw_VjWnN7^1d@p5C$?!?a@e(_V z!p=O3a(`fV66Y$eUnH^uXzSyc0yp26JEUyJ@sy*u>5q6L)rJz|!Z5#1Ul-Hoc z@X^?ortP3vp--T&)t2|(;>VZlL9(=L83lw{ET_lw$**UbYRR4utB;;C5E09muL4T^ zf#Gxqo;rsZ#2w^EbWv+Hb2^Mor~Qh&^5}C*epXoFUd7}+CB-Z)%dQN;*`yC+%@@V& z?E@w1+L&Q_JyklnzMs1fr6(T#D7nWke!Na9WPO1{t%FUN*NbM-KbN5hLiDuiS0|=> z6WzBjNF1a~H&Awe{0vEB30lV#jy|4qxh>C5TrSG>71dj>X`#HW2-b!f%dvytaR9?} z*r~&jsQrL022si@T!aS{Jy)wp&4fY}+F~W7vVy0N@;s-0hFL~1;1bBl$*x48e$`OL zh+Ojhvt)*MUg5JKabju-FtneXUFIckp$zoN%Ch#nBd`Q5{KKagD!Nc4IMHpBnL{%< zDPZD^jtMp6$G6V%vp`~&Cbk^U$K%N!DR@Gpnf4bh$GobBaoNDenu$<>y}7AiQV)!? z8TR?eG=yG=fcXS(n7#H{OqIib9u&NBce?LJqn7M@3-T{^M<)VeOzgmXHDv!&NmN$7 zF5JW3KIoGfo4m+SvWbk0apgJ|@$UcL2mIlTw%tqC)pX~HBwI75Y}#8IKv=aJ|$OzUr#-XNDI5UFP(M z=LPk4RIaqC(|UJa4XM1T3Nvk7T2hk!Q_>{nl5|JS65u!k|3`lN3aD-BGVJm&%DhF?OslgfGtQc4p?M zLUR;eiHtP@EApgQ{|*3@3_f7JY)`Z)Nh_pqJ;0O;`s2vRlTnS@3uqJ>IUeHl(GjtU zxxk1hricgE+D2nNA}DHPp9oP!=H(>oijibC#lh10s@o&+%ApxT_=GD3>$)&IJT#k9 zBYtKv4hU9BFkfh-=I3XDM1E|2uW)bBLo1G*rPd-|J6+P>3_s@QV<3F|D1lKNHBx1s?@RVC zJ*zlTH5%uE{*h#cw;R`gtEMtCFG03HSpOkb%9&fj#oog})<#2if#Ye-xQMBq`+ob! z!ft^7NUyHypm4Gh{{6@IS6K+m;ymWOwe;Llh17j>oJ3oR*DC{I&Hef6A$1^%2YsP> zj_@?B$fc@*>0;rK+sr4JCK@XqI(la?X>w3d!{wt{+V3BS=`=BeNQ-kH!6jodR7HzQ`~!by!#fe}7fuWq-$ zlI*_o;KdvE$&w{(9RQ`Qx3;^(T6pw$xMT%7s3>3y3mvncrF*MU#%|qgEyYj}<*m01 z%5(dNlgf8xazNeI8uQ8K)OqO^(%rrQx{n4nkk-?*B9xbW+I3f}UgV>KG=0e@DU*69 zQW9gqh%+j9aQe2>VmcE@4Hos$@`r-UWEYsrbL+nIv+Jp5$<)xt1e5b;tMZ;*lghpm z!4~Fuo@IBoBIx3PN+pQ%Fpwp15=1ePA;T-l)}iHwcg)Jm1{&RBGZtuI}m8hap?s*TBb0mT4XUH{2!gNb`LxGG~KhJ^69;gia`)Uu?4M zT9)EystQ_05Hoa2**|f$xI^q@`8#!d%X_;zOU+G(KjMCz9^XsLbx6$rth5O8pSVT3 zUt@LcloN32jeky+HO0YzM4p{-`_Lt@rWR{Yv0<#>XCakKjUI<5NskY)tT~iK)sRc# zCO?fO?hXT9x(TLJyduv7j61BFmQ~>1RceNnm`&x`^!&`OCsz2B0kZN~%s|O-j+4a} z*p*PllDS4M?=yoo#bTg_!X2Ezrd4TVMBS%~{*L#%i+&?UHA)EO6>7L<)2dB9e$F{a`tS zOs*co^%P0e%0*jv1F7t)VsofcEj(5F`dlG1b^fGbfI;+lZ@Z;^8~YVx*mcd29Xhy_ z$!}df2&1EAjUPEWq}E`;{r4H8KE%SX#wClq$D7e^F>f%e#rP4qihWqNV<lNgA1HOTJ>h z7p53()wpG8k`tGdVP<>zv-D=~Fn8oT_Si<~B^)m1ae43nN-C!i6C|GDNQ`>ID3;++ zhIGN(DAAnC+@P%vPkva_sY#;(K5-U-D z{pgHvzUlONO_X@&`k;c1-c(3Zhlv3U6grBh^_iI{#r5?u89fTo_VZ0SV_=T^5=c2m z!fRk-KUH1q_lh#U;Z&GcZ&RRxWE#S6l_B@kPtEr=3)GQM)e_=U{q46-Hko-@cf{d5 zCH6v%xnkY+g*`4k8(i(9HM{!*6fO2{FVXmv-)=Ixkgz^rsc~9cJv1(VY6@z6^Cs8P z8P0gjXP-*#lJc>sce0>Ov*F&=;+wSoN@pCR9eYc#W*Z3eLs>=6i;92%v5KDA+!ZXD zuKmvZV>a(KJImI@U%Ba@#Ih%SWj}}#=~!j;;Vtg*C%k|Dz8tt@_=8e{GLYhyE(0+D zv5~f!!9QSj{#NE8uG8lSV|wNa0yNcIV}47jq?qG(OXHgk^Fc#H*ngYg(N!m~S#RWb~MB z_ojPTDz#xp(T^;uHH+j1nJ+7 zGpxamFltbw%@0S%GxF9|-31cds&!lE${)U*8R+az%5(~EEVESTBbZ-*(Q0COq+L)l z(iEsK`C~qYRNZ8;bFtx?tS|1S+mzR|sRNXyQ0}0-n_&mI`3`ojNA_harBdIc*dkrD zSYY`KJ$obY=y)j3SA&gz_ss2LcSr+*+Z<44Sh%z7t_!Y*Rsn+FtZ zCYe}XP><)UMSV{V?)Ph&M@g5?+`>#&g}NUqUM>*`G(U+XsW3`=YE@k?*#}6`(nVb|t<86cX23nnK5O4JI0=ZD@2&0 z4aZWmTxbJnCDEA8QlZ$N>2^fIr;!)VQE~lDaU*lua`MwSu@R;}@6!MhQS#Tof4M8Z z&tq-Nm#zfqfWW0@?EPfR9nCEKA2+HvE`{1;<8KX2Ejgh^OFG<{n9 zx1-~KQuw#b{Qs)qcf$2<+oxNRXX)(U2>!mNrnC>J;}GCy*;R_8@wQlXLj-?h$^eF) zhMxOSZN!maQ)J&%hjqD~s>Qg-coRX)be{{AVRCAMkc*3j%igu(%UPr{s|9HfmlUU- z_kC=Nt3bs`5rku;s-8scu9&@#cfxNjhFY&E4P;u;Pd={eCZU{Q%7}Fc?CQ+mwNvK} z^pZ~puY-ID=tFl|c4A!#1?FdWca|q@wDal$+kQk^mYr8sB%*s?JoJ)nT|u{u?UMF- zBBW34kZTD1B=+KasiHDAGa&v8*AZoe<_XvlQR0)*$c6c6e1O5os`3N5+RI}`GYdEu zsh9{{p7JrNfLNHzqVEIgO(&!eqqnj9q?V?P_>V>Q!6kYP;z_cxBCWGM6EU{49xuss zud>9`iTQQM&B?QM_*IUo0x+)>TO3w+QhK?wm*#B-LWhlY z;~FLpe66M_Hk=*MZc|9)-OgmC9Ln)*=KxI$Uem~E{r#)Qfzp4(5OB`m z)9($$;#I_OTV!Mm$oLY-Sj*%lk9J3vQ>I}|ho^B9F|J+wr4ZjwsQlnna$OqqBLklJ zfv$2zrlRUJ@BPing`PB5)!}|9s9XLeX1>}jy#^&?75h9A*kcalh3fiN>BT%qstI zNeg+g#M*?h0wo4OA=J4rzZm*%(YM%4?;&PVs5x4;~efK8Vt!ncaT>R;w;5*Hps#oP`1$Uu z^Yri!?Lkg;#Ro5wFOPxLiyrzXh`~my{Y{`8@5DcX`6fWO-qOcz_!9hu+b}2T=&f!O zLC)?*09jf}5Ro!|Rl2U-5N`ia+E29HN?CNTSZ@+LT8hgL3bzQZ=w;~0xB8bhTTc_} z=vpJ6L%k9oOZ6=IdQ6ng4DU2dVm94l!mb?AKK=~CNv7QK7Zw;2{=vcf?R~18v4I?1 zZ&`yGlUyjOA9DV-WIbPIv@;CjjQzn`~`O zj?)@~C7zxb3h&AiyO$;V2c84_aVQGz(SpCmrV7yapJ41*=ZrQ`F_mIZS3;z#c{B)q zE@YpVe+X=#Po9c?0IZ{Dl7XLvuF>XpO~H>(L`Js3IT>%!bLk(sF8mj&AOD$nMEZ+( zB>GR{k$^~$TMBH{h?;6Dn;2t^y&2hfbSI96HGxEmuT*dpmcH{(rgemvF8Zi(&{3xT zAd?fj;@<6o_(W{TMGOz5=oQe@vZ5h|7#WYaL= z@+{r%4J0*dWV_@G7mFH-BYuKz!sd{3PR)xm96G;l2(-B=Wr5huyv8N0qV&&^@f&yZ z|C;Mrtm+_MUJmB@Xnv4N#S97%rDd1h?vNIMo#-86*yWsXiCerp1=#$4ni>yp%|P&*)=wX^Eqd)NdugG5H}!7mRVTu#FYg>6giJOAHI%pK;7oP3;4;O{ zr{)#=&s~$McKQ8F8D_N)uHBF|)642e^55oYZ+9kVNUw$rd0*n*`Z2TqBedj>BWP1) z1{>;k;~`AInjkq=G~E0>nmIj|2sZ6iG@5Ou#hdGSs9o}Z`^hwBoCl=kuHyhlT$Ap- zTNSvCAPU91HoqZCo~^RN;HDl_*~lj@HF^(boZio`IJq@jGr^k>$zOE#{UjR_M;er` z0i*4ET`MeRMQKAMYZLIv`~5%|3i?+#Qn1MHS)3#WW}S&{ECu&}6f4wm>}Q(YXE=t+o0XN-}T%cc12 zAn1`>k>X~b%=CeV6?x&k-sFesv(b@jeNCHsGTo*Z8Xvlm@M5sG(N%||Rt2s`4Bnzr zmsVg5Zzn0;fVKqM&(S9dD-)ONdzp2EnWCj(F-E{{Vj``&g!)NqOO>APq z&84e-^m=dcCISFFftPfl6Y%@_0a@B$fj2P{2#YyHP$)0em_V3GeCB%Iar}0V++;vR z)SEfHM1DN5qie%EVc+|riX=F_gZ5#T#j{6lVGRU^zJ zuc&BdcMd6kH_xVTRlMjnYoH2kg+-Mi_`C(8J}wI=F;CZFdQAcnq%!MJ88OJwBS;HD zfaYS1ifH4TVqv25l4RB4(#Fv}Q# z#yLLl262PIC9YBoK}ur#^|Z(uN&{vS!5gP>sQEV@T3F+v=7Mf1j4`^fw3$FFrju#E zqI#6c6bo#)>Ocf$M!uR(twGWy(%=8xMu0^ii;e(0Yi2xkH}V?oXb}{EPlGN*srRL> zlMp!oNu=6K1hoB^sOeU!PyXDFVb=eH;M*hBR4%Ts8ncrxzPe5?uf+bo*}IpGesZAc z2itQJ=i+;rP8n4}){BW#B3EHIHZg5zFaMvfT={KdLU)DckKFFQ`>8^_b{r;)@7Pg~ z^1~E{@19Z-LoN)I=S4Q2En4k;W&3&gSB0xdmx+-p9fFQAdK6CTS0N__%hWXJZqCCW z^56l*=FdWQi5*bijd`*f0Z1Keob4ShYRV9-n&>iG_d`X_L^?8oZ2jVv=_*db2?L-h zImhi!U4AU%+$7~xX<-U;E~EM5;xv}>U~F90J=lJuF~hMxt+sskmT+gUr7&2DzEm4E z#xYAk{}*-d8JAZ2ul+icHj{4Dm{?-Q8hb2QqfQb_>>-HQo!G?|3-&VUqJm>rM2x72 zC>RSCY$^7xh}ez2V(%>vInVy@ng8eP^Xzk8>=$Rf@kU+uy&7<@YhAzVJM9)1n8eAn z$8)e6e%!BHX5LG2DGH=VVAAGeLwy_ct+Y9-sAC>RNo?KK%q=pe1mT`n{@-xB&+4xP zzU_*QQBM7V+l4&n4S!jcN0vR-iut>(gPuGF@X8EN0o&fju>1!7=Ny=$>yz45&W&h+ z?<`@a$ud?eXL=?hZk1^4(Od!Q=Sit6`DH(7Se_nj%OL2Gx^@|x3fBli&VAcQ#?M!* zfawF0G6oA~L}BvplPws#s@A;8R9#-lD|HwZ3l{-HZgvAEpW7J76$xLy&RhJQrH_+0 zW9pb#J?H21WMbVVe@W_>f+c~4>^<!tdhx42>izxSo)(wz;gBCvrN=U|A`0E#FXH6g4?r|N zV3O*|#O4qA_w48J6~?6#dj}0e^(S+*Vab%|DTM*Q4u#o-`LztVc+&AHF1IgtL=DG| zJ-Gw7AT%4SO0EjIflQ`-!4l73Bu+~;7J!tyQR*Iyk?15BszzPK#D`o3w^u9gp@X~$ zE`iB9Wugp7n`!@-f-?8lLD2;AMz!9!NHN2gCu1J)H2$AkaF;Mf5ko=K;IZ;yhE6Cu zAM|1U><@79udhyqhB*(LTEbB(|JbwC-qKlPlQ08Eqwg#M$Las(guL2WEOE6pqI{-D zH*tVIG#ekxY3*}V+jdVVRQAz)ITs;KVEo%`9HjuJ8N8VFfD?+fOU*_p@A!7CWz2%u z5+AwgjQ$nE9ok$x{jbJS`2!BM>xW#*_gQ{rqAt(bcSN3|!9 zc}Sw}1q=v=+*{(er_~5-gSBj01G@q&n=UP;xYjQ#3LL(;`9l0oMGPlZiW)KCsk1#f zu<`29aoFpyv*i?h4t=qiIDKxry=-D9J?=yaR`W+)nt%FfsgFk9PfWt_a^UAMS%%_? z(@caBuh%VUoHdT=*BOmn{AB*AFnIjFtwFWncNX(1KI;4b-ww%@;x$U?{ycNSA>Q?m z<21c-+%?D(($vxv|7!L?v7UP+Ls!<3ccit=JhP!n0R4RVr%49t3ymr)3daCw3 z;wXO9{FAAg_?C9y?B_a`{_iZ%t4Rmh4}88&us|comy{-*&BZ1MJ(k5h6d$P2wIo6O z)4i*1V2kLyJE%p%KFfQ*qR!jXDd+dkfKKo#khz$R_Sd05<)8KgB-w0a42H+tI(FMr zZKU>4qPTbcm1FV>97zJcqk~YptOBt4i>y-T}qIcYjQGVg|CqQHP^*?s*aYBrZ zuTYm%;*bq29%!4iQ{dhRC6>JyBuqhTMKcV|644T?W`nJF8VdYkz`=D2irTo{CaDV4 zFr`KIB+HRj#ShXE`pQ!`jK^au^e7U@Y%^Con87cz-})RdSam_e9e=|4=KqJ$A9b;q zm?&m^oH_zF$~>UTH+cFS)bxelUjH{&{z)PKkJLOi*fiA|(l3+&%rY9e+@5~=J}z`PEy~GXe5`S()D+QH zl32-lC!bw(#4gPz;scbkgU0)ep*v#Fd^JmAZ*}+#2>Ds3F(Y3BV4OdJ4Svkk__cm)|gZB%}t1dDAOvQ}`-%4xchzl7EWO zrAg64F7vV5sjnXqJHn=4A1{UB4}SD&H54D_t5l}7LjIL+(IvdXEnO^l71y_6y*5Rh z%HZ4--{Io$bYA1(o1-#xIwjBgNanb2MikChu4IPzy$tPA{H=XMCAQGV*>r>Nd?j6R@l-g(%opXQ*iPxugA#}CW5lA!4S%w<{CL-Bd!;LW+2k6J zhL}yio5#U@vf{R3c+Aznx0b>f+%6_d_`IEy0)MUD0Ds1%{zf3hUcFyDH|&Eso0XTw zLX4!5n87$jXM{Iv(j5}~#^Fr= z?Y@bNqk10umy$qp-Fg}{bVE>ns?Lh??(GDFvSce{RB-w3HuEk2th?^*;gbm%{>fGF z5qpzQq~&>CW-XYzvrCd+M~Zi-B!s^JLVNr!9gtTcT#19knUzgHnIz5Q+4`Rl;!Oc{ z*{pTA=qA-6{u)P;wTzV)ye%xPOJksIvSh_3xXLqGfo7kgoD#HC?pig}r)p#_plOyn zV@#46jSK`FnKpwhC2rQ##VPY~$4^+nm&gHGabYHYx~&Z%zR5I3ZD(lHns=Un*a9vq zDJ;l76k+Ql$gAX}@SSC>GtJ7XpOISz0S#zlrpMR|R<#S3xZN^U5~+5hi&}u;f@7Hi zoSz**1P7}Z7{&k$W}@%qRoUMl!I^hWeTCPTzv;ahe;L-wp43O{V^TCpQ8=+kA;UR+ zw%!$=K&FKC1k12IYbT-D90EpI zsLRrOPiGDz<-{*DvtGYLbE#tpq}Cq$)>U!;Ael_fhFt>+GxXzmc8Y0iE}QXEq~61u zhB?!jU$L$BN5@Vx{l^98-|C0WrQmQivt~lWuL#MGc^Tzy2p&1@6Wfav!DJDvE;rR= zrB|LFtDSdS4SBh7O1|t~1`xe8x1T>%*R$?))uVB_zX`q2RGHeH{-E4Bd5AV2cHUkB zXv~d8DYP^TBi#~AY^~YzJ|fbrWv!$>$I%(@UE=!3Jp9O|vfPDFn(E9@dji1cU`<*( zj(PtbW<&=D7x7f`J=b}X z2o8PpJhuAdMk~&B8;S}MzHv2K?tGY+YrusN00l9T&8_ph?_8Ld1}>mvD0QtjF2||D z0a5Wx-}c4GyPieY4|c5*RGSYD-ehH~c?lK%U_yv+lNcCaSn44JWI`Lgu60~pJ{1d# zJm3o$p0GX9JI#5WWvTBquw{9sHswxIgf@{0AHjAX>qP6HzQxC$x;8}MYavMMoC6!a zRNlY0d$qS4tlkic{LKsH#`Ia)Hs!p2JscguFe|H{+qwLm1@ZOmaJ0q>^W{94mFXp{ zjNRcRY_ykUihtcY^N$|;Mj5@k&fmO6k%n#4$3wdfIlQdHp<#7GF&&tjw)4I9Yz|px`O7D&Ih>xr*JfQT9)m4GjO|crcOfuc%Nm z<|CdlTW&yb3zO7pa!B@jDJp7%fbjE6I||U@Y>5WLC?|p|yuI%LZE_WEBt z4|8HE8=<&s*G?`ysHX`un~ZAJ_DT+vJJO#mccL%3)}O;CUr}SU$iFx> zIg;7orSkF}`Gxpy3*C)|DVOMs2Dm4ueEvKG=z<1!hLWJ+5Bm(8q^5?YK*rw&^vvr? zFQ==9Fot2?o1K`osO%JH4Q+fTjXn2nv|m;FAJ z7aXB`K)vIA4dyyfRI zMD`fHF_hy+ez$^j4#CB?`sW$TC+EAtmo8h6Ikqi65Elm6%;k|5rhGx0n2gWc;9L5@ zQ?AhCF7P<(SJ$qjU=`*AuM7>sZ_;NU6UMvJ#>^kE+uR9@(z8|z=OFfsW({k1OF`kD z-7>?uHrt9%?$pQeSoIe8T6pj4&5LZI}q=^ysRj z-1nWAFr4f#`*P|$&AUYmewQ8 z4Tc|B$]vXUu=aa}|t1?|kTnn+F&fz~qc(%T@@!Ajz}^Es?IZ%e7-AMN_jHmYuY@7u#FPP^|bZ zV}958(rQ)DLh{Qs_Kd~$!M=yTFL}hCP}}M_tWN*3*V{|r_1)AT{m7SYTg3!JqQi{^PF~K<*K%81On_ ze*0x^NGr1HfVcgp1M(5;>6FREWu-5Y{-NS`t4E5IO~8H%6iTY#B6fz+dixTZ*6VCy z&A|o-J^GXjhRGZG5C}~)u+4Xt>sSgdABS(JXMW+Dx5r#(B`r_* zlIi_Znp2vO30mb2dx{szEoXcv`j7OTLy}++m3RnMyp|Si>z5dBo|^90p>2@`dgDrn zaU6Cl(6b|Cs~s3D|3ZR|1r|-8)#x|SLvS}nwZ;LrHSU)7j4lTB8U0+6k)Tt9MvnQ2 zK~Y6~1Su+@SLVtK#f7gExY>?PI>r*#(3~E=@5Q>()frGt9T6-5c_XcDHQV{?77ICDFa2v0QQ{IATzMBtR zr66dp3cghy_5QlqsrtrYK9>E{nLPBp%>4F0`}p;Rp6Qnv0N^E{AD)09jl^$7go!0FuHKm?+}bLSr$ zWkOwPW%F_eTJ8{V7oeOF#wOvX8}Bo35>( zyVp&-PZpjUg=%729yJsz{IkZ4U(i;)S#WvzU zfhk0woB_B(+#8eMjak|H@=t+$`X5KN)S+2s1&Yx#@M-iSKNR2BY1A@kxi!B4ufaEH zG6S3eJHN_SS(`BF#jHi1p;YedV6@d2vr?aQ0N8}i%C#67xt3q>V2Vi>u6toxfuq;vXrd?D5VRj2WrgIKf$%LrNF;D*O()D4Wd;TmtJ^zROqys_M!c z-Y~^&dV2}P$qRlfiu`KXK+U#QsAQIOsZIsuO%h-RUqaRS=eUSs$~y)|tq3a5#s-~h zvZ;A9SbXo&lZ6~?Ri8^z@*&~|b3URqHRa2>FYQST2nqt;R`h9H$-EKs`ewz%zRLSn z0PmMH4pC2blD5giA~C?Qm^h@4&QA_m(Dq6?$iOh);N^JF?Ue*=x+OX$trfe`YIMTN z`L%M-Z5-;uqt00$a_wc67aN;QG6BoXhBwi!%zO|~bI=qlSsdtQR=^B_O@+_noCJo_ zXfhOGzp9dq(uKc;a?R{Kv^D&M>SLj`mTPt6cj6Amo&KIY{|a*T9pe&%d7ga4J(7Ec ziL9_7Tmo>#i%UhBRo>bHwSo2afd(-!tY3QJWKU0Rn1N$aH(%vM$L!>3_j>L!Yy#V8 zp|FV}8{sFCha%@w;gR#L+bk?;jXyP|$Ta`vs6SJ=P?quw10?q{&Sp5DBeG>LARr~= zjU5&%=E8t6@qQEj?a1=xc*B@(AfTCel(YcTx?m&ao3msIJ`8UlVdJFs)tIQ_LCnO#-Zhy zj(chT4^39Br=sIu;c;fQ>%cr#Jxa_L&cL6!2yBWTFkgMh#|-d>`4iFYADBT`Qa^y5q&1V zVwBViwoz^xh$|pu{!uB*MGi?S&gCBaS%GZBV9hru5l`x*TF))-cb2Ri3@(=hSdnC& zm6T?!<)PXwc|)KT;LevW85d1*kWgroL~t$7Sik=ktlPV4rW=@TIx~3vcKO(=Mje-; zD2Zg8YUdYy2OxEt^R}4i(yd0{bfD2+FM3?yMYLPvLgNgWj~8y>qoVAxxD@%>V<(7? zxvFH6(c4nN_KVaK%~*d6B&%ZJdGTE9IWa{YGDMCk8v6$$xGIFcy=*4C8E&cqwC^3* z3|B8pa;#esY4QNS>K2kF5f??S|7yCuL!**F5wXrs8zDkXGe0-HYdcB4$^?NH|l3Gjm+ zmS0eRvYc}*AJ#J?1~RNndS!#Q9(a_r4e+aLdNfJ)`)ra>B-AD}HyL8-yW(9K?o~XO z+I<9pIz==XzF#lfF3(Q7^mB52a@2V$5Ts>%i342R&|nV&gRNPWDrw*_YX8qSKQO0) z|2-#>=knT>a>fO=%IAB*1WK@e!mU=J9A9p6MH^;7pAB8n+5$}k)v**(qQ*jl8H#P} zwoIs?XPugV`s_t%Y_iMGB}?KkCcALr9x#j@#zEQN8TLxNR~Kde;bJ?UNN2JOL$kD) z>_XFJCcCiiDfUp*=}&PfY=!NeYQxR9oJ@A1Wl^j(?%+}MLN4lmZWvw9b8kn=L!zHe z`BR36+k(x-gmssB8c{l(s&m2BukE=E9^92y!ydR*(HYK)bx+NCWk);|bu4pUrH6|&WSTk(KyybCt56m5@!8qn z+Q7~wM9dUGUJ1;TV3jU>LGnRzTj~;Pe9IsT@h#7k%q{3SW{+;vG+Y>*>9wF4Ia~6{ z&BIqLTUU79L%T5|#a<#GujVRrh(iPykw;}Kq@%9BZlD{Mh#cWnBbndY_4?Yi9jC74 z?xTj7oDg%N5X7qm?5_=VYAgDu+^u&$5Pt4w0n2_x*lxQukbFUz6zW|Pg~F(}cGwl5 z>8iz=TAEWzVgET4tawX35Yt$L`Sb(f@n8JOQ>o0D0j>5)5=!=a7E~wtMTgXshbrv27QNL?bqSL2+J;+G`7zQin4?wBGLH%d>D~w z!V0ki@GTssMjT-D|LjYM96=g_bqf(~dzfmFz73AT zCtnMufy0`C62fu|{^Z@xrFvZ=ufm-B;anT3Ygat! zQoWv2{5Ls7Ge`Bo4h*=>ucqoiJX~$rEZZ>$x%q@w6>VS5^z=Af?I>AbCT{oEZ;P>~ z{Dk&YA}SUajfTtx&2Hs&$pXJH{i=_nTOH`&5dwsU!@S&9OxG_f=sh7Vj|?F zBzm00A_tLkS9b>6D2oJ*Mor@;4o+2fsQOHU?6O_n=yC9oRvz(F!iNOjmz_APUC0(Mae8znKQFYP-fnxZyBdusk@k=)En(xgc@zwY4jF* zoZYL_c!ws3P#sm5qER=W0(1;Pa%ICw^y6vvh(;^N zK1Byxj|;5XQCj`IA_p1fBu7Jc-J$?}m|rQxMDm0)vrvt zt8-I8)-~JN(yNT_UIeD@{h4>C?bDUot6bHJQ>q!>CLNufaXdq#1)iNCBT~34V3&LwS(A1Bf~@R({y85&=^cohhGU^?l73;g)YM z7&XwZc?hQo`Nd_sjyFOZu}cN{K0kY|X`8$3hSrA;0eUmm5?0cU+O{l(d-A1j6RYo* z^iL)kN5pu>J6p;1nKJ8YPPuv+bkZRkA$<9EnQ5+W`DqEkRj2bm*O9bkJN$;^+rPbz{R&~iu~B9+BABsCfI1C z=*H)WRu904F}_8LeJCkEL)vP(LcfQi3;n}v7AZ_EcOtjUYOAgK@Ryp3sqxI#y)3$o z<>$Y*GSSl&v-Y%dpie4kM5lZtn7IAu#L|zDQ}gY?xf|PD2t=GEu!=|5{AT)J(wF2( zQAT{lP=V>O<(19pOnuP%8TuG@)N}j59x8w@>wKuiAtbeOEiU$D@1vpKiD#Mtzlsl6 zcbT}UvU@aLfz}%|0S!WGPQ5gYh&dqDPd}MgnvU?C3=Vru*Xk_EYsEh^lk&JJ8ZoR1 zHk+Lz{VJ#Oo@gy0L-~b{##3Qyz9W@278@JhdACtTK)X)ZC^{SBE?E4&DysS>L)-Ug zy!zp7Y}d_cqhSh<=@#(Jk@<6&M4_#@xhxiQqR^I6ClcXxP{7%-Bi1BE1EP&7;rbje z!uivBQ)3S8=hj}oq`uJ|nXcIV&XSF(^UyIWA2iZkdtWvN zu&Hq!@vgs6326c?lVSId)Xr(z<~018ImxvsYz~EovVmopkWtsC-ZdI2yf3^j+s=Yl zx?3kMNL?5x^5ATv-$=$wM`bjt>kuyo;WqeStVUP7=Fq6j&zWqfMSb|9HZz2kMIR9OmIy1#s)KVLOGNN;?0Dn!Zw_bH!1 z@?7~v1gJKGA-c*^+#E(?qgIjap+E>8D_NSET> zDSEb*O#z*Kb`_@zWFJlzYXFnpojlAF8<^hd0cbS)-J|WXw`IC<%MwyDhA@NXii0>3 zQsg@eU@7|K?8h%I&+!O5JUqU5lo$eRshf&f9Cfj0`p_fmW!+=B9^LAJ%rQGVPz*${b~=g`ES#R3|YP)&Q;9 z_54hU8NmtHz1qLa8N;~K%!@)M)9mB*@H2#>Jo2N%yx+&bz0D#wn241z>*fX|Gt=g- zrP)xpKuHF??sMcbLw4CQ(K&o_(3nI*dnIwgr|5=MB-&8B;?sMbS5rtuH%ZFV{mgPj zCDTATUaeu#Ro*7pe38CQ%UH7ce6kf)l}|BFUlFSgWP}xUo9MOVruXvQ+pVL|6Vz_3 zi6JxJ)Qf+sIWN!?dz9Sw@h3SZwuOZS;UU*EExsFHefU1(&}ioU;K-a3x52hj+er@T zG;2OQq3X9?g@Z`@ug04G?OC>wz(x9@OUNA#+Fv6J1o0*7Y7Tj0l-4=`PpI#CU&Y($ zXpR>xWc8AuQ}7GhP*Ogpmt18PE5H5zu~`3F`dHB;I6=d=&WH4s4)ZF7J_4 z$p-eZzlXczx)#uwjTSZ(?_;I~I(iMgx~8yWr)B&z1qq{%^%bi%9lpU2G!dLKsA^Ts z)q*ub6Qj5lcLK^8XP1i0-^Kp^A18`+3G>xOVf#oDReAzntatw_ZltJxD>U3|x_4Cc zI}7?FQ#Or!_nk#pq?`BS!VAx8vi6}=2%ZrB>vfj2?jNT*ti8DY(Tdyp`A~}Ay@8KUT9AnISw7)&Ef^WQ}S66ID%EO7uI&VTR zkTPkPYWOCne=vRTvee}K=>5MT043sv$|GW@ExEcqH#C>3bFC>j^8$jOAEC$^%vRGs zy~ZD$JMgz2rh~F5_MBsKNvUY6OiH?y@}QNcz!fc1ce*^)256#PIHjD|IXCp+h*`dO zSu|_sNX^4P%s7Rzg81O@?VlN_~^R75;-fCV&GFpOrpes+7xv-dVgqtb(e z#w}zy6C&9{N=ngFRdCeu`sjc}(A$)WSMdc&mTde1swOX1+_^Uz8m#wodts)F`NhIr zn~?)2_7#o;mBnr=;4T>ZfU6+!6*iwV;VTxOTWHq13K8JFSd9Qh7|MVA3AyGgQFq<7 zt*UOS&+OTizUsvl2e<^Iq8^i#LL3789%LdqS9D(wwmhpU*p;w06&)M`v+{ z{=6fpqq#APLcaUf{+&fTJIs+xd%CKUCOY%Bx7=lvP&jT9tS0Y|BDX|Er8sQ~3rT6{ zhCgvj3q&1gS(K%(yvw2?^AUVE4`0M+`7bl;fqY@TW`wAO7xvW``s&URp8bxtdp|~ zM3rS*$+k%%_GHJxtnr^HPTclB7sb8=XP=;66xGCXo&4iMzc}wz`|c-Q@OVyJad2MP zN;_eSTKxN2$={jlvstLm zyk>sPs>O2st6^FEEq~#CZ*S|LEP8`K#`vFGWD?3i0!&`WnY;gQ#<&{RefQ%K&^oYo zWPz0pY=KJFI@EjZX0ePLb%iKD{_sl_!`b;N*yE1n;}<4VeWN6zbtu>Gu^KA5PmPaK zq8-WOS4KFrRHO^ZR}gArehNJWK6&FxMsA7Snho71Zu+0EFILOtpL7pd56G{nOnPJA za*pRFwXWjoKFoI#!T!lS&xUC;=2A%*lFl1&2qX=@7^yTIO_N3=cbGozU4cQIZ{ zw4os<5=Fg?xi+p06uvN973Tc@Gy|VU--5*+UU=qy?u71`TumbtnCb4DqNFy5u-qYx-J(?GW~4< zPRLdFwlT;)_duSlvqJ3j!_GGwXHB&`D z(30YP5@s0y+!iNAc`#?^mS1I>@|ac!{xr@Ll;YL!;i&H{lkVpAi-&K&vm`uvcJ2OZ zf4Egd!4fPmccQz95Sw*#z7{Wi%Ga2Fnu@nQaJYA|9XD*9%J>=i)%fz@7cG+tr%t&U z>?^I8ft~?L3^&>WW3@3Kw|4`V5x4X3b9a4U8XuV>v%j+HO*7SA4>N19sBN)DBLNsA z)xH_A-&9kFSLjV{c~!LBf_uzoF3H}k1Yi1Xqwrl!YwgALiN>RVrQUd~c!}4e8pVz9 zvBNS4{JiySw|+hM^}^1W%DH`OWHEk8#2Dhs47o1XU7Ys%nWi;m%`4V|xu8iidh~I~ z!@aBO(-7v$z~aU0-%X2HZbqMD5G;uctmD_&DZ`m9Hd)EyvuC!EW{ z#%fw>T39l{+Kpixng`70~oUzUP{70o4=&k5_Po@_EbiADho}c)gS8oVPQex zN`pd!X3IL=N9CN|?7mHaY6`#QOmcN9W`oCd8R<@z3eCTfaLwgm2#d+8LL?E1q#B=r zCL4~kI%>_@HT{%A4eZMI%D9we34UpMaiI?-mRBnZ^?a%T zaCk-#qf{7L68H<^-sdtiR-blxD1|8~9eXyz>Md3|$TX&+lvMmsNJ#T(f%#bu53LDv z-iD-W+8ZthtN>WtU*B#CTR#N3wXLULS&AyjBE#6}-0lDwLsbiedyxae#J88|25dty z5fy<8z(IHaJy6}N&c_BzPiCSrp6A)$6n-+}hj4-qW}^qHn3z8xN6=-%&Mfz_o_eIL*-_k`ireOd;K(M(hg_q-z=C*cD_C|5nc)r=9C4h)T1%XXJj?(1cIrVGD zRqOg`nT^An392SzJ&g*~@^;*BAzf>him&3kmU&XrA8h6FJS|>8`1!5Hqo%<^kCb^R z?VqTttNy5JScR4i$2)qvC#w2JNx!ZOAq-Z#*`v7!?5_pe%8L;X(MX6`K{}Q|SgLVK zI^VwQ46U^G+^x-+W{1(6s#5gulI$By#*Nfgd;mGJ1Y5+lCbpD=w(FnIH3~0!(6zrz zuR`1&N48(pa_?BL&OI#|0tQeFZ9NEKHMg2>>e{q!B?B~!J8K-?ip zyiNcjp3)r3g0wVuq%mXqk^qT|+fVo>ITUBKvCtwDH%lfuQqe@ya9(UDiY^vaax~gCtviTFoKKrv}GyCs(w;j zUgxk&>+#nNUww#=)xEVBA}7{vLBrX`jtCBxi2T=^12(EN&!BT~y+vA|yQC8R$iYN1{{F6?pb<(_`cp$|#% z+S{}u`#6i4b!?t!0*Vf>n8RXm%*bfH_vhWkI)->bE*8;}kLlp#F_E8T;|5BNrt?qODoYr`0q zzjeB!;u9pVp*b7EL3T_ej87C;@QSZs=j{kqAw~=;F#UIm!E!H+Yb2&9({GbyeZvYEC;3cBDLSYj#? zB={kjGlZmTmAR6!?i>x|77ioS$u{#=Js`MdZi3b$Q{L9iVyJy`ZyG%S28MnxwXp?e zuHCmfcFj|tbY8&t&ZIm=rT$-VF zYFn!DoU9s-f{DsqovH!!9miE|N_d%0qqSShJ$hZq5ER|NGv1_}e_)VSX2sE^t)DdF zidhwOG+8{86w0Mb$%$!PaX^?pY4}k=2r_v#@7vVWo_M&B`PO@oO8H~ngHj7_?%i>eD+f>1j zq*-HQSV>h(t;Lhi{&}+8EE&XG*Kd)9N;XSAKh94klR|XJw8o~>cZ?oy% zO)6mGbB(r8Gp2;Vr*m7#p2@>;-RF4Yv*mEJwRwds&`G?w|Ki&DN}AJ^S6_uFWPANG z?^byOd#ZLh5d>=+IQRh9vR)n8 z8_#*mTQP`?_2Vp!Uc#DeKEzjZ_AeWSz%qkkTUXxhp87Y16}p#0pR7vG8Ul7Mp}D^d zipeC;6~u8(d%id*Di38v*6v2!_8hB9ONTiogE|iWj54of-Hdf(ga>1v&J(<`5f5*b zGL^H+Dmk)I+nAe;4U>SN^qu9my<4_qD~>N#A`dv;Rc9=zu2fLvyDBphSmhG88nzr0 zyJts@2i5OcR!8w=&&BY&pBMUlh#N-n1pzFX3d zkxI`{UIfXop^b*Uw^5YB)^iE zj3KZi%^lqnlXlok1#*4rG$-vsY$@|ngt36YglM?@7V)!8)WRYb#=gC%^YgPWW#H1j zs=u(ypVuDk637rkAVjMdKz}4kj*!3xgzp+R`lG$h8+3v#(R0pf=1b_!A)f~$@;+^_ z_O~I!@s??BgbyV|M>UTJFu)V^=3@S>9Zk>8$Hsz&r<^?TP0ixz{$s{Q1N-fmY!-ehwivRDw+t;Vzh`dr7ihrn>@@^Dn{`8b8)-Q4 ztpG(Bmz3|l+9-KNk|*f~RjYETDljM|2oiLJ9}7HCLiJCrbB|zmF#*D|-&x+en+m+H zegk}q#S`p&)3&kp7=LZ=&W_3dqvkl{p+Ixa^HUhGtKz3A6Ojs?+HL+-hu*^5MP6cu zr;E9xTGgCRo<`;k{%uXyUKOK7U*hg3&k?znx}8Y7h^m?5nGk;a+$4tmt*C#|#^O{B z!z8;(iZrTdkIxZMB2-JkxP=(KFrXtIY-7aQscF1^i*|a0$yngUJ3S*yE4YCP{n52O zhf(kKzev@_Uir+Ny_|F|P;Ev+{)z`qvd5ytMv>)iVn#n&;ZK;k$-}RCQYHK96bNXJB?U6OIkRg0pA0PrIs5RpgY<8g_gm9u&AM+@EgHM+iLgZc%1p?Tilwr!ke2^s zIs3OxDJT#W5ny*ZR=VTb_CVm9n%^njn)zjQ?FWorm*w2--5=XI?J(BPSrV$}Z=_&2 zS{x$MkSG1F=Fz-P6UTplz)}G;<78HbO$8-Qv+k9Bg zv#^{Uh^@NIRPX?K6+`$dxN`dLipKFwJGsr!B z@}m};n8L@(^hh~M_vx6n$3~9f4rEgn@BXN#F1HHRW+=8M*6Z^A+c1=m9+>2O-!H*N~#Xqp=AK_m0W*Rm8Twi3xtD&1&P?_Q|^CJ1;3Ln__p z!|(uMkr}g!&Z_w(nBn$Q61cp&KP82K0q%^&OcM^bSAs(*3o0SC;0^O~=L8e%rv9_U ze(yX|f?j;MwrF__A#D0BM#~$LJz)%1#<4{D?$QeCN|Dp1IB5Zbr!Tk#Q{(;?aU6ed zF~lXQo?@x}Dvq<(rKI^{ULjdJgOg4j1^J4smIFLi1?qS3_&4 z4GvOsq7|g(Lfl_XG0+frLrBabQwR_nv6ksI z*zL4E`#A41r66jgq`e(fb9gu`<}Y2@niCvCeApdgQE)i+p1m9p#4Fi_C5|s!p4I)K z5;Bc8+S5^181Pcw5VFlKY$4+J-3-WB)d?Yvb6;WkBDwWcp4t+nL~&Weqfvg@COuA?UUyYcF$6w#u`AdRw7lGK>?!sv9?G zLIo@$BhgRb;~KvMn3)BCFIOy6ymeQDdWQdHbIJULDVJ%JTD|@gVemkTUA{u^V!ETB zl_bDQ`jwNHct9%Co`%9P;jBemQhAl!=b&BAlE|i}<~!o57X6xT&(;GtPIQ-Nk9ppbZcNlGyTcW$i4vQWXI69CK)SI zTvvb_H(QEP8x0qE_ujp8>Lk3L^R2B%aT#!oa%Km}OGddj>oz^K1^Rp3%?t4uYkrvhwz@S98+tfR5>Q&`#U#FAU5$41 zuM@A+;Qb;vizn+2xlWo1n)n2F`u2~KXBD_>+I4lj?Z9L}m|&+F^!9SYwocxRoDu&R zC|fRZHN)DRvE$TN!#nJXnv%~)2GZ};lm~AnHvI=Y17Ydqt+RU2zZ)O;+u=%w^MvyC z9n#eeRU3rbUkA(7Bwx(l2l<@Zq34G?8A$Uua|9- zew4gRoYf($wx^VJuRIIk_47L60Mgu?#fKdey>{h&k6Yx$Mybr|_<0cXU#0FR-hZ5s%*7w+)_E29HO6rS)^8^mLfvpT#p-gU-uWWH#l2q83*89k0z9T= z)hh`Z=u@V(WYifmxrWByypmhJN-Gp|$ubCd?ND3`mgThgR$<$BvCd^g#++nt6IC}D z7=vENGWEOz+gw_^idP<)HOfN8BLiFa!`RdHm=c<1Bn%~EDte5&A~P07Y&F4nICM!v z{6~$Dy#Cr{^XJyW`&XR8k=OUArwgVmN9L`C_p-&06z?xBc4h89=R_9m^EsDY*~puJ zwe_Q|hwEXl^6vP;4@n&l9eMhE_s??cir%VGx;7aQIK3p9MCC{DjFlNERQF|x1`ePY zV24!5h?jWX#fuJ{>7TEaf~h*uxF!M%b2$YHwPGT!vppSukXxyMz8RP=Im&;*b%)c^36ba|@+NgTh6$J-Ln(MOT8~Luk-Ddn~(W`_T|z zOyq1_ETs;Hlu`_s8JvN97%Wpmxt*WupHfvJ-Tde}#HP4{GQ6Tg6^L7mGjnYn)JF3K z!pOC$bU&msY=KT&$eH-Q+)(=I8eAFf*{rFg*lXdOsx+hI8WoAGIas1)chg@yGkw1} z!sTb>bI>v*f4{{yaVz%O6^>x0&II^bep#C)1nZjeo9K}7O)?@(|9w-!#PY{{2NUYx zz%8D0C=q4|qFR?@flmlu*jm$p73OfS`YCcuVzA$2pvR;rY2soj92Jeb>ayjwjP=~s zq?*0S)+UrjpZVz_)&ei@b^jI$I_XvHZc!aQDJe)n?5}4nPG!)5n$pcLpmUpkPen?g z%u<~50ShtOLhj0dWzwx1`RGWZswlV zToW#j^%&E2zfOXZ+a}e}dY32~yEk8$ne!_svlj$%AHVUc=00Q$4>rfY3cV%#jOd02 z0DRd7Ii@|fPlmC0Yd6ljS6O&^IN<_cK%PVa2e9)O(0F&dcy`W(Mu58X%?Op`f~rgv zd3Di}IG{XjUl#854D|){O<;V88>Yl8O#fg$r3g^rc?3j4-y+mjd_tmgNx}sLT2m85 zTc~m63UeINgj{>M!MMB++hyu{vcE@6f0@&*-`4#W4}Ap}E)*|2gr~WE z4R_xCZMMXo`7OKybbrlMy{-7S%E5CXQz-7gP4Nc`EdV3vR{`Rh<&Y8H0_5-E-(Tjs z{U6a^juo}fYN-84{Ez7GFEi%aAJHFuk{B{sslDX%d-V6WY5wN-=nreU{U6=RAF-cO z6#-RMoVaiCTkOZoWy|*ZW15asx7*_z#e;omIv;g;j<^NllQhj#p`Ap;S6<5*sM4=P zwN+xVc)XL6IT91t4&r|RJV79tTjwJ*i{!;jFm-#nvT7*q9kFofQ1+-!zsD!$!;2Q5 zH&uGW2>8AzO95MJmucv6QmE-+?@hy3pToq!8oyQ*G#Z^zu73}dcw#KRt&Z&6_E|s; zQ8)5`1ArK~93)+~_s-Z+`O{GKYI}l3^J;4gfli41)`72`_`kCOb7%cnU=n@d(LbEu zl#3!(``D5jP0Z}QM&@&CY*6;8DnH7b-Ag@RejcS9H~M4E(kw2o8lx>hEgY)VyoYx- zxg`ph*Y-w3bgSp_KI?e5O%3;c?z{jdV2qG9Ff%&T_WGe_@^Yp`mP=;K7tn=wQZo2f z$(PivlML0+^d;MKa*FPWTPekp&k|i)Y*S!4;O?b*d_B3n)qz&E#6i;Z$cMEZ{R_j29@O z@VSp>6;rw5O@D>4aT7eqeGf=;@UZ;pK{>s#5$>`%a1b^+t!7ozwDK%$%K={)T^I+Y zG8uaEjC|tokmv383oQYvNZN<9=evq0uW^b4r6gvYbEX3E1DX_O8?`%}4@TmHe`$G8 zKYcA;?jVH;CgK&?)!^<|t<_9GD%yfsIx%UMQTfm)CQ1i0Q#*r+F>bIn=G85i{0ks) zI6c&@bYR7!)a~1VTCg>~Yhc7_v-_!n-swtZ1Rlpf>#HSVb6r|tS zF}PRVv9KiVh6rCZ>;ooDqf9j4Bd$!5W!0B7R*1x}5|NAH7L_sOE73@XRl-8hb}y=l z|6{G5w*M0+t64kI`tq81NK}so6cQedl*~WJ9Z54W_fFG-T8VL6Kc?8pP^C+I{PLfr zO8Dg)(7c-Gkg^n(uI4(JE-`qrW!1t_ke(DzPK!z%;xr)VT*nn+e0wyZ0tfL)7d!Z( z#(Lb;dp1H`PH2u$roeiEM}hf{Z?+*IA@*1T{!v0yY^9b)5v`qomKo=FljEgKr9t zJ3`Iu)HEE_K3doQlOYdQJaNR&_ zxV75&(OD%bSXe?sce(xoYs0g8lE>NQ_FNHegOrsTMLEwH;bLc?fL~@LynAePW$l`g zB?Tz$ua{XzX{rq#Nzx}g;}}E;Zn=9ZrODgWX@}+}u)W~i>C5btrQq#ee(0&{4&g0x z$Wk0xM!=YPj4WwqR^qq%TZ3h``}&uPkDDh)w{N5B_0+(pI((Yv8ppsie8QXz0GeP% zz=YnQNR_-JxAd96Gt`%B&0SoKaDZcidIq=qI$qb9N@mvx7ORG|AA?!C)&=G|CC)An zwH#=j{pBOBBgz6i^lQwHe)8pJa58I!aPeI>;JRNxLlG|~4`BnB3}I#6sQOUbiU&2o zI$%v)oGRiM^$G+=Bt}?B)(s%AIle2<>Qgb>R*YLV(cZYU)y3YBi!k6=rL zlOtc*SK7S2`Z}C4%fNZGKH`6U}uB&vzVyjod|eV(na)CvlA)hxEp>gb$3HZ1Bm6Uu~tM?CtH9wPYL0TpXma zKCfaAJHw*(DLjN)$u-Z@Z`SHd;zB!>h#ox%*bqRuQfS)1(#PyIwyYOODbk%S+cRaf<$`^|ZLJvY;+ zRNa!FDmq?|kxEwvN++oDz0I<#oEnd}l4LUiEy+u*mBAd@xR3Au0jnm{dS%t;XtY*P zuvP&_R4?n2>D1F3rm>$Ew^FCYm|BUQ^QFO^A+UGd}wXO>1~Zz@%L z;6|0fi0DqOc>BN_o`IXk8xNS8*Au(F&+byUMCNmJb+|_px)Qd-w6E6hZEpjmb`#Q0 zdZR0&B(?pydno6^r5FVpnzNTtW9@B}gNezRz`Tu_BU|H^o8e($kg)Hnv;!Zl(oWGI2h>B&(FWa(4K4CZ^(HE5a>rJ!l_?&J zUhm5?h97gaWF8|6;fMIIo###GrSHcJ!%;^Oi=XeuJRCEIAC1LGAMU)GI@FOJjcI%u zBRx?FZ@+hY23Q{pi0IT0H^N3GO}>COQi_kReV_8U)yvNj=#biKXGuH&r6u0*PT(ub zB#O*u0^bfGxGd{86gKi?fuz5WHul0)_wP`H`HunYevNXU0^K>P#G|YB_;?StrqY~$ zNj?(DjT(_ZsV8ff^9oquo?of2$GfT~kzXCdadXCH2HDW^r@-_QYjjN9q^deXsaMm# zVUBK;N};LxYM*|9%bxDx=?;C_8TRPsAK#7=STOxmDAdxupiFch?(^9;AGfNDEku-` zdsmcgcJ#}PJ7=)F_)v5RCS;lI^hjcu7U{Ug!Rikn%c268Y^do(pchoXN2)K|V?uF` zCqCgGDe$!)tYt-&T(>X9Ok-m2D=2vXY`F9&VKVUu)Vgjl#YVG>p7_QwD)h1wT``8P z`2A{Iq}}}^XSNDyqiKpp?x)O2snGD_q9lgvlVH33@q^lO?cF4K?W%EzV$My69aI-j z=WJn=qR7n)3u*g3nfMVf&9`HjwYK3_-?KbJ`2j_vatM7J3fTjc=nuJVA9qGgK&8@2 z`hf%b!4riml|kXTraPNA_uX*JAgJY61rGx#@=Fh^ zbKeb*ZqUZ*Gft9%yhq;i4+jnB=qY>)Ke`rB~hEOM9D_8~VeL zV^9Fx)b1}q;@a~nAlUAIW*44wyV>gM*#FSHfNnc&g}2`0^Qm%8ctSGPJiHe)w#V`O zx2mWPvq*4mx*|em;gjd1v#?JfQ1l2mNA5+kv9BC4X~NeC+N=93eD+?@7m(-`w3x+F zN5ugwJFa>}jL#R4F1+wwF=|gRF|38Jo}g7cFh-bOe4xBo@7{@y7?84c6uA#d{jGZE zf?!m##%BiuD}E@^$QXS0M?e)Q`{SE8f}z8z&m62B9LXp}wWA`f+I?fgJ?=NP7vMP! z)RGd+z?(#BXY=tdcQiC#e3J3kwgZxL&01=Q+UaHd~~CJ z{-cu{FTc)F{~d2UIQ^Z?b-%osbDzKR#)DLP-hOraXB)JxryuVzi635_97uH-+7*7x zS2x5D-m5LhH&y;FCdbtee^KUxbnV#Ij%!lHv1eF+uW<8nJ!CC=e+)LK1Ns5rn@3W1 z1$bJgq*j9dG(sj4P8n&a#mDP|PMW^?XV?92+xO22q$3$drwF4${QZoE{V`bwc|GgN zG}2)9#xV9($&)hG#j4B(YM8Pmt}gptendW_F=(x=;Z($4K{lu;#Bgjk{t)p2(6dG= z{ex}s=3Lv~o_T+p|K&y!oKmA#Gv{Jtd*w1c>#KO9%aq(K_2B?o?p2(9s%_sDUoTnz z331?Q{}xRp;%7(mi>w zO_Rdz6l@t+OkK?q=+xlPE#!~GbJKab_~PPt60_FOfa>73#CAcP@qP$$G4L_VGHdD8 zKQxUBNFj646%43MAJSJ#i5WREU?q3=)FkT$*m`C>dFWnba?GL2WJBT7$F$XVVx{Ba zWZywGHJ;Qk8x9F$9KAhO-~*v~`KxG_eUIuEVnL6}q7j@HG{F{XH*SPd9@*7OAi8F5 zk`~<;z5Kh2DuEj|ehf11y95rys+CVJ*?NQGa zBa6k^?Tg_7eI64XKCjwE#yYs&gNFzJMwq~vKKNl|d3{}>m#^;X_tpV-# zL9m5h?8XLIlCjomHOP=F54EgNqd2aYvlRi=hxl6ZIKS2#0v#e{%~nm++&;@Ceb<=T z8Jn8ax;5!OJnIKTU4_gEmq(XJ_DTSm`bxzaj9eS>dz*JQ@8;x1GNMLQ1}Mq^j2D2q zvk(DRAj;Pl#0}1V36H>F2b=U|$MIhgjVsKGLAdcod*6~lDgwHqDF1yL56hqoTvV}m z_nZq|1b?lx>uTJj`zQ{LMsK_#3SXA@t?`EXub^^D)m#_04Tql(Bi6l@;j$Fd;gyWd zHhH3)etqZPM2ko(cei!7VX0aMB=suv(uZO*_MEzfn;}T}P4UQ_Jlb+3@}?8AfvxB6 z;)90afxT@1>hnx&>w(*j5Ga#WAM?S8$~uu(Waqef_&_z5mLu(ji<-~q+RgSe#I`$_ zevF$9Gq!ocU>=yOYPUUFe{YQr39Z~a{{_@=?{UdPZ0G@a)BK

=o?G2~(w3V<2KCSoKiIngHchb08 zf5Yfh$>S1yJloApN1uydKxd?DMd;ZRm(J6oF$rQyVR)z9Xb4Ei@AtuhX+^%&k$!bH ze$x#5xmUYnt48-MPje97moUhKZ_F-dJ-qstC82JO}1ZUSlE!z$wmtd&--K6craATFn zk)?0Kcb_j?tK->%)Zevf+G0#@p9t3ZI%+A5{LUbkll-S1b=Sv|?`tUQ&qB=}dr$a+3pm+t`9Slf+U?h|Jh0*yS7+L(PN4m2)6sq zu1tIXytxY1cdqi^YVFw0;~Y84t%{#Y1Y^TudZ9X~vNcVhVVr3RieBtSDdzN#|MawpxC}SdIiGvCJI+U!bKchE4OF_8=0BT*qRq{rC^O*sVl66&7pe;l?H~Q$nfq93TfJbS6ip z!`O)BZm^)e4T|m-a)n`>k&&JM6;laFNv+&1O9N6;^aQBx(w?>`!tccrXmlk;vq0to_x9k1`oUq$)XvpBaT zTN^>nt@?eUtwAk)_Yk%<3g3J-WZUx(&j6i*!vK)&UjWyR>wgbj#vgf4EMvFtteyEB zv`E z>Z|iVkV*e*VrdDcV51gIZ#M$=Q9G~a+w8N?Kk5^qIc%=8H2oggwk(BCr_2S6v&d4X z{l<$EVc6DBJb|vAbI~<{gh>2^O&AB-PBdYa%9I^E?Ie5^I$$lkoiGTo`3zaZUdctG z*A*3d9gDQTdmt8bEhaIW9;c>>KxZYUP^4$aF=R{tSa$B#>QvJw_4AelmZu~oDR%1k z!hV-eA2iS{GbW`i-L2MN!%=p?%SpuHat~Ww9@G$W_`+&Uv6R5>hF3YnEBWJk?Nqi~ zE~5_Or7Sw^eh5iTu<4aA`DDdk;Rma; zTJ?pG6|o7|(Ab2XIzETm57B?Vk?q7$C!w?))sK;)nH2z}1gSu+7@AFD7#W^ix z{CLg}P%X^H`1VOyv<@%D&J?d+438W;p2Y4B9p<3{S&%B+(RSmF{R0R7#25jGBIiror;bc9Zj|xDwPoC&i>&Wtmp_r37HA zR9okY<-LOT!Cm5;wIV?+oKrmFhzZ|5SZ=Xj8R?If!AC|BRM38atcsy=uDaad6l)gB zCreX{{HfyV+F>cl@D+4Zy;k_eiTs)ci*p80>#MM3t!)R-ynK7OofDle@Lo<5ew|oM zi@RE`#P59&k~?L!k@3!YwbGSnFFuoly7s2`JTKz1fw4^-n0){RF0rv_c21%9K_U zat@Q$qCHDQoGtO#!d1TyHV?W;{a-zFm*?U=h21tIt{izk-LP29 z{Q_z?F9;~}Ud>K$WAkT-l?%G7x*@C^Ql}ViHh>YlYg^kvuEg8y!EbVX{|nP6U&qV8 zwjhWprC;}3DD>gmeVoEIPJu{j>H(fHgx={Q(1sCWJ$!Du`4)}8OMo>( zC@k<`f5Y3#4?fyRk8^VC(thY(F>Nl0IHRrx`}xI_z*uXVx1zk6F26Nf9YA=-E_+xF z$Zr#)qh~CVt;Y0xqnz_nlk?*Wfyl(cuF85I5L+!VY+*8n2EAE3DGkoG-`R7gdzo2z zs$!z!s+PdeFcuD`-rJ$)!T=Q`v+&`^8q|h^(q0 z8gE&M$ypqxz847PlZBJCy%uK~@Kocg!k`4J@^N2Ah}Efjnj#*FY~QMY7N{6bXp4L2 z*y&{Q@nK497Pp`jW46e7hcUf^)@AR9WSRs-PL#uS-aKC;$qk>$lCo7w3QFyT%s_ql zyvytGh0M3LJge%6@l$5-KJgu8O>RLxst#SOh~&;g7emEQVWVWUFtzPZZ(TY5)>i9TwAd+wD!X4##H>MJsC!)2i!Bm zV=78z9dRLE>uUn~eioA!yc{>LJeK~}Ql+V{OMIt&ZxW$(*FC9n3d&R4CGOUyNVN8c zg!+Qs@#JZG=uXR?M-?}fbD=>ti;}k#?p4&yho1?CM0O&)HqgBb_t}n0SNJT$Q6sYN}S+UoIHYIr) zal&2QJExZIXg4#s^qBVo0(5s9&-8X}A&fWmPh2s;jBt+*mrcRhs)bR^0;8%p1S~?# z_OR9x71ZsccdW53y-Pe7XpJSZs{WBC{5~eUU!o`99?afl-PMsm{cLvljWb^JGU94i z`q4M{QGtLQ$__nNurTA8q55)e;v<(hO%WD{d&sA1yo4Bj4r^T0P40b)mr-4jmbBec ziCU0!=~S=#u>mFsNUv$QZT!p*kT7=-^2ihl6()=MdQ0^ppJ5 zb6z_q(r@lPW&Q$s8E_l7=CLVhyQu)~yFp1_yP)<3i#N&#$Xad0H`YS(_is~@6NWbrWJ8mt{|0gk$k%P`FUula9_r(#Oe)Iq zWqp6rm>+2Lfjd9~w4&pzS&W0KtNXHvR=ypTRb@(el>}xayXW?6_h3w%)m@W9d{%ur zCjh>k@WP=*cT{xzgG47_UK3XM7p-A6AL|5FE=M&PhQNPAa;MC3%sA)f^%CBkDNyG- zGmX9}%KK|SAp1g*TOD8lD`9~AS=_)`58K*jwFb*92C@T+&CT8V`W_h>H0A|+G=NAB z!O|7k2Ekj05Y4%}sa(8~P3~`CYoXDb$cQd8(S&UIcE?i zJJ4R!;9N(<(V!hHOu_eEaP5sLz^^>$8g}-^#Pm_Wm%TXDZI(fdofpQ`hHL@EJhcW= z^8w;My>qP9@@!gsgC13IEuri^^u+j5f9`P$lzMz4^QrB*8=9K4#`vH+Xc70zaAv4d zkn)x-M!s9)z+Yp4!riN~kr(^!gC~vkv-Wwvv#{kgJE!c%^gz4%(9H=ad6OfR1?&?% z+W_<~7eyzU*2WJAGzYP;Mcwby7Uo-Cj`N>0ID5Q9ayPw|Nm{@wPk9Ns#7AZ1-YR-{ zns00Ap=YP}USa0I7Z4T#_Vryrx+3j6%`$s??6R0@#$GRq@uBcC(W2iG(v&nOefdgG zZ=1?;AZxYIH|<;6UNJXUYMvGgZxgq$cCh$HRK$x}DG4KxmXyQzpjOd_UMKEyRv7pj z3am}+V~}*s5}U}3#t&xddwy1FKL$)-=9rmHA#+Sp9sO~^e$8vcD-VL;&x=1wKJYRy z_Et`Yf|(1jtoY7Me4xG~$~e`^uUA&P5gdmKxziS!er6?c$Hc>eCTuzJ%o3fLTrAor zcWZIU)FE(n8bZGM3`SfrW;%3lMwT%BoJ!L4Ck46>F&o&|>G~3hMGjtJWoRWQIo<5p zOgEm^=3;j!_i#Oo>=H?62DG49Hz*jT%Dq?ZAI64bP1F5reSNze{WzqQ-Lf~STn9=& z3(Ea35#E+YUbk~w5~v&?6>n3m&`iNUbdvMEO>I{prIi@D z{&(D{8C98zS{z=Mq<)L;aj;Kz2ZJkcIX8A-`AG7e&Gp+gYT6x1eRzH~5;E`x_UJylRMv0%t z7IDueo~C9lnp)n7PI=#tmy+jq@O9U{MMv^aPx$%-N<#hmIQukrlTl>1#YQFY7F%}k zT28gi#oF=prXy_|X6x0U>4^cuy-eb`M(;1-hkM}*rj81sj!>`>dkIW~k-fcFQQj%n z-D|yKVBwhN+koX%*?JbgCwX~<+fXie={)xajJM2(UR33}>?L0{G?he5S~g5E*0fOm z;e*U$0mD=H#P*gU187fRc8I8Ji?R@Uf;{hs<{zB5^HCsN9gvw8C8&}YAal%(F!wP6 z%#axTi`|Z%>#LGE~prq|;gJ(c+Aq@0(fHs#|?u);wNnuZ2#@Q#5x0cZc_&phFEZ2JgC8wu8 zGsN}PAe>ommP z4Ut>EIt=YKg#Y?nFycabe6S;Pe#oZ?V-K&yC}B?P>baBJ|MW&5SylE`iWLjF13dM2 zUCh^`vy)kChRk0*BLZ-jI6$SoSZ_{S*0ONPB()va#<64IfnLsb3X0R{sW-D&r9C(I zB=l8$f*M3qPqk$~5U9kr~Taa(Ci%*yLRDJEcC4ShX!Y)a7s8@0? zEKFjWnhhOU_8QX5Ds(8Spy+8EnY26?$=G^g;pFcYm&t*9+X!{Ti@K8^f8!->`^Yo- z6p7+o^K2-3*9ab9tvb0W2)XzA9Y<>+m7p<{Knc*k95}idq#qjuepoMvRD%8 zpy{p!gzl2F%@GFA_wW_-H-O66(F>zmh&a*3G#apue|q{X01b0XKfc`!M%Ir*S=}gj z(QPo~U|NXzq#)_M#OivqnuleYQWgV)IbTpFBH-aF{;8h3i7?STh>)KFQeGh__lILA zH|)%PBjz~@zJQXX78s=^$JgG0kCY*e8&3X?mwBsZX)Dl;+Y$)jKB;?Hc^#BJJGh(tm9;Pzr)a2Z{LPxku|BRwi`~M_NEHC3p~H~{5Fo0n~xv5 zUj8&nKDGWScUud3x3uoEN^|Z{;g#<##0XOcKF{$}U|RtulL7;Ke8zBr$1QJumT}Hx zA0}faaB_gdTB0pmIIAt{L!>XE8K1Hq!jIBVJMXpFH-5Og z&0b0K9el9<1(ZmLIMk5|UEu9=#2@8mlSF*DYW(P-Y06>5mU{~iX~Oqy=+28tMVv8Q zDe+GfjN6Y|?!}pEdKefmaTTJ1FP*XtZ=5q-;+2rSr2W%fu&z&B;dWk0e#k1F3ZZH0 z*hIB6XlOjo&c0_oS$NBE`?03*xuf3GV-}(hLw1ywl@+$;jF!Nj617edo*6%v9<3@u z=8lnr98&esK2#ce3qamDz)h0%4yp`B&iG9S2SAfJl&DY6EqNwEv;_^6R9XGK$l@ye z%zhevsfF9t+Z5S3>Wa`%8*EX0*Rpcd+x;h5fN%wmnO_nvz&XVEs-ex4wVSC?Jv0NR z=&0tx`mHig&xwZj>&*w44IjHlng0VljkCdx8-$(M2Y1{_6rHuEPNkuI^Q~@-_@6IQmTSpqU>#YaMBIkg_NX`~ z8da&^EjCV>xr*Ez(sqAgXmh1ZZf|gY&{N&10@(F_J;Q(QqvRlCvu+Ig_Qy^GMH*At zJFM`TpO`~?lps4}0Ycf!KN(%h&gL@k&O8(17)wB9Z0jHX%ucT_+YNJ8Ei+nSiA~>P z(T2vJowBIwQGabkcRc!TF#U0ka$}gbUu(FdTJw?13#hooltq3Ac8AMme(Mlt^y&aW zgMR@P+3oo^?uFykm#_81PW!Jaqa=YG3042lEkzrDO7FO|e4Gr-xbuz_E#1eZJ)Ydt zy&{p~=oW)@*efmq1Vt{|G`=^8`-5=-mw@L#8|Zt?uue*vhVm`!59p9hn`*S z7QPU(Y#x`Ii}>kE#M{8fMbkG8M;C}z1CQShbddBT($oyyrHXuS7SHSqg)szN*Eug# zjOOi6lqEJ)NEk(qo=*0y8M}qdV#ST<2dHG}-s|m03hj4ms2UdzQUGDlUr*O`=SM~k zgD%|qGl*XO6BteS1F5Es`vi{~-Ev)d!3R`V-aZjRB&|P{r3!2EC58^P+R>Gkg}>(IV~7B!_78Eu>V^iK*)m(_StlfPQ0@77Mx1(P z+ubL1fwY3l$p_w=>Mu%3b0sxY_RYEE*&k0Vm9+kTy%T$6RO$Y?p!iEo)AWI6OAKyG zrnwK+>Xml+d64$g#jGHGO@FY;AQhsq)of^TIB+P)q5SUX%;FCRxfeNws^ciWv)XvR zx>w%ota1TVgPNR8r|#~p?y<~V*lUED;coRWHY<@?w_BOoYsVLSDFM?O#|yNW4fvrz zQS@XzlT^eTV#LNm7kG#H>8DUdqszlYvRkxWBt|rcy|-xIEwk6HPoY!DH!60U-u2!y zV%zN5XYG}qzB2QyKzbEqyhgT1s({_H6X_D!iM-Wm=akXwn!|03N-2C_V=ECDjXbCK z%;=OvZ+Jj~;l*C1+$dA&S{7|=!g=)cZL>{)v~fz*(%G7 zi}AXLbiqWUEF(w6={RPtEp2rTDjb~ZZz%hI`#S5+R2~5n{mN?F!5 z6IuO(fE&^)FPIHt(-#b|=+XR2$3(mm>LzCj31#}rzfiZ!y11Zcx!l^k?yX*8<4+wo z(BfNP?r0H)=aALwZDnoAi?h2reOV|W#45m#ZRO+_XN)3z&(hjK?T46knJ?E%Shg?+ zw>EqXz-h^{1f<5;v~N#BHLP1jh3J8L#AorkP78r(F~~!CETE8k?rfbYXkO9`mEf@rp@0iLM+j{nO#6@4Er%Nlu zik7EO{jf9wX-x?(%P~-fqDJiVJR2x?StOL9)-{~|)UM7s8>sItHHg;W1+s{Yw!bkv zJziryim6SOmacS$wS#WG2ma^&x5B8;%^J@wP+a7qc}dLD z*znG?@}0^hlhM&xkFCX2=*5YNG~1badG@>u2G+%3+^A*13?ZT6BZI!ROoulMP85q5?Wic;3 zF@nkDsFDNDLgpi@;YC~nal&hdyi7)J@C+3bH+hFWRZo=8bIMd%DN+Wx=5#7vH}!TB zecv^anCdtPllUGPYOl4zU@hosyfO)8->pTx7{lBZ=;&BEFu1uQ6S(S+d7_k1R;fVY zNC4iz%(f6lQ_uD8DLsLW0Z;FXQQIaD%WKlVvn*>2;H;a|TuBcoHZV)jLc?S9PiPpB zB(fQ7USou_~|a0s0E1M(2wuz{>$g+hjoLa?Q)%m+B zi{Ou!uhuS7Mqs4|c@wZ{xHB@1yKifQ*pX*8bp|f!vtef3-Zxlxb7UdST{TwaqGIP^LrI z*ZI6kWb4{Z#|Apu5%aKp=oK*`#{SYozA^I6PFEBI^U9{JZY`cMP%G_Yh+!^`-URlnB3e7}=^VKT`=h{7x3Nw@5P zgA)t)W)X>XZncF#!8s9$qyF9Zq+ji_;5TA%8IfBNbM@n>hVGoiuwymN1Mn>c_uB< zHUBF80d_DGvtl1YA6#`~EDZrV!T0NLU;qC!g(N6A>zBWtgMVYN#P>Pq6Wqpb_k5nx z^GHkozDhNiMZ~h4TGLRk2}Z*Sdf1>uPcu1d)Cc)c^mm-b))x%0l_q%XE;O`H2lum~ z`o|st&t1sYNIVNq?V;oL1+IBHQm4I`+v)a)3*Yn z9qff&es%b-obErlIREc1acS<4wPKFSKZbyi+%rKrC0eL~@Tz3~et4J?l+~6`QWRsIv&#l>hFZ_U*Z+o_z7U74d@BMGL>q zHSd5+>Yiq$PMHfe3zc>Kef~5FJ$m0qaSz_uh{icMJ!_SM?mQn&GnL zt|Jet?;*uR*Ak+FCo@^tj{B}=OAmbB_-V>5t>)TD!)1f=ZnYSW=*oNh81F%tBr~4? z5M$QZ8iR#$--gEf)oVaBrZoiScL~uL5v+q-LT<@1JKoOu#_(^t&LEIbMOeoffE@|J zBlD+GW#0s*T+Yi&27yvv|I-`$Z`%nxs~9cdp*?;3zi`Uaf4reQ|163!`bEWLEziuM ziqsXKegPD0_5afQ|IAbq^!H@3rTQQ2<8$j{HYsXWjK&>5&O>r7@AXHQ4Z|h=_3iwR z>V`eKEdB7&*Z!S*cWXXz#Pm$^(9e4p->y^coo=Q_7Ou#W;^GACRFMtWvL~SU7z{aS zq!i9<`V8rWn_$X5$QrA%9-*LxoV&}L^tLBgz>My^4{-yFGsIoHTrWr7Z@qH0C5{FX z{-5@)Jsj$+kE?Chc4Jjau0^P{sTffqk=Y1MjKR2tvSwVzEhB8&3Nd1lCU?2bgbW75 z(3U|W#Fz#{gN$)EZVj^U?ABE8^R(~m?)&t<+deb@{LV9T&iDI0pWkOb&+nYyIp@0^ z@%lDf;mv9l$nibFm9&VUinvRhEkKf-+^6qaO(ca3LdIGe{znyY_g(uWyVR6{iT%Ea zj;_&Um2@|IC=P##7DWCu?pC0YS3BhiWMa=oCN#hLE)kGBvI3ZM00u%e3eP*nvb% zFBjiCG~1nZp+jn>P|O_^QX=gwZf|!#jKNz{Rl@~Oh<8E^O52CtOxVHNHBRwiogs+vyVBBik^cX7mV3DEm z@unuz?ZMS$Am!5SI6bWK20<5kJKh94{ZH{)E%NE8Xc+PmMcoNz58G;c3GUiOqK;^0`D zRh41w+)8Nn5t{!#BUOFxBx9S+n_J?%zqQ9^(1y{B-Hnb~iHSp`7VYLx`jd6%tC28~l=_@|cD zsQALsCnZUjwdT>iDaiAZ?hAtu3b4})YL{vP4mt7N*L?=Jvc~bzvC3>EWI!I!;4oku ze>qlp$Ym%;5;i+l1hJ6;k?zg(=3r{Fc5z>`qmvaomEDpCZ>(6YnbAYwB=s$r{gCt2 z4d|K}^64pLr0(rUVv%|;-1Vr50vrr&n#S;rk=E-KU%o8%G%(PH~uirsG6}! zf7aXj$=T8dLPkcLN|bQ+jLlD`FE^&8Wfr1iBQz4M>J3c+dMG_3@tC_P^Ni_A2qI^j zvbb{N(kWc`baTnjRzqv|^WX0B!|S6E6&IOe7!0-#47T%GEL=(LA(0=&wL4EYQeF^GI-bG#8;1|z!gRQYyB{VO^~e9obx`nKQ&G9j$;>N)hQ~*kNfJU0zB~I zV+ol%ORd~yMMc_A$-~Sv%z+tLQ2w<&+p4PI=?}1>dtrGl^n2IxV=AnubYSK#lL3Hq zXQhcvZgskY>ykoA_x+=^P}ggZUCTQm?Pj`dfl#ddC0BS1E&6CvhaUzFqXnG>M!FeL zPz6%o`$5H_%)RdJ)p%5b1vA?z8bP{uNy2}?X3p%wL=>e|w`*?&f|F%bd)c|NV^O@& zCIf@Z(L@r8X*K5LUF*xlx=69$I`{2Yr{`{=4WLzvkaI((;h z%0&!4LIqCdNjfTF&sV(;nQm!fzu0DU2X2n6Z#5gD+@A1m8}tQl!L_U(@)cFRIYCkZ zJh?AwmqdrGO60VnEJnL+Y@m5|Ux_n$0%q z;gnupFbpcJp%fHT zp0ayWN#u*@lnjONiLDeBtvWT!gfRp;xX}|1?j>O87wJv~H?G6W+ZC-qNXXEsG zBg1Xx&AN`+p?Y@fG$Kzb2qrjRNO4K^ue5{Hk3I*xmyGvmoirq~`icYfstiwE=qc}& zCiR>7TIVy6zP4Js`{PZ`XfdJy1$C_!FR5gx6TTmRH-~X+iX4BofjKgoJ=qL87J)P2 zBtYCg0iHz2?v(pVi3kQ|if8%+&!pNqkyUa9L;zfI{~I1?$PJCx^$#4E{vS>7$_4(z z>X8HQ4dk+OgEnmI77tOm;rT&%S#$tT+W>&Cnr*`6v4I86vh74*4Xy8Guh%cLjv_*cV z1meZ>#c@wG?Y6vf1^37YJ!^WY9Jko+mp>r0nI&cN3~1#}u5#=T*3DZyHD}K`;`hcy z#~EVBaD6&(niKN){o57Vd&1fqNw!P(29<6xGGIA z3RVW%tk|n2`a#uCP!xOIwI?PrIpgxpzhL|`nP&Z1&;IPDTCNT5v)y0V-T%e}f2x9$ z_wEn875~3ZRdDY%k32xXKZ(mV@EH$9r2(FVjO6KqAki)a3z6~wHBRt=VrWnW1;x&$ z)9o6MVp@@@I3OD`C?%M;v@0Y&Shqk(ncgJC95tyc(BOWl!>x7XMX=<9iIn0fYs3*@ z)A{c>$6hU8Nt@Glie?oy_&!+HxJ=V@7B3(4kJ9M{b|$JeceA0j#eJ+#7&MqTc%1!F4R7cagO#!vMuz#Q5s}b!C z?PA-L!9CTWQR6OQT2o*jgPq=)Tq0AMxKPtF10+8PmaX?dW%BKXp!xW{=S$`*A#KYD zIzG~mzVDD3lzC@E^i{A0CV7^#_C(X?#PL<63hSN%IM#I(skKd5Ux*|YXpNTLg9?jG z6A)MAin@Tn#`VNCl&>u%_d9|MdTn0Xt*ZXoYwK>3)t$p?hE~Hj;+g@j`UI-s}K)_ex;Cr_Ak_b E0f^link to ROS documentation of the message type) + +### Vision Node ([vision_node.py](/../paf/code/perception/src/vision_node.py)) + +Evaluates sensor data to detect and classify objects around the ego vehicle. +Other road users and objects blocking the vehicle's path are recognized (most of the time). +Recognized traffic lights get cut out from the image and made available for further processing. + +Subscriptions: +- ```/paf/hero/Center/dist_array``` \(/lidar_distance\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/carla/hero/Center/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/carla/hero/Back/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/carla/hero/Left/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/carla/hero/Right/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) + +Publishes: + +- ```/paf/hero/Center/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Back/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Left/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Right/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Center/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/Back/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/Left/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/Right/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/Center/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Back/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Left/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```/paf/hero/Right/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) + +### Traffic Light Detection ([traffic_light_node.py](/../paf/code/perception/src/traffic_light_node.py)) + +Recognizes traffic lights and what they are showing at the moment. +In particular traffic lights that are relevant for the correct traffic behavior of the ego vehicle, +are recognized early and reliably. + +Subscriptions: + +- ```/paf/hero/Center/segmented_traffic_light``` \(/VisionNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) + +Publishes: + +- ```/paf/hero/Center/traffic_light_state``` \(/behavior_agent\) ([perception/TrafficLightState](/../paf/code/perception/msg/TrafficLightState.msg)) +- ```/paf/hero/Center/traffic_light_y_distance``` \(/behavior_agent\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html)) + + +### Position Heading Node ([position_heading_publisher_node.py](/../paf/code/perception/src/position_heading_publisher_node.py)) + +Calculates the current_pos (Location of the car) and current_heading (Orientation of the car around the Z- axis). + +Subscriptions: + +- ```/carla/hero/OpenDRIVE``` \(/carla_ros_bridge\) ([sensor_msgs/String](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) +- ```/carla/hero/IMU``` \(/carla_ros_bridge\) ([sensor_msgs/Imu](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/Imu.html)) +- ```/carla/hero/GPS``` \(/carla_ros_bridge\) ([sensor_msgs/NavSatFix](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/NavSatFix.html)) +- ```/paf/hero/kalman_pos``` \(/kalman_filter_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/kalman_heading``` \(/kalman_filter_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +Publishes: + +- ```/paf/hero/unfiltered_heading``` \(no subscriber at the moment\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/unfiltered_pos``` \(/kalman_filter_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/current_pos``` \(/pure_pursuit_controller, /stanley_controller, /MotionPlanning, /ACC, /MainFramePublisher, /GlobalPlanDistance, /position_heading_publisher_node, /curr_behavior \) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/current_heading``` \(/stanley_controller, /behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + + +### Global distances ([global_plan_distance_publisher.py](/../paf/code/perception/src/global_plan_distance_publisher.py)) + +Subscriptions: + +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/carla/hero/global_plan``` \(/ \) ([ros_carla_msgs/msg/CarlaRoute](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaRoute.msg)) + +Publishes: + +- ```/paf/hero/waypoint_distance``` \(/MotionPlanning, /behavior_agent\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) +- ```/paf/hero/lane_change_distance``` \(/MotionPlanning, /behavior_agent\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) + +### Kalman filtering ([kalman_filter.py](/../paf/code/perception/src/kalman_filter.py)) + +Subscriptions: + +- ```/carla/hero/OpenDRIVE``` \(/carla_ros_bridge\) ([sensor_msgs/String](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) +- ```/carla/hero/IMU``` \(/carla_ros_bridge\) ([sensor_msgs/Imu](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/Imu.html)) +- ```/carla/hero/GPS``` \(/carla_ros_bridge\) ([sensor_msgs/NavSatFix](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/NavSatFix.html)) +- ```/paf/hero/unfiltered_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) + +Publishes: + +- ```/paf/hero/kalman_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/kalman_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +### Localization + +Provides corrected accurate position, direction and speed of the ego vehicle. For this to be achived the [Position Heading Node](#position-heading-node-position_heading_publisher_nodepy), [Kalman filtering](#kalman-filtering) and the [Coordinate Transformation](/../paf/code/perception/src/coordinate_transformation.py) help class are used. + +## Planning + +The planning uses the data from the [Perception](#Perception) to find a path on which the ego vehicle can safely reach its destination. It also detects situations and reacts accordingly in traffic. It publishes signals such as a trajecotry or a target speed to acting. + +Further information regarding the planning can be found [here](../planning/README.md). +Research for the planning can be found [here](../research/planning/README.md). + +### PrePlaner ([global_planner.py](/../paf/code/planning/src/global_planner/global_planner.py)) + +Uses information from the map and the path specified by CARLA to find a first concrete path to the next intermediate point. More about it can be found [here](../planning/Global_Planner.md). + +Subscriptions: + +- ```/carla/hero/OpenDRIVE``` \(/carla_ros_bridge\) ([sensor_msgs/String](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html)) +- ```/carla/hero/global_plan``` \(/ \) ([ros_carla_msgs/msg/CarlaRoute](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaRoute.msg)) +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) + +Publishes: + +- ```/paf/hero/trajectory_global``` \(/ACC, /MotionPlanning\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) +- ```/paf/hero/speed_limits_OpenDrive``` \(/ACC\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) + +### Behavior Agent ([behavior_agent](/../paf/code/planning/src/behavior_agent/)) + +Decides which speed is the right one to pass through a certain situation and +also checks if an overtake is necessary. +Everything is based on the data from the Perception [Perception](#Perception). More about the behavior tree can be found [here](../planning/Behavior_tree.md) + +Subscriptions: + +[topics2blackboard.py](/../paf/code/planning/src/behavior_agent/behaviours/topics2blackboard.py) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) +- ```/paf/hero/slowed_by_car_in_front``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) +- ```/paf/hero/stop_sign``` \(/\) ([mock/Stop_sign](/../paf/code/mock/msg/Stop_sign.msg)) +- ```/paf/hero/Center/traffic_light_state``` \(/TrafficLightNode\) ([perception/TrafficLightState](/../paf/code/perception/msg/TrafficLightState.msg)) +- ```/paf/hero/Center/traffic_light_y_distance``` \(/TrafficLightNode\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html)) +- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) +- ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/overtake_success``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/oncoming``` \(/CollisionCheck\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +Publishes: + +[maneuvers.py](/../paf/code/planning/src/behavior_agent/behaviours/maneuvers.py) +- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) +- ```/paf/hero/unstuck_distance``` \(/ACC, /MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/unstuck_flag``` \(/ACC\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) + +[intersection.py](/../paf/code/planning/src/behavior_agent/behaviours/intersection.py) +- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) + +[lane_change.py](/../paf/code/planning/src/behavior_agent/behaviours/lane_change.py) +- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) + +[meta.py](/../paf/code/planning/src/behavior_agent/behaviours/meta.py) +- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +[overtake.py](/../paf/code/planning/src/behavior_agent/behaviours/overtake.py) +- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) + + +### [Local Planning](../planning/Local_Planning.md) + +It consists of three components: + +- [Collision Check](../planning//Collision_Check.md): Checks for collisions based on objects recieved from [Perception](#perception) +- [ACC](../planning/ACC.md): Generates a new speed based on a possible collision recieved from Collision Check and speedlimits recieved from [Global Planner](#global-planning) +- [Motion Planning](../planning/motion_planning.md): Decides the target speed and modifies trajectory if signal recieved from [Decision Making](#decision-making) + +Subscriptions: + +[ACC.py](/../paf/code/planning/src/local_planner/ACC.py) +- ```/paf/hero/unstuck_flag``` \(/behavior_agent\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) +- ```/paf/hero/speed_limits_OpenDrive``` \(/PrePlanner\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) + +[collision_check.py](/../paf/code/planning/src/local_planner/collision_check.py) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) +- ```/paf/hero/Center/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) + +[motion_planning.py](/../paf/code/planning/src/local_planner/motion_planning.py) +- ```/paf/hero/spawn_car``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/curr_behavior``` \(/behavior_agent\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) +- ```/paf/hero/unchecked_emergency``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/paf/hero/acc_velocity``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) +- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) +- ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/Center/traffic_light_y_distance``` \(/TrafficLightNode\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html)) +- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_wp``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)) + +Publishes: +[ACC.py](/../paf/code/planning/src/behavior_agent/local_planner/ACC.py) +- ```/paf/hero/acc_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_wp``` ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/speed_limit``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +[collision_check.py](/../paf/code/planning/src/local_planner/collision_check.py) +- ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/paf/hero/collision``` \(/ACC, /MotionPlanning\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) +- ```/paf/hero/oncoming``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +[motion_planning.py](/../paf/code/planning/src/local_planner/motion_planning.py) +- ```/paf/hero/trajectory``` \(/pure_pursuit_controller\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) +- ```/paf/hero/target_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/overtake_success``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + + + + + +## Acting + +The job of this component is to take the planned trajectory and target-velocities from the [Planning](#Planning) component and convert them into steering and throttle/brake controls for the CARLA-vehicle. + +All information regarding research done about acting can be found [here](../research/acting/README.md). + +Indepth information about the currently implemented acting Components can be found [here](../acting/README.md)! + +### [MainFramePublisher](/../paf/code/acting/src/acting/MainFramePublisher.py) + +Subscription: +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +### [pure_pursuit_controller](/../paf/code/acting/src/acting/pure_pursuit_controller.py) + +Calculates steering angles that keep the ego vehicle on the path given by +the [Local path planning](#Local-path-planning). + +Subscription: +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +Publishes: +- ```/paf/hero/pure_pursuit_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/pure_p_debug``` \(/\) ([acting/msg/Debug](/../paf/code/acting/msg/Debug.msg)) + +### [stanley_controller](/../paf/code/acting/src/acting/stanley_controller.py) + +Calculates steering angles that keep the ego vehicle on the path given by +the [Local path planning](#Local-path-planning). + +Subscription: +- ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) +- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +Publishes: +- ```/paf/hero/stanley_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/stanley_debug``` \(/\) ([acting/msg/StanleyDebug](/../paf/code/acting/msg/StanleyDebug.msg)) + +### [vehicle_controller](/../paf/code/acting/src/acting/vehicle_controller.py) + +Subscription: +- ```/paf/hero/curr_behavior``` \(/behavior_agent\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) +- ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) +- ```/paf/hero/throttle``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/brake``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/reverse``` \(/velocity_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/paf/hero/pure_pursuit_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/stanley_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +Publishes: +- ```/carla/hero/vehicle_control_cmd``` \(/\) ([ros_carla_msgs/msg/CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaEgoVehicleControl.msg)) +- ```/carla/hero/status``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) +- ```/paf/hero/controller``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) + +### [velocity_controller](/../paf/code/acting/src/acting/velocity_controller.py) + +Calculates acceleration values to drive the target-velocity given by the [Local path planning](#Local-path-planning). + +For further indepth information about the currently implemented Vehicle Controller click [here](../acting/vehicle_controller.md) + +Subscription: +- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) + +Publishes: +- ```/paf/hero/throttle``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/brake``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/reverse``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) diff --git a/doc/general/architecture.md b/doc/general/architecture_planned.md similarity index 87% rename from doc/general/architecture.md rename to doc/general/architecture_planned.md index f8eaf839..911392f8 100644 --- a/doc/general/architecture.md +++ b/doc/general/architecture_planned.md @@ -3,24 +3,25 @@ **Summary:** This page gives an overview over the planned general architecture of the vehicle agent. The document contains an overview over all [nodes](#overview) and [topics](#topics). -- [Planned architecture of vehicle agent](#planned-architecture-of-vehicle-agent) - - [Overview](#overview) - - [Perception](#perception) - - [Obstacle Detection and Classification](#obstacle-detection-and-classification) - - [Traffic Light Detection](#traffic-light-detection) - - [Localization](#localization) - - [Planning](#planning) - - [Global Planning](#global-planning) - - [Decision Making](#decision-making) - - [Local Planning](#local-planning) - - [Collision Check](#collision-check) - - [ACC](#acc) - - [Motion Planning](#motion-planning) - - [Acting](#acting) - - [Path following with Steering Controllers](#path-following-with-steering-controllers) - - [Velocity control](#velocity-control) - - [Vehicle controller](#vehicle-controller) - - [Visualization](#visualization) +- [Overview](#overview) +- [Perception](#perception) + - [Vision Node](#vision-node) + - [Traffic Light Detection](#traffic-light-detection) + - [Position Heading Node](#position-heading-node) + - [Distance to Objects](#distance-to-objects) + - [Localization](#localization) +- [Planning](#planning) + - [Global Planning](#global-planning) + - [Decision Making](#decision-making) + - [Local Planning](#local-planning) + - [Collision Check](#collision-check) + - [ACC](#acc) + - [Motion Planning](#motion-planning) +- [Acting](#acting) + - [Path following with Steering Controllers](#path-following-with-steering-controllers) + - [Velocity control](#velocity-control) + - [Vehicle controller](#vehicle-controller) +- [Visualization](#visualization) ## Overview @@ -28,12 +29,13 @@ The vehicle agent is split into three major components: [Perception](#Perception and [Acting](#Acting). A separate node is responsible for the [visualization](#Visualization). The topics published by the Carla bridge can be -found [here](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/). -The msgs necessary to control the vehicle via the Carla bridge can be -found [here](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) +found [here](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/).\ +The messages necessary to control the vehicle via the Carla bridge can be +found [here](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg).\ -![Architecture overview](../assets/overview.jpg) The miro-board can be found [here](https://miro.com/welcomeonboard/a1F0d1dya2FneWNtbVk4cTBDU1NiN3RiZUIxdGhHNzJBdk5aS3N4VmdBM0R5c2Z1VXZIUUN4SkkwNHpuWlk2ZXwzNDU4NzY0NTMwNjYwNzAyODIzfDI=?share_link_id=785020837509). +![Architecture overview](../assets/overview.jpg "Connections between nodes visualized") +![Department node overview](../assets/research_assets/node_path_ros.png "In- and outgoing topics for every node of the departments") ## Perception @@ -43,7 +45,7 @@ environment representation that can be used by the [Planning](#Planning) for fur Further information regarding the perception can be found [here](../perception/README.md). Research for the perception can be found [here](../research/perception/README.md). -### Obstacle Detection and Classification +### Vision Node Evaluates sensor data to detect and classify objects around the ego vehicle. Other road users and objects blocking the vehicle's path are recognized. @@ -51,18 +53,28 @@ The node classifies objects into static and dynamic objects. In the case of dynamic objects, an attempt is made to recognize the direction and speed of movement. Subscriptions: - -- ```radar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html)) - ```lidar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html)) - ```rgb_camera``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) - ````gnss```` ([sensor_msgs/NavSatFix](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/)) - ```map``` ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) +- ```radar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html)) SOON TO COME Publishes: - ```obstacles``` (Custom msg: obstacle ([vision_msgs/Detection3DArray Message](http://docs.ros.org/en/api/vision_msgs/html/msg/Detection3DArray.html)) and its classification ([std_msgs/String Message](http://docs.ros.org/en/noetic/api/std_msgs/html/msg/String.html))) +- ```segmented_image``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) + - /paf/hero/Center/segmented_image + - /paf/hero/Back/segmented_image + - /paf/hero/Left/segmented_image + - /paf/hero/Right/segmented_image +- ```segmented_traffic_light``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```object_distance``` ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) + - /paf/hero/Center/object_distance + - /paf/hero/Back/object_distance + - /paf/hero/Left/object_distance + - /paf/hero/Right/object_distance ### Traffic Light Detection @@ -84,6 +96,11 @@ Publishes: position ([geometry_msgs/Pose Message](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/Pose.html)), distance_to_stop_line ([std_msgs/Float64 Message](http://docs.ros.org/en/api/std_msgs/html/msg/Float64.html))) + +### Position Heading Node + +### Distance to Objects + ### Localization Provides corrected accurate position, direction and speed of the ego vehicle From 4245b707cb01c8546127b82e809f0540cdaf3df7 Mon Sep 17 00:00:00 2001 From: asamluka Date: Mon, 25 Nov 2024 07:56:46 +0100 Subject: [PATCH 50/85] Correct linting mistakes --- doc/general/architecture_current.md | 129 ++++++++++++++++------------ 1 file changed, 76 insertions(+), 53 deletions(-) diff --git a/doc/general/architecture_current.md b/doc/general/architecture_current.md index 3be7c975..f771d5a5 100644 --- a/doc/general/architecture_current.md +++ b/doc/general/architecture_current.md @@ -47,7 +47,8 @@ Further information regarding the perception can be found [here](../perception/R Research for the perception can be found [here](../research/perception/README.md). In the following, all subscribed and published topics and their corresponding nodes are listed with the format: -- ```name of topic``` \(origin/destination node\) (typo of message) (link to ROS documentation of the message type) + +- ```name of topic``` \(origin/destination node\) (typo of message) (link to ROS documentation of the message type) ### Vision Node ([vision_node.py](/../paf/code/perception/src/vision_node.py)) @@ -56,6 +57,7 @@ Other road users and objects blocking the vehicle's path are recognized (most of Recognized traffic lights get cut out from the image and made available for further processing. Subscriptions: + - ```/paf/hero/Center/dist_array``` \(/lidar_distance\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) - ```/carla/hero/Center/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) - ```/carla/hero/Back/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) @@ -92,7 +94,6 @@ Publishes: - ```/paf/hero/Center/traffic_light_state``` \(/behavior_agent\) ([perception/TrafficLightState](/../paf/code/perception/msg/TrafficLightState.msg)) - ```/paf/hero/Center/traffic_light_y_distance``` \(/behavior_agent\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html)) - ### Position Heading Node ([position_heading_publisher_node.py](/../paf/code/perception/src/position_heading_publisher_node.py)) Calculates the current_pos (Location of the car) and current_heading (Orientation of the car around the Z- axis). @@ -107,11 +108,10 @@ Subscriptions: Publishes: -- ```/paf/hero/unfiltered_heading``` \(no subscriber at the moment\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/unfiltered_heading``` \(no subscriber at the moment\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/unfiltered_pos``` \(/kalman_filter_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) - ```/paf/hero/current_pos``` \(/pure_pursuit_controller, /stanley_controller, /MotionPlanning, /ACC, /MainFramePublisher, /GlobalPlanDistance, /position_heading_publisher_node, /curr_behavior \) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/current_heading``` \(/stanley_controller, /behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - +- ```/paf/hero/current_heading``` \(/stanley_controller, /behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) ### Global distances ([global_plan_distance_publisher.py](/../paf/code/perception/src/global_plan_distance_publisher.py)) @@ -122,8 +122,8 @@ Subscriptions: Publishes: -- ```/paf/hero/waypoint_distance``` \(/MotionPlanning, /behavior_agent\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) -- ```/paf/hero/lane_change_distance``` \(/MotionPlanning, /behavior_agent\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) +- ```/paf/hero/waypoint_distance``` \(/MotionPlanning, /behavior_agent\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) +- ```/paf/hero/lane_change_distance``` \(/MotionPlanning, /behavior_agent\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) ### Kalman filtering ([kalman_filter.py](/../paf/code/perception/src/kalman_filter.py)) @@ -138,11 +138,17 @@ Subscriptions: Publishes: - ```/paf/hero/kalman_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/kalman_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/kalman_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) ### Localization -Provides corrected accurate position, direction and speed of the ego vehicle. For this to be achived the [Position Heading Node](#position-heading-node-position_heading_publisher_nodepy), [Kalman filtering](#kalman-filtering) and the [Coordinate Transformation](/../paf/code/perception/src/coordinate_transformation.py) help class are used. +Provides corrected accurate position, direction and speed of the ego vehicle. For this to be achived the + +- [Position Heading Node](#position-heading-node-position_heading_publisher_nodepy) +- [Kalman filtering](#kalman-filtering) and +- [Coordinate Transformation](/../paf/code/perception/src/coordinate_transformation.py) + +classes are used. ## Planning @@ -175,41 +181,46 @@ Everything is based on the data from the Perception [Perception](#Perception). M Subscriptions: [topics2blackboard.py](/../paf/code/planning/src/behavior_agent/behaviours/topics2blackboard.py) + - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) - ```/paf/hero/slowed_by_car_in_front``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) -- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) -- ```/paf/hero/stop_sign``` \(/\) ([mock/Stop_sign](/../paf/code/mock/msg/Stop_sign.msg)) +- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) +- ```/paf/hero/stop_sign``` \(/\) ([mock/Stop_sign](/../paf/code/mock/msg/Stop_sign.msg)) - ```/paf/hero/Center/traffic_light_state``` \(/TrafficLightNode\) ([perception/TrafficLightState](/../paf/code/perception/msg/TrafficLightState.msg)) - ```/paf/hero/Center/traffic_light_y_distance``` \(/TrafficLightNode\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html)) -- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) +- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) - ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) - ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/overtake_success``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/oncoming``` \(/CollisionCheck\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/overtake_success``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/oncoming``` \(/CollisionCheck\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) Publishes: [maneuvers.py](/../paf/code/planning/src/behavior_agent/behaviours/maneuvers.py) + - ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) -- ```/paf/hero/unstuck_distance``` \(/ACC, /MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/unstuck_distance``` \(/ACC, /MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/unstuck_flag``` \(/ACC\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) [intersection.py](/../paf/code/planning/src/behavior_agent/behaviours/intersection.py) + - ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) [lane_change.py](/../paf/code/planning/src/behavior_agent/behaviours/lane_change.py) + - ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) [meta.py](/../paf/code/planning/src/behavior_agent/behaviours/meta.py) -- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) [overtake.py](/../paf/code/planning/src/behavior_agent/behaviours/overtake.py) -- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) +- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) ### [Local Planning](../planning/Local_Planning.md) @@ -222,8 +233,9 @@ It consists of three components: Subscriptions: [ACC.py](/../paf/code/planning/src/local_planner/ACC.py) + - ```/paf/hero/unstuck_flag``` \(/behavior_agent\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) -- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) - ```/paf/hero/speed_limits_OpenDrive``` \(/PrePlanner\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) - ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) @@ -231,45 +243,47 @@ Subscriptions: - ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) [collision_check.py](/../paf/code/planning/src/local_planner/collision_check.py) + - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) - ```/paf/hero/Center/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) [motion_planning.py](/../paf/code/planning/src/local_planner/motion_planning.py) -- ```/paf/hero/spawn_car``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +- ```/paf/hero/spawn_car``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) -- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) - ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) - ```/paf/hero/curr_behavior``` \(/behavior_agent\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) - ```/paf/hero/unchecked_emergency``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) -- ```/paf/hero/acc_velocity``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) -- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) +- ```/paf/hero/acc_velocity``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html)) +- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg)) - ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) - ```/paf/hero/Center/traffic_light_y_distance``` \(/TrafficLightNode\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html)) -- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/current_wp``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)) Publishes: + [ACC.py](/../paf/code/planning/src/behavior_agent/local_planner/ACC.py) -- ```/paf/hero/acc_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +- ```/paf/hero/acc_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/current_wp``` ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/speed_limit``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/speed_limit``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) [collision_check.py](/../paf/code/planning/src/local_planner/collision_check.py) + - ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) - ```/paf/hero/collision``` \(/ACC, /MotionPlanning\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) -- ```/paf/hero/oncoming``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/oncoming``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) [motion_planning.py](/../paf/code/planning/src/local_planner/motion_planning.py) -- ```/paf/hero/trajectory``` \(/pure_pursuit_controller\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) -- ```/paf/hero/target_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/overtake_success``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - - - +- ```/paf/hero/trajectory``` \(/pure_pursuit_controller\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) +- ```/paf/hero/target_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/overtake_success``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) ## Acting @@ -282,8 +296,9 @@ Indepth information about the currently implemented acting Components can be fou ### [MainFramePublisher](/../paf/code/acting/src/acting/MainFramePublisher.py) Subscription: + - ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) ### [pure_pursuit_controller](/../paf/code/acting/src/acting/pure_pursuit_controller.py) @@ -291,13 +306,15 @@ Calculates steering angles that keep the ego vehicle on the path given by the [Local path planning](#Local-path-planning). Subscription: + - ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) Publishes: -- ```/paf/hero/pure_pursuit_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/pure_p_debug``` \(/\) ([acting/msg/Debug](/../paf/code/acting/msg/Debug.msg)) + +- ```/paf/hero/pure_pursuit_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/pure_p_debug``` \(/\) ([acting/msg/Debug](/../paf/code/acting/msg/Debug.msg)) ### [stanley_controller](/../paf/code/acting/src/acting/stanley_controller.py) @@ -305,31 +322,35 @@ Calculates steering angles that keep the ego vehicle on the path given by the [Local path planning](#Local-path-planning). Subscription: + - ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html)) - ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) Publishes: -- ```/paf/hero/stanley_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/stanley_debug``` \(/\) ([acting/msg/StanleyDebug](/../paf/code/acting/msg/StanleyDebug.msg)) + +- ```/paf/hero/stanley_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/stanley_debug``` \(/\) ([acting/msg/StanleyDebug](/../paf/code/acting/msg/StanleyDebug.msg)) ### [vehicle_controller](/../paf/code/acting/src/acting/vehicle_controller.py) Subscription: + - ```/paf/hero/curr_behavior``` \(/behavior_agent\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html)) - ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html)) -- ```/paf/hero/throttle``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/brake``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/throttle``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/brake``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/reverse``` \(/velocity_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) -- ```/paf/hero/pure_pursuit_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/stanley_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/pure_pursuit_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/stanley_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) Publishes: + - ```/carla/hero/vehicle_control_cmd``` \(/\) ([ros_carla_msgs/msg/CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaEgoVehicleControl.msg)) - ```/carla/hero/status``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) -- ```/paf/hero/controller``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/controller``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) ### [velocity_controller](/../paf/code/acting/src/acting/velocity_controller.py) @@ -339,10 +360,12 @@ Calculates acceleration values to drive the target-velocity given by the [Local For further indepth information about the currently implemented Vehicle Controller click [here](../acting/vehicle_controller.md) Subscription: -- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg)) Publishes: -- ```/paf/hero/throttle``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) -- ```/paf/hero/brake``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) + +- ```/paf/hero/throttle``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) +- ```/paf/hero/brake``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/reverse``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html)) From 17d9f9efabfc1ab6eb123be0bec566e1f2d90906 Mon Sep 17 00:00:00 2001 From: asamluka Date: Mon, 25 Nov 2024 08:01:07 +0100 Subject: [PATCH 51/85] More linting fixes --- doc/general/architecture_planned.md | 28 ++++++++++++++++------------ 1 file changed, 16 insertions(+), 12 deletions(-) diff --git a/doc/general/architecture_planned.md b/doc/general/architecture_planned.md index 911392f8..1d6fd803 100644 --- a/doc/general/architecture_planned.md +++ b/doc/general/architecture_planned.md @@ -53,6 +53,7 @@ The node classifies objects into static and dynamic objects. In the case of dynamic objects, an attempt is made to recognize the direction and speed of movement. Subscriptions: + - ```lidar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html)) - ```rgb_camera``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) - ````gnss```` ([sensor_msgs/NavSatFix](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/)) @@ -64,17 +65,17 @@ Publishes: - ```obstacles``` (Custom msg: obstacle ([vision_msgs/Detection3DArray Message](http://docs.ros.org/en/api/vision_msgs/html/msg/Detection3DArray.html)) and its classification ([std_msgs/String Message](http://docs.ros.org/en/noetic/api/std_msgs/html/msg/String.html))) -- ```segmented_image``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) - - /paf/hero/Center/segmented_image - - /paf/hero/Back/segmented_image - - /paf/hero/Left/segmented_image - - /paf/hero/Right/segmented_image -- ```segmented_traffic_light``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) -- ```object_distance``` ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) - - /paf/hero/Center/object_distance - - /paf/hero/Back/object_distance - - /paf/hero/Left/object_distance - - /paf/hero/Right/object_distance +- ```segmented_image``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) + - /paf/hero/Center/segmented_image + - /paf/hero/Back/segmented_image + - /paf/hero/Left/segmented_image + - /paf/hero/Right/segmented_image +- ```segmented_traffic_light``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html)) +- ```object_distance``` ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html)) + - /paf/hero/Center/object_distance + - /paf/hero/Back/object_distance + - /paf/hero/Left/object_distance + - /paf/hero/Right/object_distance ### Traffic Light Detection @@ -96,11 +97,14 @@ Publishes: position ([geometry_msgs/Pose Message](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/Pose.html)), distance_to_stop_line ([std_msgs/Float64 Message](http://docs.ros.org/en/api/std_msgs/html/msg/Float64.html))) - ### Position Heading Node +There are currently no planned improvements of the Position Heading Node. + ### Distance to Objects +There are currently no planned improvements for Distance to Objects. + ### Localization Provides corrected accurate position, direction and speed of the ego vehicle From 0540464f288556164c1d64244dcee3a76012f8b1 Mon Sep 17 00:00:00 2001 From: michalal7 <53532256+michalal7@users.noreply.github.com> Date: Mon, 25 Nov 2024 10:21:57 +0100 Subject: [PATCH 52/85] Update radar_node.py New functions have been annotated with comments. --- code/perception/src/radar_node.py | 50 +++++++++++++++++++++++++++++++ 1 file changed, 50 insertions(+) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index ca3cded6..fdb54caf 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -54,10 +54,24 @@ def listener(self): def pointcloud2_to_array(pointcloud_msg): + """ + Konvertiert eine ROS-PointCloud2-Nachricht in ein NumPy-Array und berechnet die euklidischen Entfernungen + jedes Punkts vom Ursprung. + + Parameter: + - pointcloud_msg: sensor_msgs/PointCloud2 + Die ROS-PointCloud2-Nachricht, die die 3D-Punkte enthält. + + Rückgabewert: + - np.ndarray + Ein 2D-Array, in dem jede Zeile einem Punkt in der Punktwolke entspricht: + [x, y, z, distance], wobei "distance" die Entfernung vom Ursprung ist. + """ cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) distances = np.sqrt( cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 ) + return np.column_stack( (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) ) @@ -66,20 +80,56 @@ def pointcloud2_to_array(pointcloud_msg): def cluster_radar_data_from_pointcloud( pointcloud_msg, max_distance, eps=1.0, min_samples=2 ): + """ + Filtert und gruppiert Punkte aus einer ROS-PointCloud2-Nachricht basierend auf DBSCAN-Clustering. + + Parameter: + - pointcloud_msg: sensor_msgs/PointCloud2 + Die ROS-PointCloud2-Nachricht mit den 3D-Punkten. + - max_distance: float + Maximale Entfernung, um Punkte zu berücksichtigen. Punkte außerhalb dieser Entfernung werden verworfen. + - eps: float, optional (default: 1.0) + Der maximale Abstand zwischen zwei Punkten, damit diese im selben Cluster sein können. + - min_samples: int, optional (default: 2) + Die minimale Anzahl von Punkten, die erforderlich sind, um einen Cluster zu bilden. + + Rückgabewert: + - dict + Ein Dictionary, in dem die Schlüssel die Cluster-Labels (int) sind und die Werte die Anzahl der Punkte + in jedem Cluster. Wenn keine Punkte vorhanden sind, wird ein leeres Dictionary zurückgegeben. + + Funktionalität: + - Die Funktion konvertiert die Punktwolke in ein Array mit Punktkoordinaten und berechneten Entfernungen. + - Punkte außerhalb eines spezifizierten Entfernungsbereichs und räumlichen Filtergrenzen werden verworfen. + - Anschließend wird DBSCAN-Clustering auf die 2D-Koordinaten (x, y) der Punkte angewendet. + - Die Cluster-Labels und ihre Häufigkeiten werden als Dictionary zurückgegeben. + """ data = pointcloud2_to_array(pointcloud_msg) + + # Filtere Punkte basierend auf der maximalen Entfernung filtered_data = data[data[:, 3] < max_distance] + + # Zusätzlicher Filter auf Y- und Z-Werte filtered_data = filtered_data[ (filtered_data[:, 1] >= -1) & (filtered_data[:, 1] <= 1) & (filtered_data[:, 2] <= 1.3) & (filtered_data[:, 2] >= -0.7) ] + + # Rückgabe eines leeren Dictionaries, wenn keine Punkte übrig sind if len(filtered_data) == 0: return {} + + # Extrahiere die 2D-Koordinaten (x, y) für das Clustering coordinates = filtered_data[:, :2] clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) labels = clustering.labels_ + + # Zählen der Punktanzahl in jedem Cluster clustered_points = {label: list(labels).count(label) for label in set(labels)} + + # Konvertiere die Labels in Integer und gebe das Dictionary zurück clustered_points = {int(label): count for label, count in clustered_points.items()} return clustered_points From 30a569ce1ec4ed97eb4c8a516eba6335ffb2d0fa Mon Sep 17 00:00:00 2001 From: michalal7 <53532256+michalal7@users.noreply.github.com> Date: Mon, 25 Nov 2024 10:33:15 +0100 Subject: [PATCH 53/85] Update radar_node.py Whitespace elimination. --- code/perception/src/radar_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index fdb54caf..2ace7d92 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -128,7 +128,7 @@ def cluster_radar_data_from_pointcloud( # Zählen der Punktanzahl in jedem Cluster clustered_points = {label: list(labels).count(label) for label in set(labels)} - + # Konvertiere die Labels in Integer und gebe das Dictionary zurück clustered_points = {int(label): count for label, count in clustered_points.items()} return clustered_points From b99d8f9872d101a5ffd9bccbbd7d2763211d6e0a Mon Sep 17 00:00:00 2001 From: michalal7 <53532256+michalal7@users.noreply.github.com> Date: Mon, 25 Nov 2024 10:38:03 +0100 Subject: [PATCH 54/85] Update radar_node.py maximal line length of 88 characters. --- code/perception/src/radar_node.py | 45 ++++++++++++++++++++----------- 1 file changed, 30 insertions(+), 15 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 2ace7d92..eb00bd5c 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -18,7 +18,7 @@ def callback(self, data): Extracts information from radar data and publishes the clustered radar data - points as a String message + points as a String message. Args: data: Point2Cloud message containing radar data @@ -38,7 +38,8 @@ def listener(self): # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( rospy.get_param( - "~image_distance_topic", "/paf/hero/Radar/dist_array_unsegmented" + "~image_distance_topic", + "/paf/hero/Radar/dist_array_unsegmented", ), String, queue_size=10, @@ -55,8 +56,8 @@ def listener(self): def pointcloud2_to_array(pointcloud_msg): """ - Konvertiert eine ROS-PointCloud2-Nachricht in ein NumPy-Array und berechnet die euklidischen Entfernungen - jedes Punkts vom Ursprung. + Konvertiert eine ROS-PointCloud2-Nachricht in ein NumPy-Array und berechnet + die euklidischen Entfernungen jedes Punkts vom Ursprung. Parameter: - pointcloud_msg: sensor_msgs/PointCloud2 @@ -81,27 +82,35 @@ def cluster_radar_data_from_pointcloud( pointcloud_msg, max_distance, eps=1.0, min_samples=2 ): """ - Filtert und gruppiert Punkte aus einer ROS-PointCloud2-Nachricht basierend auf DBSCAN-Clustering. + Filtert und gruppiert Punkte aus einer ROS-PointCloud2-Nachricht + basierend auf DBSCAN-Clustering. Parameter: - pointcloud_msg: sensor_msgs/PointCloud2 Die ROS-PointCloud2-Nachricht mit den 3D-Punkten. - max_distance: float - Maximale Entfernung, um Punkte zu berücksichtigen. Punkte außerhalb dieser Entfernung werden verworfen. + Maximale Entfernung, um Punkte zu berücksichtigen. Punkte außerhalb dieser + Entfernung werden verworfen. - eps: float, optional (default: 1.0) - Der maximale Abstand zwischen zwei Punkten, damit diese im selben Cluster sein können. + Der maximale Abstand zwischen zwei Punkten, damit diese im selben Cluster + sein können. - min_samples: int, optional (default: 2) - Die minimale Anzahl von Punkten, die erforderlich sind, um einen Cluster zu bilden. + Die minimale Anzahl von Punkten, die erforderlich sind, um einen Cluster + zu bilden. Rückgabewert: - dict - Ein Dictionary, in dem die Schlüssel die Cluster-Labels (int) sind und die Werte die Anzahl der Punkte - in jedem Cluster. Wenn keine Punkte vorhanden sind, wird ein leeres Dictionary zurückgegeben. + Ein Dictionary, in dem die Schlüssel die Cluster-Labels (int) sind und die + Werte die Anzahl der Punkte in jedem Cluster. Wenn keine Punkte vorhanden + sind, wird ein leeres Dictionary zurückgegeben. Funktionalität: - - Die Funktion konvertiert die Punktwolke in ein Array mit Punktkoordinaten und berechneten Entfernungen. - - Punkte außerhalb eines spezifizierten Entfernungsbereichs und räumlichen Filtergrenzen werden verworfen. - - Anschließend wird DBSCAN-Clustering auf die 2D-Koordinaten (x, y) der Punkte angewendet. + - Die Funktion konvertiert die Punktwolke in ein Array mit Punktkoordinaten + und berechneten Entfernungen. + - Punkte außerhalb eines spezifizierten Entfernungsbereichs und räumlichen + Filtergrenzen werden verworfen. + - Anschließend wird DBSCAN-Clustering auf die 2D-Koordinaten (x, y) der Punkte + angewendet. - Die Cluster-Labels und ihre Häufigkeiten werden als Dictionary zurückgegeben. """ data = pointcloud2_to_array(pointcloud_msg) @@ -127,10 +136,16 @@ def cluster_radar_data_from_pointcloud( labels = clustering.labels_ # Zählen der Punktanzahl in jedem Cluster - clustered_points = {label: list(labels).count(label) for label in set(labels)} + clustered_points = { + label: list(labels).count(label) + for label in set(labels) + } # Konvertiere die Labels in Integer und gebe das Dictionary zurück - clustered_points = {int(label): count for label, count in clustered_points.items()} + clustered_points = { + int(label): count + for label, count in clustered_points.items() + } return clustered_points From b4e217cb2c16e23a47f7889891340c54ca986f0e Mon Sep 17 00:00:00 2001 From: michalal7 <53532256+michalal7@users.noreply.github.com> Date: Mon, 25 Nov 2024 10:48:15 +0100 Subject: [PATCH 55/85] Update radar_node.py Translated comments to englisch and reformated code. --- code/perception/src/radar_node.py | 90 +++++++++---------------------- 1 file changed, 25 insertions(+), 65 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index eb00bd5c..4ddf5b4d 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -9,9 +9,7 @@ class RadarNode: - """See doc/perception/radar_node.md on - how to configure this node - """ + """See doc/perception/radar_node.md on how to configure this node.""" def callback(self, data): """Process radar Point2Cloud data and publish clustered data points. @@ -23,56 +21,46 @@ def callback(self, data): Args: data: Point2Cloud message containing radar data """ - clustered_points = cluster_radar_data_from_pointcloud(data, 10) clustered_points_json = json.dumps(clustered_points) self.dist_array_radar_publisher.publish(clustered_points_json) def listener(self): - """ - Initializes the node and it's publishers - """ - # run simultaneously. + """Initializes the node and its publishers.""" rospy.init_node("radar_node") - - # publisher for radar dist_array self.dist_array_radar_publisher = rospy.Publisher( rospy.get_param( - "~image_distance_topic", - "/paf/hero/Radar/dist_array_unsegmented", + "~image_distance_topic", "/paf/hero/Radar/dist_array_unsegmented" ), String, queue_size=10, ) - rospy.Subscriber( rospy.get_param("~source_topic", "/carla/hero/RADAR"), PointCloud2, self.callback, ) - rospy.spin() def pointcloud2_to_array(pointcloud_msg): """ - Konvertiert eine ROS-PointCloud2-Nachricht in ein NumPy-Array und berechnet - die euklidischen Entfernungen jedes Punkts vom Ursprung. + Converts a ROS PointCloud2 message into a NumPy array and calculates the + Euclidean distance of each point from the origin. - Parameter: + Parameters: - pointcloud_msg: sensor_msgs/PointCloud2 - Die ROS-PointCloud2-Nachricht, die die 3D-Punkte enthält. + The ROS PointCloud2 message containing the 3D points. - Rückgabewert: + Returns: - np.ndarray - Ein 2D-Array, in dem jede Zeile einem Punkt in der Punktwolke entspricht: - [x, y, z, distance], wobei "distance" die Entfernung vom Ursprung ist. + A 2D array where each row corresponds to a point in the point cloud: + [x, y, z, distance], where "distance" is the distance from the origin. """ cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) distances = np.sqrt( cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 ) - return np.column_stack( (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) ) @@ -82,70 +70,42 @@ def cluster_radar_data_from_pointcloud( pointcloud_msg, max_distance, eps=1.0, min_samples=2 ): """ - Filtert und gruppiert Punkte aus einer ROS-PointCloud2-Nachricht - basierend auf DBSCAN-Clustering. + Filters and clusters points from a ROS PointCloud2 message based on DBSCAN + clustering. - Parameter: + Parameters: - pointcloud_msg: sensor_msgs/PointCloud2 - Die ROS-PointCloud2-Nachricht mit den 3D-Punkten. + The ROS PointCloud2 message containing the 3D points. - max_distance: float - Maximale Entfernung, um Punkte zu berücksichtigen. Punkte außerhalb dieser - Entfernung werden verworfen. + Maximum distance to consider points. Points beyond this distance are + discarded. - eps: float, optional (default: 1.0) - Der maximale Abstand zwischen zwei Punkten, damit diese im selben Cluster - sein können. + The maximum distance between two points for them to be considered in + the same cluster. - min_samples: int, optional (default: 2) - Die minimale Anzahl von Punkten, die erforderlich sind, um einen Cluster - zu bilden. + The minimum number of points required to form a cluster. - Rückgabewert: + Returns: - dict - Ein Dictionary, in dem die Schlüssel die Cluster-Labels (int) sind und die - Werte die Anzahl der Punkte in jedem Cluster. Wenn keine Punkte vorhanden - sind, wird ein leeres Dictionary zurückgegeben. - - Funktionalität: - - Die Funktion konvertiert die Punktwolke in ein Array mit Punktkoordinaten - und berechneten Entfernungen. - - Punkte außerhalb eines spezifizierten Entfernungsbereichs und räumlichen - Filtergrenzen werden verworfen. - - Anschließend wird DBSCAN-Clustering auf die 2D-Koordinaten (x, y) der Punkte - angewendet. - - Die Cluster-Labels und ihre Häufigkeiten werden als Dictionary zurückgegeben. + A dictionary where the keys are cluster labels (int) and the values + are the number of points in each cluster. Returns an empty dictionary + if no points are available. """ data = pointcloud2_to_array(pointcloud_msg) - - # Filtere Punkte basierend auf der maximalen Entfernung filtered_data = data[data[:, 3] < max_distance] - - # Zusätzlicher Filter auf Y- und Z-Werte filtered_data = filtered_data[ (filtered_data[:, 1] >= -1) & (filtered_data[:, 1] <= 1) & (filtered_data[:, 2] <= 1.3) & (filtered_data[:, 2] >= -0.7) ] - - # Rückgabe eines leeren Dictionaries, wenn keine Punkte übrig sind if len(filtered_data) == 0: return {} - - # Extrahiere die 2D-Koordinaten (x, y) für das Clustering coordinates = filtered_data[:, :2] clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) labels = clustering.labels_ - - # Zählen der Punktanzahl in jedem Cluster - clustered_points = { - label: list(labels).count(label) - for label in set(labels) - } - - # Konvertiere die Labels in Integer und gebe das Dictionary zurück - clustered_points = { - int(label): count - for label, count in clustered_points.items() - } + clustered_points = {label: list(labels).count(label) for label in set(labels)} + clustered_points = {int(label): count for label, count in clustered_points.items()} return clustered_points From 5083db9c81d3a34686cb087d52c4448cd05a3bb5 Mon Sep 17 00:00:00 2001 From: asamluka Date: Mon, 25 Nov 2024 12:55:46 +0100 Subject: [PATCH 56/85] fixing broken or wrong references --- doc/general/architecture_current.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/general/architecture_current.md b/doc/general/architecture_current.md index f771d5a5..aa0a472a 100644 --- a/doc/general/architecture_current.md +++ b/doc/general/architecture_current.md @@ -44,7 +44,7 @@ environment representation that can be used by the [Planning](#Planning) for fur It provides localization of the agent, filtering noise from sensor data, preconditions images for further usage in other nodes and detects certain points of interest (at the moment only traffic lights). Further information regarding the perception can be found [here](../perception/README.md). -Research for the perception can be found [here](../research/perception/README.md). +Research for the perception can be found [here](../research/paf24/perception/). In the following, all subscribed and published topics and their corresponding nodes are listed with the format: @@ -228,7 +228,7 @@ It consists of three components: - [Collision Check](../planning//Collision_Check.md): Checks for collisions based on objects recieved from [Perception](#perception) - [ACC](../planning/ACC.md): Generates a new speed based on a possible collision recieved from Collision Check and speedlimits recieved from [Global Planner](#global-planning) -- [Motion Planning](../planning/motion_planning.md): Decides the target speed and modifies trajectory if signal recieved from [Decision Making](#decision-making) +- [Motion Planning](../planning/motion_planning.md): Decides the target speed and modifies trajectory if signal recieved from [Behavior Agent](#behavior-agent-behavior_agent) Subscriptions: @@ -267,7 +267,7 @@ Subscriptions: Publishes: -[ACC.py](/../paf/code/planning/src/behavior_agent/local_planner/ACC.py) +[ACC.py](/../paf/code/planning/src/local_planner/ACC.py) - ```/paf/hero/acc_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html)) - ```/paf/hero/current_wp``` ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html)) From c9dde1f55d5b843b543c902b4b7f4737749c4488 Mon Sep 17 00:00:00 2001 From: SirMDA Date: Tue, 26 Nov 2024 18:19:12 +0100 Subject: [PATCH 57/85] added yolov11 --- code/perception/launch/perception.launch | 11 +- code/perception/src/vision_node.py | 161 ++++++++++++---------- code/perception/src/vision_node_helper.py | 126 +++++++++++++++++ code/requirements.txt | 2 +- 4 files changed, 225 insertions(+), 75 deletions(-) create mode 100644 code/perception/src/vision_node_helper.py diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 67a9c2ab..7059f24f 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -32,8 +32,7 @@ --> - - + @@ -58,10 +57,14 @@ Image-Segmentation: - deeplabv3_resnet101 - - yolov8x-seg + - yolov8x-seg + - yolo11n-seg + - yolo11s-seg + - yolo11m-seg + - yolo11l-seg --> - + diff --git a/code/perception/src/vision_node.py b/code/perception/src/vision_node.py index 7039b9f3..9df05e27 100755 --- a/code/perception/src/vision_node.py +++ b/code/perception/src/vision_node.py @@ -15,6 +15,7 @@ ) import torchvision.transforms as t import cv2 +from perception.src.vision_node_helper import get_carla_class_name, get_carla_color from rospy.numpy_msg import numpy_msg from sensor_msgs.msg import Image as ImageMsg from std_msgs.msg import Header, Float32MultiArray @@ -24,6 +25,7 @@ from ultralytics import NAS, YOLO, RTDETR, SAM, FastSAM import asyncio import rospy +from ultralytics.utils.ops import scale_masks class VisionNode(CompatibleNode): @@ -77,6 +79,10 @@ def __init__(self, name, **kwargs): "yolov8x-seg": (YOLO, "yolov8x-seg.pt", "segmentation", "ultralytics"), "sam_l": (SAM, "sam_l.pt", "detection", "ultralytics"), "FastSAM-x": (FastSAM, "FastSAM-x.pt", "detection", "ultralytics"), + "yolo11n-seg": (YOLO, "yolo11n-seg.pt", "segmentation", "ultralytics"), + "yolo11s-seg": (YOLO, "yolo11s-seg.pt", "segmentation", "ultralytics"), + "yolo11m-seg": (YOLO, "yolo11m-seg.pt", "segmentation", "ultralytics"), + "yolo11l-seg": (YOLO, "yolo11l-seg.pt", "segmentation", "ultralytics"), } # general setup @@ -239,7 +245,7 @@ def handle_camera_image(self, image): vision_result = self.predict_ultralytics(image) # publish vision result to rviz - img_msg = self.bridge.cv2_to_imgmsg(vision_result, encoding="rgb8") + img_msg = self.bridge.cv2_to_imgmsg(vision_result, encoding="bgr8") img_msg.header = image.header # publish img to corresponding angle topic @@ -341,7 +347,7 @@ def predict_ultralytics(self, image): cv_image = cv2.cvtColor(cv_image, cv2.COLOR_RGB2BGR) # run model prediction - output = self.model(cv_image, half=True, verbose=False) + output = self.model.track(cv_image, half=True, verbose=False, imgsz=640) # handle distance of objects @@ -349,81 +355,86 @@ def predict_ultralytics(self, image): distance_output = [] c_boxes = [] c_labels = [] + c_colors = [] + masks = output[0].masks.data boxes = output[0].boxes - for box in boxes: - cls = box.cls.item() # class index of object - pixels = box.xyxy[0] # upper left and lower right pixel coords + for i, box_image in enumerate(boxes): + cls = box_image.cls.item() # class index of object + pixels = box_image.xyxy[0] # upper left and lower right pixel coords # only run distance calc when dist_array is available # this if is needed because the lidar starts # publishing with a delay - if self.dist_arrays is not None: - - # crop bounding box area out of depth image - distances = np.asarray( - self.dist_arrays[ - int(pixels[1]) : int(pixels[3]) : 1, - int(pixels[0]) : int(pixels[2]) : 1, - ::, - ] - ) + if self.dist_arrays is None: + continue + + # crop bounding box area out of depth image + distances = np.asarray( + self.dist_arrays[ + int(pixels[1]) : int(pixels[3]) : 1, + int(pixels[0]) : int(pixels[2]) : 1, + ::, + ] + ) - # set all 0 (black) values to np.inf (necessary if - # you want to search for minimum) - # these are all pixels where there is no - # corresponding lidar point in the depth image - condition = distances[:, :, 0] != 0 - non_zero_filter = distances[condition] - distances_copy = distances.copy() - distances_copy[distances_copy == 0] = np.inf - - # only proceed if there is more than one lidar - # point in the bounding box - if len(non_zero_filter) > 0: - - """ - !Watch out: - The calculation of min x and min abs y is currently - only for center angle - For back, left and right the values are different in the - coordinate system of the lidar. - (Example: the closedt distance on the back view should the - max x since the back view is on the -x axis) - """ - - # copy actual lidar points - obj_dist_min_x = self.min_x(dist_array=distances_copy) - obj_dist_min_abs_y = self.min_abs_y(dist_array=distances_copy) - - # absolut distance to object for visualization - abs_distance = np.sqrt( - obj_dist_min_x[0] ** 2 - + obj_dist_min_x[1] ** 2 - + obj_dist_min_x[2] ** 2 - ) - - # append class index, min x and min abs y to output array - distance_output.append(float(cls)) - distance_output.append(float(obj_dist_min_x[0])) - distance_output.append(float(obj_dist_min_abs_y[1])) - - else: - # fallback values for bounding box if - # no lidar points where found - obj_dist_min_x = (np.inf, np.inf, np.inf) - obj_dist_min_abs_y = (np.inf, np.inf, np.inf) - abs_distance = np.inf - - # add values for visualization - c_boxes.append(torch.tensor(pixels)) - c_labels.append( - f"Class: {cls}," - f"Meters: {round(abs_distance, 2)}," - f"({round(float(obj_dist_min_x[0]), 2)}," - f"{round(float(obj_dist_min_abs_y[1]), 2)})" + # set all 0 (black) values to np.inf (necessary if + # you want to search for minimum) + # these are all pixels where there is no + # corresponding lidar point in the depth image + condition = distances[:, :, 0] != 0 + non_zero_filter = distances[condition] + distances_copy = distances.copy() + distances_copy[distances_copy == 0] = np.inf + + # only proceed if there is more than one lidar + # point in the bounding box + if len(non_zero_filter) > 0: + + """ + !Watch out: + The calculation of min x and min abs y is currently + only for center angle + For back, left and right the values are different in the + coordinate system of the lidar. + (Example: the closedt distance on the back view should the + max x since the back view is on the -x axis) + """ + + # copy actual lidar points + obj_dist_min_x = self.min_x(dist_array=distances_copy) + obj_dist_min_abs_y = self.min_abs_y(dist_array=distances_copy) + + # absolut distance to object for visualization + abs_distance = np.sqrt( + obj_dist_min_x[0] ** 2 + + obj_dist_min_x[1] ** 2 + + obj_dist_min_x[2] ** 2 ) + # append class index, min x and min abs y to output array + distance_output.append(float(cls)) + distance_output.append(float(obj_dist_min_x[0])) + distance_output.append(float(obj_dist_min_abs_y[1])) + + else: + # fallback values for bounding box if + # no lidar points where found + obj_dist_min_x = (np.inf, np.inf, np.inf) + obj_dist_min_abs_y = (np.inf, np.inf, np.inf) + abs_distance = np.inf + + # add values for visualization + c_boxes.append(torch.tensor(pixels)) + c_labels.append( + f"Class: {get_carla_class_name(cls)}, " + f"Meters: {round(abs_distance, 2)}, " + f"TrackingId: {int(box_image.id)}, " + f"({round(float(obj_dist_min_x[0]), 2)}, " + f"{round(float(obj_dist_min_abs_y[1]), 2)})", + ) + c_colors.append(get_carla_color(int(cls))) + # publish list of distances of objects for planning self.distance_publisher.publish(Float32MultiArray(data=distance_output)) @@ -437,7 +448,7 @@ def predict_ultralytics(self, image): # draw bounding boxes and distance values on image c_boxes = torch.stack(c_boxes) - box = draw_bounding_boxes( + box_image = draw_bounding_boxes( image_np_with_detections, c_boxes, c_labels, @@ -445,7 +456,17 @@ def predict_ultralytics(self, image): width=3, font_size=12, ) - np_box_img = np.transpose(box.detach().numpy(), (1, 2, 0)) + np_box_img = np.transpose(box_image.detach().numpy(), (1, 2, 0)) + + scaled_masks = np.squeeze( + scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), 1 + ) + + mask_image = draw_segmentation_masks( + box_image, torch.from_numpy(scaled_masks > 0), alpha=0.6, colors=c_colors + ) + np_box_img = np.transpose(mask_image.detach().numpy(), (1, 2, 0)) + box_img = cv2.cvtColor(np_box_img, cv2.COLOR_BGR2RGB) return box_img diff --git a/code/perception/src/vision_node_helper.py b/code/perception/src/vision_node_helper.py new file mode 100644 index 00000000..0ea33d95 --- /dev/null +++ b/code/perception/src/vision_node_helper.py @@ -0,0 +1,126 @@ +# Carla-Farben +carla_colors = [ + [0, 0, 0], # 0: None + [70, 70, 70], # 1: Buildings + [190, 153, 153], # 2: Fences + [72, 0, 90], # 3: Other + [220, 20, 60], # 4: Pedestrians + [153, 153, 153], # 5: Poles + [157, 234, 50], # 6: RoadLines + [128, 64, 128], # 7: Roads + [244, 35, 232], # 8: Sidewalks + [107, 142, 35], # 9: Vegetation + [0, 0, 255], # 10: Vehicles + [102, 102, 156], # 11: Walls + [220, 220, 0], # 12: TrafficSigns +] + +carla_class_names = [ + "None", # 0 + "Buildings", # 1 + "Fences", # 2 + "Other", # 3 + "Pedestrians", # 4 + "Poles", # 5 + "RoadLines", # 6 + "Roads", # 7 + "Sidewalks", # 8 + "Vegetation", # 9 + "Vehicles", # 10 + "Walls", # 11 + "TrafficSigns", # 12 +] + +# COCO-Klassen → Carla-Klassen Mapping +coco_to_carla = [ + 4, # 0: Person -> Pedestrians + 10, # 1: Bicycle -> Vehicles + 10, # 2: Car -> Vehicles + 10, # 3: Motorbike -> Vehicles + 10, # 4: Airplane -> Vehicles + 10, # 5: Bus -> Vehicles + 10, # 6: Train -> Vehicles + 10, # 7: Truck -> Vehicles + 10, # 8: Boat -> Vehicles + 12, # 9: Traffic Light -> TrafficSigns + 3, # 10: Fire Hydrant -> Other + 12, # 11: Stop Sign -> TrafficSigns + 3, # 12: Parking Meter -> Other + 3, # 13: Bench -> Other + 3, # 14: Bird -> Other + 3, # 15: Cat -> Other + 3, # 16: Dog -> Other + 3, # 17: Horse -> Other + 3, # 18: Sheep -> Other + 3, # 19: Cow -> Other + 3, # 20: Elephant -> Other + 3, # 21: Bear -> Other + 3, # 22: Zebra -> Other + 3, # 23: Giraffe -> Other + 3, # 24: Backpack -> Other + 3, # 25: Umbrella -> Other + 3, # 26: Handbag -> Other + 3, # 27: Tie -> Other + 3, # 28: Suitcase -> Other + 3, # 29: Frisbee -> Other + 3, # 30: Skis -> Other + 3, # 31: Snowboard -> Other + 3, # 32: Sports Ball -> Other + 3, # 33: Kite -> Other + 3, # 34: Baseball Bat -> Other + 3, # 35: Baseball Glove -> Other + 3, # 36: Skateboard -> Other + 3, # 37: Surfboard -> Other + 3, # 38: Tennis Racket -> Other + 3, # 39: Bottle -> Other + 3, # 40: Wine Glass -> Other + 3, # 41: Cup -> Other + 3, # 42: Fork -> Other + 3, # 43: Knife -> Other + 3, # 44: Spoon -> Other + 3, # 45: Bowl -> Other + 3, # 46: Banana -> Other + 3, # 47: Apple -> Other + 3, # 48: Sandwich -> Other + 3, # 49: Orange -> Other + 3, # 50: Broccoli -> Other + 3, # 51: Carrot -> Other + 3, # 52: Hot Dog -> Other + 3, # 53: Pizza -> Other + 3, # 54: Donut -> Other + 3, # 55: Cake -> Other + 3, # 56: Chair -> Other + 3, # 57: Couch -> Other + 3, # 58: Potted Plant -> Other + 3, # 59: Bed -> Other + 3, # 60: Dining Table -> Other + 3, # 61: Toilet -> Other + 3, # 62: TV -> Other + 3, # 63: Laptop -> Other + 3, # 64: Mouse -> Other + 3, # 65: Remote -> Other + 3, # 66: Keyboard -> Other + 3, # 67: Cell Phone -> Other + 3, # 68: Microwave -> Other + 3, # 69: Oven -> Other + 3, # 70: Toaster -> Other + 3, # 71: Sink -> Other + 3, # 72: Refrigerator -> Other + 3, # 73: Book -> Other + 3, # 74: Clock -> Other + 3, # 75: Vase -> Other + 3, # 76: Scissors -> Other + 3, # 77: Teddy Bear -> Other + 3, # 78: Hair Drier -> Other + 3, # 79: Toothbrush -> Other +] + + +def get_carla_color(coco_class): + carla_class = coco_to_carla[coco_class] + return carla_colors[carla_class] + + +def get_carla_class_name(coco_class): + carla_class = coco_to_carla[int(coco_class)] + return carla_class_names[carla_class] diff --git a/code/requirements.txt b/code/requirements.txt index 55de87f0..746fcdfe 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -13,7 +13,7 @@ scipy==1.10.1 xmltodict==0.13.0 py-trees==2.2.3 numpy==1.23.5 -ultralytics==8.1.11 +ultralytics==8.3.32 scikit-learn>=0.18 pandas==2.0.3 debugpy==1.8.7 \ No newline at end of file From 7b1cc263d232c4ff066b23796e31878e18fe91ac Mon Sep 17 00:00:00 2001 From: SirMDA Date: Tue, 26 Nov 2024 18:22:09 +0100 Subject: [PATCH 58/85] removed debug --- code/perception/launch/perception.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 7059f24f..1c3f487e 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -32,7 +32,8 @@ --> - + + From 77c68f646d706c727b55c6c6eaa1f631cd63cf32 Mon Sep 17 00:00:00 2001 From: SirMDA Date: Tue, 26 Nov 2024 18:23:08 +0100 Subject: [PATCH 59/85] removed superflous enumerate --- code/perception/src/vision_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/code/perception/src/vision_node.py b/code/perception/src/vision_node.py index 9df05e27..65647ba9 100755 --- a/code/perception/src/vision_node.py +++ b/code/perception/src/vision_node.py @@ -359,7 +359,7 @@ def predict_ultralytics(self, image): masks = output[0].masks.data boxes = output[0].boxes - for i, box_image in enumerate(boxes): + for box_image in boxes: cls = box_image.cls.item() # class index of object pixels = box_image.xyxy[0] # upper left and lower right pixel coords From f20ac2b56becc2c07388438c54c93eb587983577 Mon Sep 17 00:00:00 2001 From: SirMDA Date: Tue, 26 Nov 2024 18:24:47 +0100 Subject: [PATCH 60/85] renamed --- code/perception/src/vision_node.py | 24 +++++++++++++----------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/code/perception/src/vision_node.py b/code/perception/src/vision_node.py index 65647ba9..df8a4244 100755 --- a/code/perception/src/vision_node.py +++ b/code/perception/src/vision_node.py @@ -359,9 +359,9 @@ def predict_ultralytics(self, image): masks = output[0].masks.data boxes = output[0].boxes - for box_image in boxes: - cls = box_image.cls.item() # class index of object - pixels = box_image.xyxy[0] # upper left and lower right pixel coords + for box in boxes: + cls = box.cls.item() # class index of object + pixels = box.xyxy[0] # upper left and lower right pixel coords # only run distance calc when dist_array is available # this if is needed because the lidar starts @@ -429,7 +429,7 @@ def predict_ultralytics(self, image): c_labels.append( f"Class: {get_carla_class_name(cls)}, " f"Meters: {round(abs_distance, 2)}, " - f"TrackingId: {int(box_image.id)}, " + f"TrackingId: {int(box.id)}, " f"({round(float(obj_dist_min_x[0]), 2)}, " f"{round(float(obj_dist_min_abs_y[1]), 2)})", ) @@ -448,7 +448,7 @@ def predict_ultralytics(self, image): # draw bounding boxes and distance values on image c_boxes = torch.stack(c_boxes) - box_image = draw_bounding_boxes( + bounding_box_images = draw_bounding_boxes( image_np_with_detections, c_boxes, c_labels, @@ -456,19 +456,21 @@ def predict_ultralytics(self, image): width=3, font_size=12, ) - np_box_img = np.transpose(box_image.detach().numpy(), (1, 2, 0)) + np_box_img = np.transpose(bounding_box_images.detach().numpy(), (1, 2, 0)) scaled_masks = np.squeeze( scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), 1 ) - mask_image = draw_segmentation_masks( - box_image, torch.from_numpy(scaled_masks > 0), alpha=0.6, colors=c_colors + mask_images = draw_segmentation_masks( + bounding_box_images, + torch.from_numpy(scaled_masks > 0), + alpha=0.6, + colors=c_colors, ) - np_box_img = np.transpose(mask_image.detach().numpy(), (1, 2, 0)) + np_box_img = np.transpose(mask_images.detach().numpy(), (1, 2, 0)) - box_img = cv2.cvtColor(np_box_img, cv2.COLOR_BGR2RGB) - return box_img + return cv2.cvtColor(np_box_img, cv2.COLOR_BGR2RGB) def min_x(self, dist_array): """ From b29e3258838875981f98248d5cfbc9e71e406ab8 Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 27 Nov 2024 16:17:12 +0100 Subject: [PATCH 61/85] added first draft of radar data visualization --- code/perception/src/radar_node.py | 115 +++++++++++++++++++++++++++++- 1 file changed, 113 insertions(+), 2 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 4ddf5b4d..247a2df4 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -2,10 +2,12 @@ import rospy import ros_numpy import numpy as np -from std_msgs.msg import String -from sensor_msgs.msg import PointCloud2 +from std_msgs.msg import String, Header +from sensor_msgs.msg import PointCloud2, PointField from sklearn.cluster import DBSCAN import json +from sensor_msgs import point_cloud2 +import struct class RadarNode: @@ -25,6 +27,23 @@ def callback(self, data): clustered_points_json = json.dumps(clustered_points) self.dist_array_radar_publisher.publish(clustered_points_json) + # output array [x, y, z, distance] + dataarray = pointcloud2_to_array(data) + + # input array [x, y, z, distance], max_distance, output: filtered data + # dataarray = filter_data(dataarray, 10) + + # input array [x, y, z, distance], output: dict clustered + clustered_data = cluster_data(dataarray) + + # input array [x, y, z, distance], clustered labels + cloud = create_pointcloud2(dataarray, clustered_data.labels_) + + self.visualization_radar_publisher.publish(cloud) + + cluster_info = generate_cluster_labels_and_colors(clustered_data, dataarray) + self.cluster_info_radar_publisher.publish(cluster_info) + def listener(self): """Initializes the node and its publishers.""" rospy.init_node("radar_node") @@ -35,6 +54,20 @@ def listener(self): String, queue_size=10, ) + self.visualization_radar_publisher = rospy.Publisher( + rospy.get_param( + "~image_distance_topic", "/paf/hero/Radar/Visualization" + ), + PointCloud2, + queue_size=10, + ) + self.cluster_info_radar_publisher = rospy.Publisher( + rospy.get_param( + "~image_distance_topic", "/paf/hero/Radar/ClusterInfo" + ), + String, + queue_size=10, + ) rospy.Subscriber( rospy.get_param("~source_topic", "/carla/hero/RADAR"), PointCloud2, @@ -109,6 +142,84 @@ def cluster_radar_data_from_pointcloud( return clustered_points +# filters radar data in distance, y, z direction +def filter_data(data, max_distance): + + filtered_data = data[data[:, 3] < max_distance] + filtered_data = filtered_data[ + (filtered_data[:, 1] >= -1) + & (filtered_data[:, 1] <= 1) + & (filtered_data[:, 2] <= 1.3) + & (filtered_data[:, 2] >= -0.7) + ] + return filtered_data + + +# clusters data with DBSCAN +def cluster_data(filtered_data, eps=0.2, min_samples=1): + + if len(filtered_data) == 0: + return {} + coordinates = filtered_data[:, :2] + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) + return clustering + + +# generates random color for cluster +def generate_color_map(num_clusters): + np.random.seed(42) + colors = np.random.randint(0, 255, size=(num_clusters, 3)) + return colors + + +# creates pointcloud2 for publishing clustered radar data +def create_pointcloud2(clustered_points, cluster_labels): + header = Header() + header.stamp = rospy.Time.now() + header.frame_id = "hero/RADAR" + + points = [] + unique_labels = np.unique(cluster_labels) + colors = generate_color_map(len(unique_labels)) + + for i, point in enumerate(clustered_points): + x, y, z, _ = point + label = cluster_labels[i] + + if label == -1: + r, g, b = 128, 128, 128 + else: + r, g, b = colors[label] + + rgb = struct.unpack('f', struct.pack('I', (r << 16) | (g << 8) | b))[0] + points.append([x, y, z, rgb]) + + fields = [ + PointField('x', 0, PointField.FLOAT32, 1), + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1), + PointField('rgb', 12, PointField.FLOAT32, 1), + ] + + return point_cloud2.create_cloud(header, fields, points) + + +# generates string with label-id and cluster size +def generate_cluster_labels_and_colors(clusters, data): + cluster_info = [] + + for label in set(clusters.labels_): + cluster_points = data[clusters.labels_ == label] + cluster_size = len(cluster_points) + if label != -1: + cluster_info.append({ + "label": int(label), + "points_count": cluster_size + }) + + return json.dumps(cluster_info) + + if __name__ == "__main__": radar_node = RadarNode() radar_node.listener() From 614869034793471e0a4c396da3eedce809cb7475 Mon Sep 17 00:00:00 2001 From: Ralf Date: Thu, 28 Nov 2024 16:15:49 +0100 Subject: [PATCH 62/85] Added velocity as clustering criteria --- code/perception/src/radar_node.py | 32 +++++++++++++++++++++---------- 1 file changed, 22 insertions(+), 10 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 247a2df4..08dede8e 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -5,6 +5,7 @@ from std_msgs.msg import String, Header from sensor_msgs.msg import PointCloud2, PointField from sklearn.cluster import DBSCAN +from sklearn.preprocessing import StandardScaler import json from sensor_msgs import point_cloud2 import struct @@ -23,9 +24,9 @@ def callback(self, data): Args: data: Point2Cloud message containing radar data """ - clustered_points = cluster_radar_data_from_pointcloud(data, 10) - clustered_points_json = json.dumps(clustered_points) - self.dist_array_radar_publisher.publish(clustered_points_json) + # clustered_points = cluster_radar_data_from_pointcloud(data, 10) + # clustered_points_json = json.dumps(clustered_points) + # self.dist_array_radar_publisher.publish(clustered_points_json) # output array [x, y, z, distance] dataarray = pointcloud2_to_array(data) @@ -91,11 +92,14 @@ def pointcloud2_to_array(pointcloud_msg): [x, y, z, distance], where "distance" is the distance from the origin. """ cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) - distances = np.sqrt( - cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 - ) + # distances = np.sqrt( + # cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 + # ) + # return np.column_stack( + # (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) + # ) return np.column_stack( - (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) + (cloud_array["x"], cloud_array["y"], cloud_array["z"], cloud_array["Velocity"]) ) @@ -160,8 +164,15 @@ def cluster_data(filtered_data, eps=0.2, min_samples=1): if len(filtered_data) == 0: return {} - coordinates = filtered_data[:, :2] - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) + # coordinates = filtered_data[:, :2] + # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) + + # worse than without scaling + # scaler = StandardScaler() + # data_scaled = scaler.fit_transform(filtered_data) + # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(data_scaled) + + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(filtered_data) return clustering @@ -183,7 +194,8 @@ def create_pointcloud2(clustered_points, cluster_labels): colors = generate_color_map(len(unique_labels)) for i, point in enumerate(clustered_points): - x, y, z, _ = point + # x, y, z, _ = point + x, y, z, v = point label = cluster_labels[i] if label == -1: From 78179453423369e2b51792a0d0cecae272f7e2ca Mon Sep 17 00:00:00 2001 From: Ludwig Holl Date: Fri, 29 Nov 2024 17:04:01 +0100 Subject: [PATCH 63/85] updated vision_node --- code/perception/src/vision_node.py | 34 ++++++++++---------- code/perception/src/vision_node_helper.py | 38 +++++++++++++++++++++-- 2 files changed, 53 insertions(+), 19 deletions(-) diff --git a/code/perception/src/vision_node.py b/code/perception/src/vision_node.py index df8a4244..0e6a03cd 100755 --- a/code/perception/src/vision_node.py +++ b/code/perception/src/vision_node.py @@ -356,7 +356,10 @@ def predict_ultralytics(self, image): c_boxes = [] c_labels = [] c_colors = [] - masks = output[0].masks.data + if hasattr(output[0], "masks") and output[0].masks is not None: + masks = output[0].masks.data + else: + masks = None boxes = output[0].boxes for box in boxes: @@ -390,7 +393,6 @@ def predict_ultralytics(self, image): # only proceed if there is more than one lidar # point in the bounding box if len(non_zero_filter) > 0: - """ !Watch out: The calculation of min x and min abs y is currently @@ -448,7 +450,7 @@ def predict_ultralytics(self, image): # draw bounding boxes and distance values on image c_boxes = torch.stack(c_boxes) - bounding_box_images = draw_bounding_boxes( + drawn_images = draw_bounding_boxes( image_np_with_detections, c_boxes, c_labels, @@ -456,21 +458,21 @@ def predict_ultralytics(self, image): width=3, font_size=12, ) - np_box_img = np.transpose(bounding_box_images.detach().numpy(), (1, 2, 0)) - - scaled_masks = np.squeeze( - scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), 1 - ) + if masks is not None: + scaled_masks = np.squeeze( + scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), + 1, + ) - mask_images = draw_segmentation_masks( - bounding_box_images, - torch.from_numpy(scaled_masks > 0), - alpha=0.6, - colors=c_colors, - ) - np_box_img = np.transpose(mask_images.detach().numpy(), (1, 2, 0)) + drawn_images = draw_segmentation_masks( + drawn_images, + torch.from_numpy(scaled_masks > 0), + alpha=0.6, + colors=c_colors, + ) - return cv2.cvtColor(np_box_img, cv2.COLOR_BGR2RGB) + np_image = np.transpose(drawn_images.detach().numpy(), (1, 2, 0)) + return cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB) def min_x(self, dist_array): """ diff --git a/code/perception/src/vision_node_helper.py b/code/perception/src/vision_node_helper.py index 0ea33d95..a96a0c82 100644 --- a/code/perception/src/vision_node_helper.py +++ b/code/perception/src/vision_node_helper.py @@ -1,3 +1,6 @@ +from typing import List, Tuple, Union + + # Carla-Farben carla_colors = [ [0, 0, 0], # 0: None @@ -115,12 +118,41 @@ 3, # 79: Toothbrush -> Other ] +COCO_CLASS_COUNT = 80 + + +def get_carla_color(coco_class: Union[int, float]) -> List[int]: + """Get the Carla color for a given COCO class. + Args: + coco_class: COCO class index (0-79) -def get_carla_color(coco_class): + Returns: + RGB color values for the corresponding Carla class + + Raises: + ValueError: If coco_class is out of valid range + """ + coco_idx = int(coco_class) + if not 0 <= coco_idx < COCO_CLASS_COUNT: + raise ValueError(f"Invalid COCO class index: {coco_idx}") carla_class = coco_to_carla[coco_class] return carla_colors[carla_class] -def get_carla_class_name(coco_class): - carla_class = coco_to_carla[int(coco_class)] +def get_carla_class_name(coco_class: Union[int, float]) -> str: + """Get the Carla class name for a given COCO class. + Args: + coco_class: COCO class index (0-79) + + Returns: + Name of the corresponding Carla class + + Raises: + ValueError: If coco_class is out of valid range + """ + coco_idx = int(coco_class) + + if not 0 <= coco_idx < COCO_CLASS_COUNT: + raise ValueError(f"Invalid COCO class index: {coco_idx}") + carla_class = coco_to_carla[coco_idx] return carla_class_names[carla_class] From 38d85f7dad0453a983a2ebc303e2bc61d61278b6 Mon Sep 17 00:00:00 2001 From: Ludwig Holl Date: Fri, 29 Nov 2024 17:09:51 +0100 Subject: [PATCH 64/85] fixed minor bug --- code/perception/src/vision_node_helper.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/code/perception/src/vision_node_helper.py b/code/perception/src/vision_node_helper.py index a96a0c82..6778f7b6 100644 --- a/code/perception/src/vision_node_helper.py +++ b/code/perception/src/vision_node_helper.py @@ -1,4 +1,4 @@ -from typing import List, Tuple, Union +from typing import List, Union # Carla-Farben @@ -135,7 +135,7 @@ def get_carla_color(coco_class: Union[int, float]) -> List[int]: coco_idx = int(coco_class) if not 0 <= coco_idx < COCO_CLASS_COUNT: raise ValueError(f"Invalid COCO class index: {coco_idx}") - carla_class = coco_to_carla[coco_class] + carla_class = coco_to_carla[coco_idx] return carla_colors[carla_class] From 3b5a15c7a9e7129a84f7dd8d1dfb32fe997d93ff Mon Sep 17 00:00:00 2001 From: SirMDA Date: Tue, 3 Dec 2024 20:01:03 +0100 Subject: [PATCH 65/85] modified requirements.txt with pyopenssl version --- code/requirements.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/code/requirements.txt b/code/requirements.txt index 55de87f0..cbe57476 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -16,4 +16,5 @@ numpy==1.23.5 ultralytics==8.1.11 scikit-learn>=0.18 pandas==2.0.3 -debugpy==1.8.7 \ No newline at end of file +debugpy==1.8.7 +pyopenssl==24.3.0 \ No newline at end of file From f5bbe472694e29c32a5cc882cca3ac1b7c9f0c67 Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 4 Dec 2024 16:17:28 +0100 Subject: [PATCH 66/85] started implementation of bounding boxes for detected radar clusters --- code/perception/src/radar_node.py | 176 ++++++++++++++++++++++++++++-- 1 file changed, 165 insertions(+), 11 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 08dede8e..39ed7ec0 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -8,6 +8,9 @@ from sklearn.preprocessing import StandardScaler import json from sensor_msgs import point_cloud2 +from visualization_msgs.msg import Marker, MarkerArray +from geometry_msgs.msg import Point + import struct @@ -37,14 +40,26 @@ def callback(self, data): # input array [x, y, z, distance], output: dict clustered clustered_data = cluster_data(dataarray) + # transformed_data = transform_data_to_2d(dataarray) + # input array [x, y, z, distance], clustered labels cloud = create_pointcloud2(dataarray, clustered_data.labels_) - self.visualization_radar_publisher.publish(cloud) cluster_info = generate_cluster_labels_and_colors(clustered_data, dataarray) self.cluster_info_radar_publisher.publish(cluster_info) + points_with_labels = np.hstack((dataarray, clustered_data.labels_.reshape(-1, 1))) + bounding_boxes = generate_bounding_boxes(points_with_labels) + + marker_array = MarkerArray() + for label, bbox in bounding_boxes: + if label != -1: + marker = create_bounding_box_marker(label, bbox) + marker_array.markers.append(marker) + + self.marker_visualization_radar_publisher.publish(marker_array) + def listener(self): """Initializes the node and its publishers.""" rospy.init_node("radar_node") @@ -62,6 +77,13 @@ def listener(self): PointCloud2, queue_size=10, ) + self.marker_visualization_radar_publisher = rospy.Publisher( + rospy.get_param( + "~image_distance_topic", "/paf/hero/Radar/Marker" + ), + MarkerArray, + queue_size=10, + ) self.cluster_info_radar_publisher = rospy.Publisher( rospy.get_param( "~image_distance_topic", "/paf/hero/Radar/ClusterInfo" @@ -149,18 +171,20 @@ def cluster_radar_data_from_pointcloud( # filters radar data in distance, y, z direction def filter_data(data, max_distance): - filtered_data = data[data[:, 3] < max_distance] + # filtered_data = data[data[:, 3] < max_distance] + filtered_data = data filtered_data = filtered_data[ - (filtered_data[:, 1] >= -1) - & (filtered_data[:, 1] <= 1) - & (filtered_data[:, 2] <= 1.3) - & (filtered_data[:, 2] >= -0.7) + # (filtered_data[:, 1] >= -1) + # & (filtered_data[:, 1] <= 1) + # & (filtered_data[:, 2] <= 1.3) + (filtered_data[:, 2] <= 1.3) + & (filtered_data[:, 2] >= -0.6) # -0.7 ] return filtered_data # clusters data with DBSCAN -def cluster_data(filtered_data, eps=0.2, min_samples=1): +def cluster_data(filtered_data, eps=0.8, min_samples=5): if len(filtered_data) == 0: return {} @@ -168,11 +192,11 @@ def cluster_data(filtered_data, eps=0.2, min_samples=1): # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) # worse than without scaling - # scaler = StandardScaler() - # data_scaled = scaler.fit_transform(filtered_data) - # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(data_scaled) + scaler = StandardScaler() + data_scaled = scaler.fit_transform(filtered_data) + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(data_scaled) - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(filtered_data) + # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(filtered_data) return clustering @@ -216,6 +240,136 @@ def create_pointcloud2(clustered_points, cluster_labels): return point_cloud2.create_cloud(header, fields, points) +def transform_data_to_2d(clustered_data): + + transformed_points = clustered_data + transformed_points[:, 0] = clustered_data[:, 0] + transformed_points[:, 1] = clustered_data[:, 1] + transformed_points[:, 2] = 0 + transformed_points[:, 3] = clustered_data[:, 3] + + return transformed_points + + +def calculate_aabb(cluster_points): + """_summary_ + + Args: + cluster_points (_type_): _description_ + + Returns: + _type_: _description_ + """ + + # for 2d (top-down) boxes + # x_min = np.min(cluster_points[:, 0]) + # x_max = np.max(cluster_points[:, 0]) + # y_min = np.min(cluster_points[:, 1]) + # y_max = np.max(cluster_points[:, 1]) + + # return x_min, x_max, y_min, y_max + + # for 3d boxes + x_min = np.min(cluster_points[:, 0]) + x_max = np.max(cluster_points[:, 0]) + y_min = np.min(cluster_points[:, 1]) + y_max = np.max(cluster_points[:, 1]) + z_min = np.min(cluster_points[:, 2]) + z_max = np.max(cluster_points[:, 2]) + rospy.loginfo(f"Bounding box for label: X({x_min}, {x_max}), Y({y_min}, {y_max}), Z({z_min}, {z_max})") + return x_min, x_max, y_min, y_max, z_min, z_max + + +def generate_bounding_boxes(points_with_labels): + """_summary_ + + Args: + points_with_labels (_type_): _description_ + + Returns: + _type_: _description_ + """ + bounding_boxes = [] + unique_labels = np.unique(points_with_labels[:, -1]) + for label in unique_labels: + if label == -1: + continue + cluster_points = points_with_labels[points_with_labels[:, -1] == label, :3] + bbox = calculate_aabb(cluster_points) + bounding_boxes.append((label, bbox)) + return bounding_boxes + + +def create_bounding_box_marker(label, bbox): + """_summary_ + + Returns: + _type_: _description_ + """ + # for 2d (top-down) boxes + # x_min, x_max, y_min, y_max = bbox + + # for 3d boxes + x_min, x_max, y_min, y_max, z_min, z_max = bbox + + marker = Marker() + marker.header.frame_id = "hero/RADAR" + marker.id = int(label) + # marker.type = Marker.LINE_STRIP + marker.type = Marker.LINE_LIST + marker.action = Marker.ADD + marker.scale.x = 0.1 + marker.color.r = 1.0 + marker.color.g = 1.0 + marker.color.b = 0.0 + marker.color.a = 1.0 + + # for 2d (top-down) boxes + # points = [ + # Point(x_min, y_min, 0), + # Point(x_max, y_min, 0), + # Point(x_max, y_max, 0), + # Point(x_min, y_max, 0), + # Point(x_min, y_min, 0), + # ] + # marker.points = points + + # for 3d boxes + points = [ + Point(x_min, y_min, z_min), # Ecke 0 + Point(x_max, y_min, z_min), # Ecke 1 + Point(x_max, y_max, z_min), # Ecke 2 + Point(x_min, y_max, z_min), # Ecke 3 + Point(x_min, y_min, z_max), # Ecke 4 + Point(x_max, y_min, z_max), # Ecke 5 + Point(x_max, y_max, z_max), # Ecke 6 + Point(x_min, y_max, z_max), # Ecke 7 + + # Point(x_min, y_min, z_min), # Verbinde z_min zu z_max + # Point(x_min, y_min, z_max), + + # Point(x_max, y_min, z_min), + # Point(x_max, y_min, z_max), + + # Point(x_max, y_max, z_min), + # Point(x_max, y_max, z_max), + + # Point(x_min, y_max, z_min), + # Point(x_min, y_max, z_max), + ] + # marker.points = points + lines = [ + (0, 1), (1, 2), (2, 3), (3, 0), # Boden + (4, 5), (5, 6), (6, 7), (7, 4), # Deckel + (0, 4), (1, 5), (2, 6), (3, 7), # Vertikale Kanten + ] + for start, end in lines: + marker.points.append(points[start]) + marker.points.append(points[end]) + + return marker + + # generates string with label-id and cluster size def generate_cluster_labels_and_colors(clusters, data): cluster_info = [] From 44864ac17fb9ad6aa74dade9387b997608ad0f6a Mon Sep 17 00:00:00 2001 From: SirMDA Date: Thu, 5 Dec 2024 12:52:48 +0100 Subject: [PATCH 67/85] bugfixing wip --- code/perception/src/vision_node.py | 48 ++++++++++++++---------------- 1 file changed, 22 insertions(+), 26 deletions(-) diff --git a/code/perception/src/vision_node.py b/code/perception/src/vision_node.py index 0e6a03cd..abbe52a7 100755 --- a/code/perception/src/vision_node.py +++ b/code/perception/src/vision_node.py @@ -356,12 +356,9 @@ def predict_ultralytics(self, image): c_boxes = [] c_labels = [] c_colors = [] - if hasattr(output[0], "masks") and output[0].masks is not None: - masks = output[0].masks.data - else: - masks = None boxes = output[0].boxes + masks = output[0].masks.data for box in boxes: cls = box.cls.item() # class index of object pixels = box.xyxy[0] # upper left and lower right pixel coords @@ -369,17 +366,16 @@ def predict_ultralytics(self, image): # only run distance calc when dist_array is available # this if is needed because the lidar starts # publishing with a delay - if self.dist_arrays is None: - continue - - # crop bounding box area out of depth image - distances = np.asarray( - self.dist_arrays[ - int(pixels[1]) : int(pixels[3]) : 1, - int(pixels[0]) : int(pixels[2]) : 1, - ::, - ] - ) + if self.dist_arrays is not None: + + # crop bounding box area out of depth image + distances = np.asarray( + self.dist_arrays[ + int(pixels[1]) : int(pixels[3]) : 1, + int(pixels[0]) : int(pixels[2]) : 1, + ::, + ] + ) # set all 0 (black) values to np.inf (necessary if # you want to search for minimum) @@ -458,18 +454,18 @@ def predict_ultralytics(self, image): width=3, font_size=12, ) - if masks is not None: - scaled_masks = np.squeeze( - scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), - 1, - ) - drawn_images = draw_segmentation_masks( - drawn_images, - torch.from_numpy(scaled_masks > 0), - alpha=0.6, - colors=c_colors, - ) + scaled_masks = np.squeeze( + scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), + 1, + ) + + drawn_images = draw_segmentation_masks( + drawn_images, + torch.from_numpy(scaled_masks > 0), + alpha=0.6, + colors=c_colors, + ) np_image = np.transpose(drawn_images.detach().numpy(), (1, 2, 0)) return cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB) From 8532d6a6ab1c40ad986b020dabae261a29bbe030 Mon Sep 17 00:00:00 2001 From: seefelke <33551476+seefelke@users.noreply.github.com> Date: Thu, 5 Dec 2024 18:06:34 +0100 Subject: [PATCH 68/85] 490 remodel acc concept (#516) * Research on general ACC implementations is added * Update ACC.md added information about current implementation, new concept and next steps * Update ACC.md fix linter * PID Control added * Link fixed * Update ACC.md made proposed concept more detailed * Update ACC.md linter * Update ACC.md * Update ACC.md added diagram for presentation * Integrated review feedback * Edited graphics link --------- Co-authored-by: Veronika Neumann Co-authored-by: vinzenzm <73160933+vinzenzm@users.noreply.github.com> --- .../research_assets/ACC_FLC_Example_1.PNG | Bin 0 -> 132699 bytes doc/research/paf24/planning/ACC.md | 115 ++++++++++++++++++ 2 files changed, 115 insertions(+) create mode 100644 doc/assets/research_assets/ACC_FLC_Example_1.PNG create mode 100644 doc/research/paf24/planning/ACC.md diff --git a/doc/assets/research_assets/ACC_FLC_Example_1.PNG b/doc/assets/research_assets/ACC_FLC_Example_1.PNG new file mode 100644 index 0000000000000000000000000000000000000000..e6382981d249d3d9d81f0516b55f7c92b0e252fe GIT binary patch literal 132699 zcmb@uc{tST{|Aglwz7s~8w@I03)y!@wn_$Bvm|@g?8~6YI(EqxMUAl=`&MF*ear4- zAEAaJ!|;66Ip1@B&viZjJ%4mf_{_b(-}imLmQT!GeXWbsSExxyNG@ta)$fy#oa-PV zA$v)A9{3Gsz9~EKLF#p1OO>Q-fMWyr0py^fr$RzfnMiZ|h#dHt>M7LJi-d&s)7d}L zZub&95|Y!m+UhC~{4BrEQ8g0{Ta->3=Nc6n4}6>IX5^m~jp(smp+rQgOE7(uX1%v6 zUJ!j3QJ{WZEk;7nj`A9!KI*()Q8?x+c$;{9I{5kM$V_poWpIA&b?|`VTC-JRcfj`+ zrB7GpH(Ta+4xCZ=!|&aVAQ}|x-=~dhDil{c6>Gz=N3JK`K7YMt?cc?A*6?XRJ)6wuv_c&x+F+}= zwBHkJ(}?)zRVn<29wVJHH=fjB(WXQ`H5|22R;OrIdjGDFyP?3NjaZO8mE{ ze_CO)9-X#0OPlk*()~E-+o_gM)H`axlMov~U`-i*gS}u8%C7?AK`x=+f=Y0fXMM`ckOuNyzaM_W|Svo%|2w-I;|G zv^nzPvw44q*1fC44F9w~j{031h$a%$uSDE1$QCMZt~%_JZXG@*Oty)Hz%4LgJ(`Jf0dq$rORj(%4}r$b2Cb`cJBidU z!dJ^fiJN@Jdvy5m3GhY5@y(RHW4qnAqQUR!lkV|cB4B}uebTy{vvcbOhbMG*I5DI~ zW-0FGou-_ozn-(d5)D1<>vvGx&01YkIz3cY*XOS1D#&#nY7M!70|a+9)d^WCKfn-zZR^c zTJx|}Nl67UZ1`6EgxOk=Nc?{mlP)_IOFcCj^^W>v;q>G{`mC4PXT9mScs7T}7!lR( zu9#NGiZqr?IphVuGJ=`DHMI^Wf0YJ%_htTb7t%_< zI_Rhiwk|C`iy&F(o&4F&z0iDuFL#HTdwgE)WHR7j^{BKVoK0wmatT)(Fw)cr`K_AK zSJ`fjj`@ujnF!SWINb$mq0*t!%C0N@#ftd%xMX$-m9Gpkb~NHwB0**rQfzM))@+{Y z(zWi_mZxd6BR4QB>iJ5`{;OFIEEZPY!y4IVU$eiFS?}?>v}q%~RV`Dm)8wx$P59}r zZl(0`O`w0Z{!@LH6U|3+J8ordCxmN)9lf>@H9iGVEZ2S7)^Y>6WU~JWH+5d|>zOb{ z7v?eQZ{pn?hGgq+Gb|fH6-zuF;0o1V&^IkEf4k~m-(sbYcG^Ox(6N_H>=h4Yy|QzB zr{B{@oTI&+->}`ddEQd;zPnl4T7ULrY14M&5^u+}yU#RMdV~S;=>Uj`Ci+h*(aRMK z#J6)WqSQjr?ja;|HpkFmxzNo(Nx2O5ZKLj<)9wS(n496Ys*kHq)QoZoOI3X$&gePc z8P)rA3VTCUcVs7GV^Xaqi`kdMDfxQcgE!5x51Q8$MpfY(`8{kY_fL-pPiKR^G38wq z8i^TJ{U_HH!X5cL$ao?TzQu})2-Wt9G<}bRK5fT-7%!7<+0e6(eYX(yotISb^;6Yq zARwf6fb`hs#5y8FImWK7d|rCWE+riLbk^DICxaHpJy`0d@NnS;ANA7xueOPgV};Rv zm#DbtW(Ady-CCSJ4-izQ5CJ-YESD)On;8C=^N9{KA)@Q2+(6X#e?XQ!^tSn+EtXRg z_;DZsNW~5QpM@;%`G!j`{O01`?;`pPP)kA^!cTcwpImBJqQP-|;Fh*6h zt_ZtdQ@;rn1Cye4%^CuLy~P9;hhm(JHoAq>Mmx_)xiXvnU|F{K(FSz&R<Sj`RwuZOxAK!8*bn{A zAHH%fyM~;GnUVj(G#NeUPJ3h|f?c!h9#bJI+?2UWnw$|R?+`x=e$ZQ;>^3e6t!Oln z-1EE<34vYV#|`Dy8_)4iZn83g+1;Bxs!s@;8RPP(axS&L=4NA2am%O>+_RP? zT#EG6wZvIWxnAiUG67o{YQ7eN%pD*PGH%^eO@Mt2>_KeTYaROJ4fiCaY<)`@WxyB8 z;e2L&RCq0Rf@-WRdhQ?9ws6-^?#}24*FMPl!RGwdqP4enB~RC_jkvFsw!*;{n2;ww z*5lPh`9u#sr#u%ml%Sl11+Y{LZzwN{HQ?>PHq`pC{Zd) zGuv`pEMg$`{YuBNwqVW}hxd?5e>eq~Nh{wahFeE2Db@$n%RQfZQ&C@!w(6`*SJeGL zQ;G;iAuk%y=BK;px)zkV*U8};>&Q!!Ai`*#o4(9SD(<=EhAsDziK)-LThrF7PqcES zNnR^dU(--r(**<35hPsVl^?IW_eeeMP#PJc+l!UreGE5V;k^R;>KZlgJ*u~sVqJ7W z`+R^lO+pF}n_t=MV63g~0>Qc(tSR_7Ri7reOl(-;iR2!YI>Owfz&)6kgGYFoY)3eE7aU|}M2)j$-jCouw%&a;+59euS4QQ+82O|9^NvN` zwPd!So>(-!xcd&XE}xDoo`3*y%freco;H9&kD^iDWs?(}C50=RHBQfMHhgNvtgR;x!;sjET8` zkEv9xV>N%;@whNv>XiXJ4LN72UYw)yx)wou+1TzSIFL20ir%Ermh2PzWPFUJ7;UP< z4Yp@keYAVXZgyYfONj`V!?6Qsi+Jd)M|WClQ7rb3Rb1h-<|R)1DwQ^f0PDYpqQ}Bi zEb4*Vli1XD9qS!(bGX|wG(Yw>uUzHB$Rf%l)OG3)C=(t&xT89YDbp>QRyl;VnJnsC zBdxaDbI>T<+w2wtC5XRu}X4^UC6 zdZeM#3XL?9?)-G;vS~@|xEYAKAl;#+fhp-S2xhSl)^z2H6Ja1R@TiaYtL7hq0 zhL!ZFWmBTs7ne!?oA|nKi5O&?R0??(pE)!~9`glTNZ|7!Tx3hUrzVX(}Xr`a;9YDP`ku5cH#*dt$SkgYStQ-#4Xs6pbI(Y zcxX(|-zRklV zW0JvFt~sYzlQvtMpTPLY54SbUlcZI^BgMgJi)2n-HZ!wva+x2^RcVV~U%reqVXpCv zTI5wqpjo#lzkqz)Yk2;febgmKH7M$3lQi}N?HqgvOcQ zY@+(83kjQA_B_$Byz#W}y4K)kf}TH)-@)F5?VS!GOdeHwMUYaQ$Vn5CWDTZk9E@pmfPzKonV!}70~QAx3VdR)&srT(xdZ2<8?HjaGq+9$j8 z7(wDY(Xl!46wxjoi|tfyMg!3;WpLn9lrBC+J32(*GGheKpIZ`R%)O4%d0JN*@v3Xe z38)&()v8F!uIu;O#gV?)@Ki^3vRHbPVH|smx}_|_+Epc_bercKGyQ8w56Ql0@G6UqRI_dqtr2TtoepY{sv+H#7m1Zn;f30>$*Th6)3~k(sOS6xv z66k=UP+wt%5fv%ohf^1=Yw4&A4I;NpXyeu(U5N(Jy|G`w_LPrG8D&J~5?)0hPhyE=zV_5A8)SySf83vpWQ~t&8~)i`Ng&_w8~|y# z7^5$~=Fk%`8NRS5q&2z0nsTjIePZmzYY1We%6mQdIO)%ckd!NX&)tSE4pvT^E*{w- ztR*V$b0Od5Kr4K|zA4`^cNQe8(XQCRblBPIXxdZ%M{H?W*!;~n zxF<3LLr(^=PFd!YnGopMuKhd_j8QwLcz>*r^1Xk+mC?odeOeVbEswTO%1Z3>A$~RmMo-_G6Y!RA@%#sCo^RRyudbDxEfS!5z^;hlq1zBLW@05{F@5 z8qRm9%a;!EltN3I;h>a;aeutJ=Q^oPRNTy+(xBy8uWI0C8J#UZHWe9(D}9L7@h^Gd zI*CCW1UJrl_N4`Mu@|Z(puPBD9;NKB3n`*sHSfv15j+iZo`!rKARoMH79-%S4&z+0 z*EzCFwmwWIHRYN1F4Ti_R)0W->cy>hXI`dabZKe}fe6`yO9(wIZbEA~F}810R_X!G zkj&<>Nm@!K5H79}bS$7H#}?OZa#29ECw6;J6z*o;tCh|8=|9_%qhJTzGW=%MU+y+G z$R~Ot<`GXRbLq=0JJp`r^Y`!8LnX=JzchxT+9|tIqg);~Xy8EGy%j4HPHCqoBSGY6 zY(%G{pv?`sjv5CJ*PT6_fcjuD^W$)7)eo(dWQ;a=(?t<(Ds7GP^n5BUxLUot?(Bk9 z(U&HQNIKN)#`>%KEt`vG!xk6zmnK`becrlKN+lPRVM-RQPPR8#B9l=@iW0mO?r=@j zi0{`w^}b^^9b8Yo*kJ0vKU=!VaBGEEpO6x?WVsR;o*YQj)Gq}$4np9b%WI#F0NCRR zf)lqEa@gtn&@6(}OZbhwP5Xr7WKx!571;*c1L7n8``P28eU0*FarB$qkrtt*9#Zd> z2hic7)n6p~vB+{u0`)y3tK|&&qz6PPm{>U%ff(-|WXoedZSM(Q46)~}qiof_;8S~X z#w?$qHYu+$K*ZRr2f-CD$)fua?4Qf0dAuils6KMub=3E8R4v&08_9c($30&!M=RA#XH&rK^b5Ff%P7Up&%v|LiL(YO5y(6 z7r!~0xi^m+<-2{>UlbP8s<07yd~uT6hT$^)XV)S*i%GtV8Z$^p3+$#r{a5AvNJ=wd z^yde6w{NT32vs{6AizD>Gs5PbYK`<&(CrJ7Crb}ZVNLXWMW3Z~-SHY^EBrsojU5>7 zt4JqbOVX-A(emDiz9oY>_ZQ0eXl%}_4YowDzr|QXQDZfa$!RntuO)NTFycHWzc_Ml zVU&vO!7@B9$o8uQUO292)`Y6SCRXOhPuqP24I9#Ra<7-3NKQQ(pFEv; z_?Ms@A?yaP=d?R-`|V*E-s6kp^w{&D!ixkwC57Fr!5he?y-C01bunU5gn(`;QgOhs zP8&jSA-Bv?YwICxFmgZS*@h~EV}kkS0}7R#adWwql|owC_L56S%&IJW+i* z-ojK9`^B|i3h^kY`|`do78;VR?0>SGx6u3}O7sSDYT51RW|doW6@$Pn8;)1z6<1ss zdy3R-aDM~CF`WRCqFu2#e0h}=-VG&8>li*=Yg)G%Ca?Et}Ysysy8X*(P9P2A=8sC$Iw5MPl z^w(7+M-smD>f}PNGP>GRlPbp{NbxFg1fxCg4P4brmLW|$vw3)ce{F=es~RnWUI-nX zO5l^hmTnV4`G~}EH6aH@R4MOAC|W9DBU8Rd@3iEmKQEHNoK^K^qb|+AGyOG+GTCUa zoQg7%$yDVsDiy0`cSR*#I;SGJSQqjzc-fsD-C7_=nC=XdPYusZd7Gx_e~qa}&3Yx~ z7jG?8(I)muN@76P6CSG+#%Ot&=~jIfjCGr5YR3M$j;rxnX5>@-(+^15X}7q$Bj=VU z@C3b3zI3~IbrVSe9SI5j>ARwhZXY$|7z|T%p^x`oKLjf8xXT=5)&Zh9v-A9GIOV6msr5O!BSwN}dbIw8 zpoP}VR8`|_9!{TpFyv%21A|UH-M`Wt4cJJLV31Mgp_bQLL8$DmJA6oge4tO3;bN`To0ojgf zL_b(BJz4wQq2mhz*bnwSNQ*WNNr$+KE8XNnv~8~F7$h0^sFnorhE3~)(0h*M;k+y` z;xNynD2bKAt-aIhQ6hEZzDQRh&%q!mTpB%Y0_?wrp+5ek*0j>joA6zeR z{(Hy%hc@~5i+@9yYX6zO|8J(}-zfcuno0QgEc2%paqs`}Sl9oqrQrWG$&|KZm3XkQ za15Z|ZUAkvBPl)mRBd;%?WFdw?ewTktIY2f2Wt@kx77BpWLV7~<1*S@xcnBwwFdT| z2XY7f=T7D^-Bo=AEg*_G_#N{?m4O_?K4KzNPMAmTyQw>tktkn(#OCzjy;4H*OW`+#=CxYpz6mPZ!_F{ryYw`=}{jp z($p=41oA9mHXhJFN+E-BpK+ejJAU1Auj<-}Tm5GsKc$H%V_YOy1Uhrjc1q-}uFO|h zjwRU`Jfn#Y+bI<9PRFf(u^+MzXdv#-NV^A&X1|;tj_65>rJ{+%onfH%5g zVZVFGO)FZQnj6EsZK48t3K$$6&#g1qNC2r@`b3Z{C)4!bxDykGT$ZVpcr>bm<;4AQ?C&h zDU_~8+L&}?1(EN--WE$xKA`oinzRg*JVU~}ARWq@(J>)cA}g8(6kc$L`0eH%G#8f! z2vD7bGTnl5lQkc%W*c0gO0QF_`mEp`bXiQ?6T|c3mb>34cIpmEnUS)#s*SY9pbZ@> zC#e~iY6&*{C+?GqIBEamZ>()sm$q|uf*gRZZ{D&3U^W_$#G}^^hPwGdTh3NO2W%O= zYI_+LzEjE4jJf}>j+@*KT#A=Y&&R;@&7PnJr~@XgLWz&#B`2OJp8QPA82|PYgs+k0PM`l)TaY#W^zhEQsIrd;`}AsdU&w$G49=$XRd9tT2qZRmA%P zoUkyHE|lr!s?T_tZ_qDq&)>DPO$IMqmK(2AGC)ui%LiP`we zt@jDz^qGBq*DD>;P*0|wPgxf1&p4$sJD4@s>dn=TvOI#E8s-rmP!WLi_^GN_xO{)Y zsOra;!YYVpI?hbtjmY*cholX6N0C=F`5T+h7dE1ewxp=gs@s-_y*e`(g=sD(kVm|O zZeh#7;r8oRL%I~UpR?{si=sh)(P)SQx3l84mbt=Q+|yR!1Ir|(2E?_)BuShdJ1S^Q zZALFLDZ;DOSt!fNaNWH98FFQMMb^hq>rj2>oPZd;n0}4!v;Q1leMho$bMh3%-M>! zNAC@Sou*oNcHHWJe5C2Cg^IChw5YyN1ZeRLEoPXd{|aul;lwa>kTJU%=SN1QZb=^F z)IOQ0Yc(Qx->5e}-8@HpzkuniFZCICMl47ii@LG#RuM#ma1-B{FIX5DuZIWqT%{-2 zHII0BK5MDMKSCMyMxPj>kKI}iS3PrrzFol;G!48z*J8ZjSJtSBF=1auZrN?h`VWV? zdbAyn`CR`G!}kyX$8?9TR>UgbB$F2HW|W_yz4nB|pyJj&#!``18d(LM?<i{9N($x{8W0T_j(v4@KeU&G5kYSl)(PrQ&!~Ic z{r8;DW-DEkGz35>J01g-qNP?o@&TSeOR31955=qx-zP50VxvKPi|9O>F9@nhWNaWg zZn=C8`!*z(sII=3MmW3_)HHcV&gL|0Fz8*gU+i&eVY5DPhu(`7{>v^B)UbeUQPfPrDn1XM zJCya%QjNQTw1W3G0h;#{v4gddt63XU>t09xto>>en>KEZ_bsP-TfycXbpjBYLyCt8Rtqpi<2V1M%=+lo z?dy1+MUr)sAS2DT4W+d~8{37q@) z9Q7^=6al_VP5Bbk4Tpf*X`Xg9sfq*Zz+C0VNbD^t0rCR$6JR6S5rvH3DYDiN6N#>a z$G1}tAs9qY894Zi?{On7H&Jz#rddwqT;a!{UONJiQtOi_m-UrJFQY&3W!CXO;DQH5 z4$-`5_BU2={Rw*>NM1k9`&GbDw0jz$5%17%g%IBfN59N~Qzav$JAR&tc&hM{=oT!y zE7KlLCpjLI6_jRAE-D~A4aqcTaJExcPPo;rlRi(FsAJ)cF`pz1QBCt^8Y{lJY5-}+ zqGkKkvY&l@^kP-m-Cw7Ny?}=m@>wPrWl4Fx0ZN$A$=H*$d7pd6JR=HydCUo2y;jYi zXP^0ebwZ+E{U)#$7@QA>If<@E6(e9BO4k!JoGK&W0@$s+*tFX`; zsLpzrFBnE3Whk`e;`W>0%{7h|SB((cv~>mBuJn!W+ldMn3b}q8yNFd&Tz>0ff8}N_ zUQ&_1MxQtl18Ne17Hf<6e+QT{`}^86=C;k?uds--Jt#vqB}aVOQrpTq+2Uejsc6fk z#DVqlk`%?5XW$p<8%p5uBN@^X?pmYz5tBrS! zt@}7CC#4!(J6u1W*wq@t)+o;WpUvJCQXg;9pz@G>7yc#07&%Q3dPqDhKP8k`k;T@7 zy%3-xOp)>|i+v{;TCsRRg}GFlOj`vRHV)IUn{>)eQzfk-;R@f|HxrUA(@>|E?5J~| zbxs@Z3v-F8Wn^8hd0sV#+}06ku&drIYhq!%QQCGrx~cZVN&%seA|4msIG=B%Ts3W$IJw z`7Re=Orcu6so|Gyzst$pdSGA|A2e3Y%Ah%Glg5%&VoW!#cL>`-P!kh6`HG`K5?U-U z-8ujsR88RUqJ4Bv8e$MK{ei9-#nGUmT4U6J5mva%+MPtXRp*2(uhlbSU~7C{lHz0T zyka=lh_IGbIZeU=dc4Z@Fhzc2ssh!Ih*1BMSlMZN>+e^!LJ{Gu5>)wR-U$f-tMe}l z6*u@d!}h`Pz4)8~@FQ=v(^r{}o8sWt%W->~H$4k=rr+xA#fpsZ6X|6W+Ow^H!k%n} z_UKsNw|lpZsi2AhkF|tFUmpz?AjPQ9A#_t7?9tszkd=A-x^cigg})0aE-0FEgGRXK zF3+%cntV?hZQz&o&hr){#n_#I!yzi7K^-RC!m!Ma7xNV_;7eqXW8BNZF<99d)Kj3^SGD znTnpNW`k&&mrVsptHASE7eJ%%1XJ2R9D0G~&ba}qW%`(lQeX4U1(jJ$XyAw!GCrj^jN6n)&`u?oQ;?=;;Dce3b$E+%K%&C_)k&)TajMD+y_>M28l)Z^rA)P7 z%lX%szzQ!FfM*3DgkN4}_*j znL9ay)gO^#Bmse05oSa@m5WgIW_W%jg4)FNB5Kw93yVV$s7Fga^)IeS^#;2Y#mM(F zzUyIuHCkN0m%uLtA~}q$8sk9?c_KrG!A~?e9(i)U(d-_-X{XK&GjpvSIlq!9*$Tka zRHn`uRdEz4P}uZFGZiIad_V~L)aBIJ0beQWG(yq=FYjoeoS!r z+e1&uzf>OEi5Ns?1;LZL?5GuB6haMln|_!?4qeq@k5F-Y^K~VnHDh1B#PifS)ai18 z!C1D)!_O0nvP|gC`l2S6!k^}9t=p5Ln8rcN75smQ0X`Ktxk)8~|E{W=0OM1t+vKyb z+oJ^}Gu@K7raV(_c>Apsv;lOCMm$^tnaCP=hMY2*d(1n&gW zkZQ?Ci1|kBVp0`%zg#utE2)IDukdwHax<2@s3>9B!+F?4YnS9aZDZ?Eqp+fJ9padw z)dq#cWHC&jM}595WgQ+eavr$k9^tigS;7ouA>NRQ#Jk&XFT(+?okAh8J?#c)=+57$>|}h) z5t&%VPPb67$G$``w~x}EW8FgY21P}(qIv295Yfn90)N%rPo!u`ONE| z3s#-fWkjgx-d)!T(9TGDkRm9V^caaB^dIo*y@NV}gD5K9`kF3Q@hHs{Y>0EdGt3Vn zT2rX#dXmo;i|V>Lvd@V#EMD2lq5RKHTaJoFm-i0r3hMZ4<5g%jB^(qe@U@rc&Gjdx zOpM{mJP=7L-*VI!SYDFd!FiAynR$3c7zZ1@81)a-U7jphD+o&&Mq=46O-XegU%?w= zjVNapP!W>h0ze#T2sqo6 z?m-B*2$pRh$^$L}V#K&siI_){Q`P+gX5?D)E6x(1+%Be2;z~NsS1L@u1f}fcL%#Y4 z+@WLe5Sp0&UN1Xjo5Ijrwri8E``Yg?w<`XTFZ6Ig5A>hoVGf9flKd@MNO<9*;avd? zN9-jZH9a^*usF-d2oN80W%8A~+$x3RcRPf?@#iz$rnyai0)1g5A`}l`*a01DV8~Y) z*Qag5#hAuO4EPfEuPZawIa*FOLSF69)UB(aV*VfGOdV5vDQX54=Fn<0+Z%EcHrY0l1$~wH@j->6|*t`+FIc&$P^jfE{dJ z?5?+*tkE|WBs3XT-N0r(_oY6@xm*#7ZrbUsAk(2+Z=^y#mq6;gEe3u*hM%SK1V4>${AlZqv}ocr%}yQeUqHf8c}__gw822u%r! zzRvlsuXiM)tKEbk%krNn0_4RYszwk3t}OH#7DoPzY}F)<&0tZI0g%#SJZ416*P&E9|POK6xl5>Xv-}|z;c=qk0b@zEY2wFMo04Buo?YpU6aP(bd#@evnLsRj0 z5yJ<#1S;}ISxTz(#O5?)kkqHh__QZWVV0SoA*JbWCP<09$R1rIeUj; zjb%ifnE#`+4A)13n~H@gUFd*HL(1kDvXy5e;VS>a&DOx>n*W+Bc9AuS&Y6PY%mADtquZ>!0v;NRla^xT%nO|X_?ettU#@L509U6j>6z|L zBeBX(vJP;RoX5WJA%(nJWyY4Tf zlsBfd$R6tJQ_^`B22V#l7?vKqIeKo3+gSqivx3a!9(LUcKqu#1RSso78an0FMl< z3wv2oy(vUn>8~OOh>YfqT;adGAI=2EGvf_uN8+AT^LKGh4fEm31O=9(uBMc)Eyaft z;q5|g#->Exe^pR5z~Pn0GrZnUfbJ2!-{A~%4;Eo<2o@qyyF-qIJtp^sm*~^C(+rGj zfww+OeIsqLvN8{DYTffJU)a51dFzqf6clEocPy!_9mynLq4T z%`g4&B-`4sU66Z{=RPz>`EsSoUGl>gxQhCPf<3rsq*|6_(s>YLrDm!^_4UiFLn%h3 zw0zD$URU*@@8l!FE>9_+ipM5_(XbcvPulPoM{Zafr&ERfDmO!Zx73d!Nh)N%GYM{? ztV4zI?m(4pn28<`qvx1FJ))pVCVu%Q#!7fZmLc|bM~Eu;F<$=(fLh@ zTwfEupJwO{fU@2=&xQG|%ejAmi85(obd-qUU_EI`8SC6lG7hV8M7!@(C?f5T;3_IznSDozIZzg_l@{8zojdVu`wXL#?|;>3G{V$ zm-iG?*9I^1I0QTrlJJIcu`?u3x9rQEewjVjy1lE;UXB9nC zolR5Q?mFimaO)$8ekOA9iqfmelsAZ1w1Cxecj_pG<&zg@Gg{TBU;@_WQ< z=ZK7cur5ydRRF323?;KgYLR`DdZhX=$-HPL|#=mIU zy%(-nH0X_>O-Tt+{)nf$A05=&?ISKz&`OFMr`;M3*@8Iul$7(`JTTjs$PkbyP38*+ zC?Btev|u(WO`DB9ue{dy@7gzH`zo?zhtymv4`XLVP;@$ z*oNnB8tiMC)x^7OJeQRn%mt4}i^?<&g4lAzA2Fs_CI}f5Yt@Kq26{D>oOaRC4;_sJ z4_|~N=V?n23q!gpB~aMwc?veHym|WhbBzTqiZuj+BlkgyVQCBTSIr4-A$Be3R zLx4$KNqkUml@(p#%jQ>Q-zOVqP?2odcrs(JR|rJ~cjU zjv4Oj504%a^X2^!k|TTuJ~Y1)l#`fDBNd&6B(B#|J&_)&eMsRnvh-TMHom!*$?5Q?SUL6>Zj3vpNG#%$?KEzYwX3V>0?u_y#EMqW`+ip=Nea zF%1E(Kg{pnpru6NQNB5HQC!5kTM7mP^(p%lro5H=b5`Vmh5NGl+WH}t>!6Wen&zJ1pD^9DiHccgw zOl96y!P?daNc`uxFl`A~4lkU8I}1I9R%}gBTD3vs5Se{qq;|&PIb1}2sSEJ`LtIx= z!;D?CYCq3czw#cXHsM9A(-vLQt~FYK`5>3(U|HS&xtasV{Oa@QglP$^KTNa~$9Q$Y zl^a#}4sb=DQbdkTIP94JNR}KFJE%4az58!o0l>gaNo9BoribQzGl$DU@PV*sI8OJS zgBnvz=fb(a@W)lG!{f1drK z0&Y6dnF`ek^fxa)9m>`HKRq}TWc^<@|ICzoffM?pvYX4yvNP=;Ka}_1+wt=R^S^z( zfNKqKwFd3>XB+CvylnuOM+ey{vV3i$|-7H-N=w?l?!2X&EbBf^Nd&vx zorIs+Ux9wGFw4x9Uc z@pQKN8*}*+k%r~ugvm2^?<#-j&zloFXXes=QVNbg)Of4*_W9izuHbV+o-90ZvaVJylKc$UhX-l`_2y*GZ*nwws9!wLJG)0 zWLn~H`*^0vmxiq&*E2EUW7bB5a5pflZIUlIeNCzX8)Uizd^2rvUm*wgTWbh3_e;?4 z6<e_Ua%rn!dmFky#B!-TQ$&3 zir?2(((!WFd%k>MY@RrL$1N{H^=`-2?ZgUrJ$C-zXrvs3ntR1H<{*zJ|z5Xu#qY1=s zr{%!yjO};~BrMl6|MTJ6w_LaXkGA>&c=3}7K=)lGOaP)SaBQaFf98bF@0w>>O&obQ zxsU%lP-3Qj=UN*WDPk-2%(}e_`0t(oVN<6Hrvv0O zT11WeMQ0-l4D3IJIs=9N;u306JO#u;sdcI|w615mc6|DilHEK1OaRxP2{qN=<*Anyn!Zi=%0&YyZ4);0x{VM{jbuGMasoS~t0<2@GMM@A^49`HJSt zNX_L@p|*co@a0dpmhPoYylN&`rYyDr4(xvd9iHEy8wQJ}h=_?`dtE#_>LZD9F& zb_`ZU2Pa26qBFTWz*w!KXWX2BGi2jN#;&x$(QS2q#$8nX7myAO8(1Fc|E-1vR{Za6 z?#mr;?Qd<@%~m%Ng1Zq)4=*zWmS5s)w(Uzuyc1%ttl*pLMC?5|!Qz+5{~27XAzq0I@qOzh9Xc z{2*Xc?OcY0=D!1+v6}AhW!+3k6O;>xsa7;hPJbnyewAMp zPs}oa2WRBsQj2c^hAf}mGt>6T^@>aW!0Zld=)?GdLTu!rjPh@ym76t-ZDZ8Go$}0+ zasD_;H*<4T+$*4yJlj~ZLw~&py$ZUm`1Z^-Ewh?w+uK_iIF|ytjqtlQZOeCzxb7pmnSO_k+E>PcI(=dQANFp}X(FuQ!d~!*&iCo6eR_91vq#m$w$* z(2`(<^I|&9wG^aegAZ06kR8w+rraNqs_;|1)oJZ-P1UG@QcD96-@QJryg(k~(o_(T zjYklU#D+wwiE_UqK_v;|7s&&rdo$y^zj4eIbNV7czVq2Nv?HKI%jpM_k=e!&=rIkQD}I}l=vdfwA5%}8RVXLbT*b>EF+0| zC36NqsU>m^#z4T+C1&V%JdH~M;J>mgspc3yUc+eiB>rObY^`}G>q!S~WP|55Gr+;9T$LId;Uy7|YwsT;%By0qdD z`v-lZZOsjU$3FW^kk=2SbE^ctPk<6{p%C}{3s z+`rl>dW$O=t_^(N0hEd8qMT>*4IDr|p6l}v?ZLGS2pYa?$c>BI_xo|gl=n-07Z7PZ zZOwBsnAK-#ZXllNJVFenx=L_|%6VOGaWjA3XL4ltE9}f_D!(fAyA|qB85YRdr04x? zr+WQ?Q{AcKj{}XZSfwVF%P&C7aVeYCJGaPGuy^rb}pUIY?qf) z3`A0(zD8q;*INw)+*#SIH>HjXnWhY9Z44SFF|XH@x(9Ao zU?^!&0qGhR}?Dvjgw{ zY$h%Lmx|SvNC8nq|M!55WBLF6q1LF9n+3mb!eced*XDkc$m1s0N-KRoZIxh}?{8{^ zZu@LRJgGoB115wRn{Q~b{sEY{54hoqrEq|6E6gVp4di8S zW@UjC+)y|LL~@njsbBv!pdAsftl7Q@^6gi?s2h6ZF=t9B_0F`ZuYwGDn&Ks>BG01- znFuQh7c=|s?*UkROqeTzj@kP%k+7dAYuW2zzcwj_)jGjcUZY#ng~j=?P$0^CihD~q zns2*FFO5&xe&WeV3ETgU9~}q?;#y?>o3K)ZoOP}NSyERo^pueVHrXq+_8S-=3%{{h z(XnD0UC9D$cy%oM?NZFpZo`6k+*EZ39q;yUuMro>@Yb{}Fi*X(Va0&`mN!RzdcifIQd?o90{EYK1sLRYQdp4( zFz+opZiY>lEo|PF!^UPZMTaE|&(VNbq&H(;e;yc5zf1!Ux>c{S`ADxhALK`A?YkQ@ zKoV;#aNA_zH8zka0Zf!%Vb=%}fR4n1<-4`N0&??GmDX&M5lABs6$2WVHQ=E8E`;e= z3k}|())qu<a~x@{)LtPLQF|97td#;%liPO`+@<)8y(B5=zf@8L3w6w|$b zY8gP@;FtixY}f;02R`8>o0tqj`1M+ro9nRb(clsuO4`?r@9Iw?%HB14`Iudiw0)?dRCk8ewx3~khCfclyg`*3fY_YqGP9cB8 zS;VlGl~@->vEeM2{{{yJ$ALrgJFv!yP5zWLh@CWi`6pocmlqDXKJSJJEkW!4c~&gL z$ufZ(P=jPysgOS7BCvdz!47zrc_3#jUKOuF7_vD++!K`{nW*~4qbl<6b3_Ho`4SvYY8W#&BnBS=GW3!|wx^n1AtiNc2 z!$_MVE)4sJhOiDKfIHuRH4pIq;#liasawioUyn9hhjV`ZU7Twm>$?yL92&kyBl7qZu5lYg(GWWtKcj&)U=^y5CXH=9A_+qqK*jcL-;EH+=6Ac*A7-v(Q1cWM2 zqvLR*L7uwyg!Gf8oE^9iB45b;0!%b(Q&qt}#^-cm)z%tAui1Sdov;*Q^#EY8{qbbZ zbAZ2ln$4Y%(On@q{%-$w0#7!MRIcMcSpP)r#a?rwCKMe@Oh}%7w4bK%Q19<+uHcW) z4ISr!^FnKu{g|51o$^^$jJZ=qedco`GapWkY7cu-qT5&$ZWcqAD9%Cuas&Xqt030GOyg zH_Yo{@7Pjy1%oC%(m8`f6pFT--X-5Wy_uHWo3?;-uEYq#fU%g?Sja#OCcJWcY9ebh z-ov?On_5)e=DSp4AsDn)bv)JsIf1PKY9lMJQAI)>65^tXzy{(V-;R|R@|==^`E;f& z0Xhn#c(zV8Jt#59o}0{-^fDF6|J@BY@FS_DU_;nIIX_-pIX&GvrNFw@?!*5Tx8na5fb+QXDq4 zr8RMe)zDb-QIp!ve)5ucPwb%)ZIIE_EgKX~%wVbF2drxR~ zBqcU{(De{{m64;{hm-ucVVK;rIWiAOB4G^RR-K$-_6n6-a5tGxE}l&voK4E2oGS&{We{bQ_^w@c_ya2I+ZJX zI1AbUrme_-mZ^V{`BoJAWt7r_|E4|gA@RY$4iCsb$EmP&_#1o|DfqU71W4%<-DS67 zN7+*UoMKkb*?N)}CHaeIYJFSQzhJh0EArM`btpf4e&7!(-w%OC%N;c5Y;DUF1nE?5 z&meu3g5qs^NLWT=K}Tb3v_Xkq;75svv!!G`TZh}*+M(}Lohj4?llM;29Xp4GJyPck z6rtN9TLIh4yGM}bIV2fc&ej&X06!EbPT0oiJc;s^+d4XsqwJBHBlHN8!T)XttTy-Lt`sIXkpWV(0w$5Mi*j>OXLh^g#@F$KDZW0Blb|QTsq{>m_ zB9-gpE7y`-g+cx`nOm`H=9fF#iM7uF#p>r@d8H9u!4Gk>WV38$D<>ebBn@;8NcWkAX=NwIFqL-)Ixya=aJ4JDC( ztMQzqtApUB@Gco$1 zO%Dwg`WCiCGTzOr80TnI2lREkjy~E__U%_ARaQqpe|&hyxgi?#nS4ga_sOSA)Yz1v zNyTxLC;sr>lgjm#dM<_adXo@Gz20QkcqN{nO#7cuR`Ou&U|_w!n9X@f7f{^D&C+at=Ge$W0FP zB{1KfkzJP>+0=ygDFkbz_AvF{`finIeHleMX>mKRd${_1CrP%hlO(%W;UbyY$69a7 zsI6b((4)nrCIRr6)RJ75*Cg}K`cISDrI0XmnkT=TlD)FG({7$pG;309h5H{ZU<~AI zp1g&{xq9EjbK?Re_2q!%#0HgT6laowLQvt=jIvQ*T9Ca#r*CsYrAqU(i|=!$pWI_6 zf}8#T_+(CfH9m42p|c;62@2={=aAnh!e{OW8&4k-O~XF#GLG}P`KyQz=LH`2eci(p zGQ>R!ve!=fD&Chi|F<;QNigHS3FgIIoK*aYF|EbC7>jevgrDbizftScl}&Rr5Phh(n4Zz4h%=U!xp!Q85ifdmjg{op znV1W=_C1@O(#m!2FJT9s6{9d<9g)*6DP)N?qs0chkCGZn2q}?*ihJIIh}YtVqD5Fq zKV=M)N&K#+Gw%5*EE+*7!m$o9DWl5rJ6gLNj))PBJhZQtBpcyw-UBjt7HmJ@jlwVc z4Hq&&&1rwcWOUan+=c3()$TPoK2~w~lvVyyW$&$4Sm^`pUYZ5WZJQgxqxWk^AV)Et zk~iWjZn%mURIfUUX=`7xtn)uGaEmlIw?!nG7_SR`XalB$X|zEZeQT`v+_|eJfB|!$ zRwegp<<^RFQRSH7i0wXrO>tS4=Tuul#~OYvU#|lTF)kt7zxZvo;6(%Zo<7q>C4ns) zI~AF1Ef`!(cXw|hzPJp!5v2ulgC~pXj^PiNPp9gfsFEqu4V@hq6W0ic`NFk z@+8JdvXAu6sul#EJa6V)j^2qEL=I%-l8kO}_UMgl-pNRxR;$TwSk3%VXL6x+U@B7!WJv6i{d0Z?o4i1=iQ zfIsi#ozo6>BvQDE9MU$v9XK+QR8NB-w_=0@0*w-4)Il-);;owjXSbJAEQE_th+8!- zq`aLz&IKb_TjBW#Kn;3^2vV2x2X<%89~WUa?Riq0_Jo7aWp;&_rxgzGB$m`_+VBqd zJDf5dm2=4;d^eOq#EPTLyzs4V`@dAqA9som?Z!!4lFzQ>tH2OpX|I^U~v{%9SeT=6WP#VSXSjf&gRdg zZ{ex>dxMAmf$~K+$KfRN`PLiho%{Qs0U7+q{z}#kC0MtM5il>aGIgH2F$o zfX~4Cq3{QoiU3CEyLVq#6aKA;Sl0~5iVAJ2;q>iQ0AfC51V^;jF+5~1VleY>t}(yzCeb`Jg#u;xPp_n(gLZxO;##mpP%WBpDW%O?^jf{ToSc! zq7Pn87R4PPMnpsfFM6Y42PKSGC)iL#lAq$8bsg7!rQQ$4A)7RW!!eLm9zCA0c-cuU z3$~d7j-L)?t-yMH%1N0~p^_aLLd*sF^R-wJG9E_fVqZVPAO~lz7slE@wIqu!^ zXtb>u+DU5lZfP3G`*EqpIyl&z;5sI+SY*Sd?#aaBjsJ?@ZmAse~ii zt%pMP6G^0s{z*JGslOR%2W$MCA2Lb6IRu;bUi#`QIE##(<&O~2&01d40qIkdE(m?w z4&4Q9$V5+T%~zs#ea#_P$Pj+NYTCI_zUq+P(xz&~89novA>Ud#=iCJ_o*6IYx^gdx z@VLW2o!J0a{kvWLH!hEc%@X-wOo+-pLBSd2dr7y0Q}&nDDXBcghNtBr?=F*W_tZUM z>YZ4@kttxx3Cw|jc||xl&S6u5vG5v+nQnn?iR&nxrL4(RzQD{9lIAZKAJuy(>4OTd z!2-Y6RU?UhECkk{z@GQE1~92>U=3u4nvs3Hla?egqDEETfx$Z z&1ssJL~TZ;0JoXt#Tot8qCci6aib0*jF@_IRTpDE=69tTiFhP0IRAH6@=>L>&|6`a z776pf5C9;387R1*t*8BX)M)ovq&S_EHSU2PcTUwG$a2#B-(5t>Wq9C#-c>vqjhVOl zLfpguw%c@xdV2q`s%JABN5OUp_tXvX!Ex%6vgBcSG>by7kI6l3wDGm$gz$L(E;8c3 z9(jupeJ^^aTv#cta51uQ%~aAlEQR%!u>Hzv7$}S1PH2dgS1T!$@|3-Tl$)FF?V-ed z#s&q}m7je=HTG7Wjie1d@V*?<3{tvcB>vkP9L{UVH@=%2Hw8x58|F{RCk0ihe>(YFfy%H4Ar#CZ%OwA zBg(?WjrdSyOB#`JLRP;9l)G&|7z+F8OV|0!SI~%wwGC6{)9uia_ zU|Yfud%yfrEK0q4ay9HGX=7#&k$|0C_)$E6O`SF3S_0@B)!YlE6&7)i#H;a!m_Yl`6Av?<)hg+ zfruwLkFs+zZ_q09NhsO9F9Wk4c{4S@&S07drLf3z3-R|l`U|eh^B(Kd+`N{~kPBXl zR>d}q&Pi|DUGK7iCq|x&QD-8l?=(bkH4%s7A%VP%EZK{nLy7XW+StriX^n+dlo zjeCJ9XA$%DtG5n0y`%@yUeU-s%Y`5b{MFx}@LMfp`qaw#-H=g&%cxwZN9czZod7_q_p%4D+H<5NgGB6xqA?zz4Um zpNJS$9_hiCAUuhQhY8R2CX1Tmve_matvL_<;;^%Sh=0`!MA+Thi zYvd8}Jx1dDgJK*XvTO36%i+JsE>TD}e;EFwSuse5D5=m=;f9E)UJf@1wBU1`#uQI$ z)15#ZG|a|dH>&j2#kQo)IgN&us9ib1yI+#3x6f$WyF<#>FbhyrO44uw+Q${mVMei_ z81d3H$ejnJPAQ9j!pKJqskQS!C6~9dbc#^|UHF?;h11qHbR8apXm8Zp;xwZ7#LvT8 zC6)8vE8K5$#+wrZqiC1&%<>1|4Kvbxl@Vk@aFpW7`z!A%Ve7%HI+YaAG*R{Pp)Ku4 zTHnz|>sgGS@TY_E7?8~HNzZG#!@l)&MpnEpp{6Sp0?rwIO7Iy;Qr5VgWKE3~^I7z} zz<9G7zC7$v3BSlHzz_oBoK9j zFaFp9w(KmzWK}rH0%IqsS#~;mi0K5UW{GTze^1EyDsv1S;k2QN+C$6OmR$Fb|8gAx zO^B|h788S7i%()O(af*~YXWJ-^$i{~Hob*zs(v zM}}`!$1Dz%yEG9DEr#krjy1C?--$Cpi`wI1a$O2X5Xu|5!BeydV&m=zO$n2iov0^9r(N&Q zY+3)?)+2~i)(@-Jh%*A6UWJBjM1e^5r1%LYNpmywZSkxsXx0&LN!%qt2{kUxbgJl2 zAWmq=ND~5nAJHL~lda5BnE6{C+HC#zaB@rlmw?sOZc*G%`cMy%7O#*osjepW^^I;hc}|UsvmA)eqe(2J9`)Z-?<(SY^Yq484_3xx+!>(vF25 z4qr9=;1TRgS1FdhALA{N_%kcKdb_L^E2F}vjYa{KQhp7q!@ds_<1kzui;MwPd}Vbz zu>tiltvn_s0m+tjwaDwWs3ChoDlw6Xw%sQ7wo9CVLDw3mONAgZljy&PR)JIt1qm1q zjKUnS?Hk-I-+OP#Xf}9vBI>ZHn23qG(C*#TN|G=Bhe!0Bbd*nRKanTlWwEjZeaqV{4Lp|5 zv5}7te_51r?O>tfPoV@w*QfUe+4Qm0DbL24q>As*`i+voqi^D$yZ3M{Yd34N(l7KE zULf{gj0XFEo;&VaLHyr~>0LULUG|VqSXUg1o|d zTw?|Xf+vvdFg=0~2DKk&cWOhSc*}t@_<=6kU}E6%fBAjXURT*fvhXc|-49MW(9^B= z`XnDDMPfvE9Ja{`Szpx8aJbbhw;z+)R0N`Hbl!(QscLfL6yauY{LJ}+mBaGR9TM`D z-Qc9Qg}v2$X+UwPZ!{c3H zw~FI2I{F;ZcT82>tMcaDeh@vZqcx^{#YvpYJZMP0lWv(xPD~yjG)q8rd*uUv;j;6y ziq2y`=P(#6TnJn-@9#S*No?J}M)nw5A;!_M^FYQdjcK(u4NOlpZk1%&gKl0-=hr95 z66kHfUG>Nd)~G(H916S@!rt!SbSXa8t@c-VrixU=fugP;HPM@i9)P$M<<2C1elerh z3;XhN#u9-yMpHs|TNc-N1^E^`>@qW&>HyNsKDVOWuUD#M_yc0YPrmvv4s>SD##W2Ja*IuB#u{ zI|Kc)uZ+Na;_KCH2E?a1Ql=)66?ErJ=;PA1URAjOU=m;i$!=?p@$yP!qFUjkW27Md z^$F!$B0py`@Z>^ranyK3HKS|HT$+BQlGqYNZ}?-Sn>>YM{q~_Ywd|w(&f0hogBuhA zZzowm-SZvs(MWhM+)<-2DoN0!8r2t0&XJ1VwgdxllQ;tb1ngDaTvD0llsN9Y)69|`VEqB%HA<=7v^2PyYlsB zGVEqG>$P=0q&Gd7@(m!9n;P+v>x;bXo#NzYaAFV)nlg94dcm2#SAxe9mYrErauGT_ zYIMlqR#tHgm0OS6l*@}>8RPD%%nd~{`y~}XGPJ3+5z*&|1A-PB_p>U8yp^<-8m8aU zC}XteW^KL`+$h}xOT~rAG~ym+1FwdTllIaTXimG}z_v+<=b!a61DgfZd*R!a1>6|b z`>~+rT=_dTqh_(>wqvc8G}@kxx!IekFUIL=y;Q%is8p@2GA;OX$I$7gRX2ek)urY)YgU&xMZ< zX%vVXCu75&vfyyytzc#r;Z~n?EtgbDw+hW>%FOnR-h{Do$bCw+IhMk4S<{yaQ8Qz5 z(Ng+FZ>*N$amx77pCNDN^Y8TM@h;jvi$#GhDi}!>9Q>%yEdKSvtRX(*%wf5h^xb=O zDzh6<&%PY5^$m0sg!-*}x^341&`9!9v}T5j!fr!3Vi2SOitn!;2=$`5MIC#X! zRvb#o;w051`Ce^HjI!CRaS8fqI%YK`CrT4@hBv0NoTnCFepDUNVI~#`{+u^?!qT5A!32b6nT~+7S9o5>ogH8CRh$7v85yTlrtM4> zwCpxbW0MS-ctaBgZb2C|IY6KADHgAW5j7>|h|O;{q=#R{#c*}$h3*=^T%M@+X2zk4 zW7scf*b#iX_>xA&7sR7CodT5n8B z>x>4E(nBJ{+~uA7KY9Nqethl1&J8!dWsxe@w9I^X=SL0CPAh~8$x4rj{N1MuG31fc zRVGB4+NI*m_AyrrZ)p`pCtsj>Ze}A-l8K?bH|e4Fyi+{jKPVC8-!Y9?o1K^ovylXz zRNe2N5|Utjw`{eVQM|1$o3+7P+^dp$BVEL{f24y-EqWD$XZnZPc$~k9PrMr?l>TbI z)hqGKSC{Eyan<>I@i1TkFxT^PV0lWxTSXC0ZcAVy}SYSk06NZpmGjrBlKU0RzMWHkkC8mh>$_^np4Q|2hsF{zr1z(cMdf z=z)5tm2hyjOkuC2muy^t%^nROW}7SW`Fxy|dW7=}pK9rjY2H}8MQwV@Q%|+t++9Ud zw;yBU_4Yhd9QFzH=DL!GypkG`B+1KNQ#p8U44Q59!DVl-uA=uIUz`|=r6mRO|D;Po zaFWH}gu@-f7rV<@q&!?nOMQv>K(V&m(FXFiX~GHlYVEx-vo(WnJwMcoj@y^X^ycM5 zf6VS~;fHZA#U5v5th-BnytS^G05uxX$?)M$OCOsQAdlC5l_tT?5s9mKsQ3b(9?Il4 z?rj<%CF<8@!Q$=@rR=Dy0i{B%$dd#bf0gqVe;HmW8rtgI91{+UGj_zG31Syah{|nU(!_RX#>O0`w+wRN)VuE$KG_xA7Ya3d(1 z#Ar0CgB?UsG##QQuZm+~8V#Mf6D&3;+xsSQwO)H)-dVnAwPoWHMV}Fw--y-^bl8KI&y+pvQm? z3v6aoZtBePV!43=n0ig-8NCxQ_vXtp`Jnbzgi7KWen$-K>vawh^{AY9b}MgUh;4cBS#IKj?Xr{LO{d3J_ZKi+@IZR5G#99|K7{AU~ZkKUUuud;z)23B}(IN0#lyDjU zmNnzw)Ij>13cbRF{*)@1roAn9+kHeyqr#wKRrfQEN{A|XpJC8P8)$n(P2*G2mwI5F zEBIS$u31om6DG|6elem*Q*k*hq$t)q^0yhyUpcVdF`3!e8Yc6;x3D*qA8jV9>56HW zx z+@tLE51|n_G}(Qk?MXaQY{CPlU%2H;od*ow__2bsKVs-54Cy8H5v>d>QAt9T{mM5<+iZAZ1!4o(gY)>D{UlJC(v@^yiD9%dWJN*ZFM({H-tv?=StYTH0 z*5F*{bGwnkcC7_mnBY zm-DT{TXYtLsy#WaJ*kpsB%Ly8!@vcT7IL1(UhF=Ph`RMeXdNQxCJIxCvLX2@tZsi; z$O6^IFe$z#CJ4*-P&RL!5KP6fMReSj+|2rNjZ1m;d&rm@5e0-_0PV|t|F93~C747Y zKQ1DGa%dVh9Ov*=VAWioHs@qj2muWa(>MDLpk8YC#N(Iw9aBq*k&WOt>MDe!Kd5_l#d@OJe%4oE?! zPKr8nxMoiX5`7QrVh#RH@De7To*y)MOEQMj){M zlWLqn_gAQz3h67vkb?aOkap$WbkX;5McYivC1m~tp*U9BN!*C64i$H)JL~wDhm`KD zs)wIUd5M-RZQhMIvpXQp*}~)4)HzvveB)qCJA(o*dBg(*&&FEs2WRQ1xzZb;3v3Q4 z18;kOHruKS&UTh45e*+CE~}NTOZ8G6l#=pEPV{{-HtM@7dTh^wPsUi&bg}ZHmp7X% zgUE17^E!voUa(i4VUok%cs6qG(HObUNVy3p>sFaqRvf&5unQ^aMBNdGj$x z5UT?yHJHe=kZ<=+w3OZ+*hCT>wDKd=M4nfxeLLNMAiQ-`Mv?ow2MYFBUuHx%i7@Bh zizEp%Bv45d1rmq(=zU+wH#_c6x6DfN@iByOZ%72uXrE8sJ59dpw-q4076>xfs+zBS zq`N^jo&2?iV}mQ?T&Bk_wG95P_{&Hy_?S!B&yv9bm-yEyqQt{tkX~Yko2gLrI5FoW zr$yK`{8qh7n2q-odPkC}c)-da$3btS>~Nz>nA4&ynG!kbA+BT=hl8Z|a{heKWlrbj zY%6NAzcFDD0DyjA4R`D#`K`FXrCJZhd1E znYd>&v46jEqHRmJ4TY0Rr6DX=Ab*^DohmiwK1@eq!E#>x=y=>VSGr8S%~EvI?0ltQ zcgt+sD|C0P0ZciW(drW(u$k%4hK9Kp@X?SX8hlTHHx>WwebU__@F|{DD|Yh#dfz4| z${gt}jpX%FD&F@08a%q$8dKDp)?t4Z?`Z4)qvU8evav{aE+J6@pFoZq-#=%YHs>(? z)$LZr7Uqi7R5(T^C!N$mc|EHhUp@wN-eybiXq|} zxE*aMd_NkZ366*dm5OxP60k^HcDyj@Dvd|Lr$(O0B`;-%%A3b^kAPrhRofAmOmn2} zN|Uq?-shMkR%zS!b%Y&zpQH;We4aA24Erbr1?4m;&TYOUrrZ6-9fDCUKE!B-nXluv z3{RC*l~wI~%RX&ai9GAM4H0pz`2ty>Xj+{k_?ZwlixY~f(9+9Bm>VeEG%XZ25H&fso+c}6E}FR+QkP42qf#*La7?=*50giYN0N?YSz~H za=y^Bx}Uv8Jtv!+(56whSsyu1t9nwNyz<4MhxwJ!GUIf-jX8$#>h#{Bzt029-V=Rd zA|tx;-sfkfjWY~EjGj>=gIb8tw-f@IPf;k7WMQH(S_HYx9 zE;v`uKsR(zoA!^`pVws#yVJQ1$K_?~J}#P5kr^rx_1%>`COJCyO_FO@eTzbM-~Re7 z`YW)_VSF0*iyIi-X^S&m7mJG{&c=F8U!*(ElK6T9Z+|*^ea4CPJGg=JY17&PZlX+= zjC`EO`VZRfX6l{C>3r9~=JS8Ya8Ts-2U&+DRVI6SIhu*>=|TYAI0xQR(NUDs5vNyZ z_}inrstqH%>I9h??Jsv8KT3M#Mst_YCLcZu+CxABy55+TPfr z9y`VIXBo&d$RI79QPg|qJ|k8=Cnr`4t>8jg3P!<}*!6C_N?|Ko#h*v5-UE*Xmz)Ms z?-cfBWBKh<)Ao1T|IhxL#-O&)30&2$1G>_!;Wb4Crk=pUd$2?)AYkns7Du3`twG%aNivg#;!Wo9|oyiqx75u4I!$6O(zqas%RE z545DrE!T(U40C5^D>pyB9eiIkWf^<7Qus+&xlD1Zb;Dcw9R8`@K*WE~vVZL3G9mSj z;JbfFOVz3r+tcS8_@; z-Ooy9EOfyC`+&(Xrc-Naab#@6WmNTZ^AWrTmmdqhbSN{SDG(j@U3`WHl&haBBPIiQ z-OJYbk7m?-c1byp4isl3Q*6M8`+A{m6wb+_6HZ? z!I)-Dg7Fk1xETyN#DVnH|8ShQcm91pjCFasOB=SsmcQY5jci2jKRomqhemaUr()oF ziB$#24Uj{xwsHT1i-@p+9#M3LrDk;)XgwBIM1CC^m3x*~`{ZmpQpFnn^ClcK@BwR* z|6wO0+@t^npwlEvM>-IlC)Yo8G6x9%Dh!HI|0WlZrTH;!pY>=x+e^2!P2T%7!_kxG z`(y6hx7M`)*(r_%RJ>L{8V$=w-D%kG0}7dMcn~kXU@7=%x3;VP+9GTraZiAVj@$dz zrlt41nb@{m=cu*3$a8DH8>*&V_^db^FJO@F#9u37&p*mik%So0ZU zx)G8PuI{# z?nzzoBNBl|%UXa>AClh_MJUS&0H9es&ys7f24CLz4qrQ8p{VS7>BfMHZx%1z_~~d}=JPa5wRx`3(js;gIXM zRyb^zIe+Ks`DsR)*gOEOcUv47?3!t%;wKjT2727S%ASb#JA{0NGXpK(CKEur@El)F zFZ&SC0XWAPbUcc7h?V_o-HQ|is}MI z0`^B()qbxG2K@9ykzJThdRlPSYyn;Q<`Fi%d;5Ez$0O-iryuuS7*MVDHDmAw17lxy z;oFpd1p(pUs+-6Nz}9&39YcD6|5-8xlqe+mma~z8P6o*tiFYXXCxYfSUwg_c+x>ul(V z#vH;881JNbiqMu10$9Y~1N(gSx1|AwTQazZlC-?v(T_ZsxAyhd znO-g61viT)(}~YuB&Imia~pb|S6ra?&&(|-T9E*F3LFC9R@1eD{jf1S168OKQPC`? zM1q!2K6CW4haO|>{_e61urTJPHVAtuZw1r^KajtM3bd-XY&A`_Eze*Au|Mb^8~v|4 z@iSqhDwHF-5^vL0W$N@r*!w#@v!`_<$OWg#p5|4i1)3PE{0bWbO=vs=@s|HtdC#-_ zR>&~&v?~aUGV);$$NzdWndzQW%NoAFSPCHfpVk0dHGaOoj78ADI`{lz%CKDd9$;-g z7bJMh85sr-)&&#q6<<%Z1Ko$pG6&afTOSe^O#>A*I&@!}te1z0Zl zA|#XP?#*DNj5#F_D~`y!4zTU#c7gQjJ|ab&%i1E>af#T*YRH(&I>SHjM{-Ey^OT`B60e^mIK45?DU-@n@fF+7! z*~G`p$ri<-Oyy_eS3u!N&{vm#y%QjS8%@)avA~R{iDR3fj{ws5GFgTi=&~`9kJ5o& ziMMKtjNSYL>#;yT;wfjFP5F5%03|=_Vf51W+O0IB=v`-dPuS<{O}ReFz)xRq~}WP~VefYr&9^Hc|>Nkl;u zq!$^Mc5LnN^NEYXL`aji*a30Bc)~q1?=fuWh!eKLo!XZ9&2Nv@1|}NAaE?4_{4K1S zKzRE9{rZXdOp`wkdRXN1KpY7)s>LGtkUfL^V1OW$D9-kLTno@s60v+W8eS*U4z!=Q z{mlBd_=B!dJ&<1jm%G4YlD#dvB|DoWzr@Q1>{4TK_%)#5;&m}xFfRms`d+L{*p2I{ogqzR^h0Jm)WBcNHOEskOK=5!(CW^H;T*moNLppfON z#5p|S?lM4M2VO7ZJgK}RBlSgm=|!OHxxuvFsdl*`c-V53OC;e)Nv_v!_08Q96x-CYB&Q>#K|Jr`=m zru)c&H!(V0!;CIib4X?1Attri^{~pS#OJdI3!1%eZ_M+R}oo>Nk53iME^)=Csn1aGz zb|y*5i$EDqE6ToSDO1`N4_Z$Lr;v5bY6&c0CzF2RP0~AAAJDK+3dNu z4w&F<3FmRd&P3FFU`fEH!)$jHNMVxse}A(26PZl-a?AqScSD@m7qUlB@F5)J2J61p zeQ?f9K344DhyUw|5&7tQfL6gwQIB%eVEJ9Y?<3fTkU*e9gg>mom-W;V)`62+3NoXhHkGIO?GiY(Jkk=L-zu?Je34rbGVGN* z!5FXuJJJN4vGfpNR{MDIJn!Z_&rTLbLd0iXJ`Ya)WDf9bKwZlN!ODw&&W6~lITXYE z-^ewf1INp+&)hlaM7!p&_4upcM~AEARV?Emdn4$!s(yuawy2{%pUpd7zVQc3R&M(0 z0kSP@i+^e@K?ySvzKAefkr9&QIf<0A~WE_G~U6jroB(ub~L5*&w3jazWwQ~J&3Tsa6SS>0u@nzu_c>%X^-h5eIkbbo2p zCM{ywyC3cYkKM1dt1o_t@d9&?jRp|nnR66eRo)P~9B9h0T&1fYvL9iNydb4^t|2BC zXM2{mejZ@*DcMp+fA}YO4H#KjwXg6DE=3#D(=gX|UD6 zUto^4VY{Q|O&k=w9fs-2i&}y$-q(+-Ss96k9e^{dCim&fS?rgFR&<5kY@UrUI0)Y3 z@CEZm(7PD{Sfm!iDFiqhuVcS7u4A=4)8MPgVo1I0fJv%lo<{XY%S1Y$&Nj`lqNe{L zF!BSnosG%Vd|fh59)vq2a-E_osC-iY4PCkUpkKavO3-dxMd$k|7mu(l)Z>GecYQr#iYnbc&7)y8!p@Q2H19{*0zv>G{v?nO*RNDJQNz=`>qm! zoXrPxA^j<7jxUJeIggnQp)RHGKl1LXftCbQ0@o}!xgzl~PV7CRHDF81HtZAgosfSF z!yFoEmg40tjwroT(nh$H>AEi6A*l#;i4ymS03neC#Mh^QhOEZgS;kwTrQCY<#96jm zv_lbEL1{8aPF9~KF&;aad=?p{+l$J&)+ykNofrBY@ekl32V#UUnb^Er+j%8ad1wK z#N-}Z<)Do+V+&4HZL?yalhR`IGF&rYkM<9GoHQXhRRwBsl!?4!%?N1VTc;lIcARUw zTYn4N$$0iTi#spS(^wPz%g$!+V^yG?u?yO?Ji>BZwXCdQUwF-$bTZmzcR7a=2_inR z=Ho=YC}A5t7UAVYk<`dOv>Xi6Gs(a&0u<7nBZcH^kKWFTCUA`1Y=p*;}64Q{6n$1f-#8Tp`0hD37F^~%g!7ZJWPo^bf$&{GeFM{mp4doZ+ci0` z6yL;O+Hi}yZ^FQK>cMfKWr$U&SHPwhF)`Z#zmLC|{1OGuRMS9jpt35;=PZ zx+bx?tp57PJO2+=Zy6TV7q)#%gCHG)bPXUNrF1t+iW1VTGJv$S3`oe(Ee#4N4HD7_ z4Ba3@2{J>MjO0+yp8s>-$NRh=_`q>+Z1$|#Yp=Dg^E!X0C}H_1)NJm1Kis=0-BqaR zK1ZzD?G{gU>gH0|5p6I_{vHeUUfe~HOy?EMS+2O3+m0&bU%dS7#ke~*=FLtLF*}o` zR^Y0-&}o}`H3Bdj0nSwFW7@{+R*6qB-4p3Nz3$~-onA;Y^_~F`Ey%yjez}sMC)l0! z(*gk?7&D^m*9GiD%hFblR>)KIBT^kjDpTS$t1FI9Ih^_L>_}CmWAQ(kX@2@E=*r{b^(Jlf&IjheeS7 zEnrmM!}_K+VB%wZ=Bd_yp$xQQu?2y9-TpLcq7wfd39x`CfAR7oHYDzAiPOXjJaVam zwynE35|KJ~9LMndPK7#Iyw|5DTJSF~?8*ng_@@A6$+Nm{(cZpgBE9m^unA*v+0u(B zTc1t09`ZUUIM_XR2y7GY;?4rbQ4`TulNK+JHM89;tTZa`=-{f9z6t&-A7uR5@JM_b zIM|EhH=r901-yYG*FeQ|#n=5&W5;wLwoVLrpS+*96xk=`WJ%C`;uYv~)1EB$MTwbW z%U-R3sU0j#A)z8K^{JT%_#=6e ziYiurRMIGx%m9Ch@0*l}_#nv*;U@lM}P5J1gKi^VGNx>yFo?bKZzq?J?!ksPR|J{olF-6o;N-Y zu$p}08XVdgy}LW3@X#9Hyh|`zBf9bt$2}mv0)-WQHY%*=7_gGb{+_+o8<6cO2 ze)-UP@JXi4O0X3%>VxT!Pv!iUui268#Em@tn;#dy`Ns#9P-dI*Fi+}mRmF*?i|ESZ zPZrdxv&wldY-kko65{&F-&iI*V(o25i>JpC2}c4=*%7t&I_x|rnVuc;7YylnRU z*U+hVwYo5Q{|Uj9xJ0GYi;`-WM-G_cQkfxk~;5KV`_PDgZG>T%3*mwL%kKnC@s^l7wFZ z>>Q2#8PhhQ;dd1Okm&Q3%UK2WywmBOpIIjW@qDFOvnbtVamkNuLs|q28dw7}4v^dS zuL{ckMawN-z<5{gCzU>*lNG%`!3IyzW)Lo_TV6T;NW!c9d+MpMrSV6qRgg={Y(gP} zPe+npPRg3!XDMT@s>5ld+qoXs9tT#g7_h~n@s5_AmlWTW?HbQjU&~Iiskm{po*n{R$mNyE&HcmQ z^M5?R!rdR2U)#~tR>Y{u>S@ecahEXUdVhmk%w++XH`vS9iz|31XT3IMct3~@@EXMe zO2$cDM>;U(xa0UQ2^!->DbEs!4pbdn#F)xp!w7N}5`giYvYnc^dBNW=o0YL8(nyk6< z8xN#eX)Jwia;wgk8;;r)80Pw~!+?@pi_~0)6D{RQ#p0unCprAYX1~y6pDi{Cf8G-A ztSHQD9YymH0 z54C@nN4{+yxAFh7ZXzCXT|8d0I{xs8b>^(G(@*u%qSS?}I%Mp%syPs9m1|&4^H&xn zLA>DagOSe*T8x(C>TH4a9;=3$-aA1vgnn?S8yvRU`}w!6#;cHMGV0{;=+rq^Kb51J zy*-RieCVUs$#s~NiS?%VLBfj98@Ao!z~>W{dhreG=^#awG5+x%VS2&Kzi^Plq!@CU ztpfBoopHo2Xo&U7!QbEZ9Hl+(aqq z2h`#i7v_hRuYy44r$`ZAGvC-|Xx)0cAEG)z|A$MyRlXK`>>Yvh1XLGyv7x1rF z^>XcN%6wKU`t@NZ?g0B4UJ1DHiG*+7EBcKQxXAl@OY6CtnzQ+eyEFJ@9C}XqrfQ&G z^7jm)L;p?2wEHuSCONJj4;7GsmgAUrpQRYS26uF9j>#VGy$jB%9{xJse|9dPH!~(Y z^wBv79t#pqLNPe1`)8F%&R#1MUGrpglAsyXZZzkZGIw1#XMwNyEPLT>TK4PokJDOA z6YUxN3@DH{?9-n43^nO_gtR=fBwCqWG(N%XAH{S}rduKeY;G&i95O!E4xi-t;m=^g z`99zFV-9a{ClyW3%hhTHTjx7?pDks)J^%}+Rq#HWGQO1uK#}YQPUJ}(Z5y9lhMwBD z-B&cajalMe864lK(!XurZKd4|!U!A4c#TPKj&v$Gu=%TpgqHyGMiqEV&2Ypwb@n#^ ztezNq1#IH#MgM0EYyPBf=dK)bp;-}4A??!=k_g=UwL&$3e@kxabp3W4^~2g*3=NLI zavW`#voc>0`;BqB52()G6QF-<(zla=0IyhX2XI3zPb7EoCcpX07GIl^R=qpA+Us94l0<>=nzLiRqzW(;L@2h zI!9BTK}tmI*;a0@ZI6Nl|Pz|omfbSoV za!BABNV|SGK76s8h>h-*2DBV8T@{&|b7ZXCqL|N8V=(|js5|Z$PW7-!1q0=Y(FwwqX1Oa=;gP(ElWjZvR+rT z?V|g|-JAkGo(3xZ1T?uRpu|d-0ITbLMa>^{R(MYxY%C^NF zN0&Y9flTvz$dwIhGy)^6t{hnL$nSw7K)7sAspay2dV@W37#CCbg!Q{8TKD#kMeAKB zVF8%A$%EoFL)ctr6QFQTeKjySsVeDsJ(&|j_OiLnXZ5RD6l2xe*mqoy)8Ge z2q*|fV_Ap8XTYIF)YK9IX8xM#M~k2KqWujxRneBq?Tj6)|EZ_zgi#sB!TwK z&i`~oVd^U&{FoOw!x{gKWd;maS6JbbOS7K>NnERNd-ZR4cobW`rvYSj0(s(>gvKeP z=v1tLklv5?u;Y9UIO3|=vHzECoIvMa!Kw9j?GRWB)h2~%nvdX2{}EZlauZ~A{HWz^r_c>*VB(0dcWS+@!sm73 zdP6Ojw?C0f769Ot>^!Ns5!Plr@B}O6vi%9{^?Kj2N2)+~_b0+?WS1f1762!bF>;AK zH**w3NTLyxw2D0xVE<4X_}qia)k=>5$qJyj_8ROvL-B0=TITb9L;zdfI}Jr(pcLT* z+^QdN4d7pe;U5A*(T4&8v4T$)Sb>Qesh*9`yS)#?{yA_-F9Pg!CxNm2gH`zcyC_hA zUNyVp$ryZIFhx)Z@C&D?Rc~x9K$`Z-1@QvU5i#|i7Z`~p zgl7}6zAL~tx*53y9{g9>%%%Bgj&$BGB6$Bt z_~IpUHGlCxcd@_?sH~rUu-1ctt7i%=76Phorvz32%Ld*wrE*R0&jB9w;}2T#_dz81 z*Sv}s+Fk%}?J-tr;V_C97r_?7v08>CHgNj2iQQG^NZP8%Irh_HzrH_sBxAS#jfXNX zHS?Cl(SIADNZSWmH8{}Y3;neeeT5&=J7vWm#ZRxX5J)dTjb?z_y^SM^9>7X98=q73 z-e3i>jR+dOR|@Cd6cSkaJ85?tP<>|oQ74NADY@ zrzI%foNoYINFf;{b2b`K0BSF=RHGoHtwTPbjpQ$oZ#$wm$&Xp@R9TE^uOkI+^x%On z1ksVIP%jFRU8&aX$vKwzb?zoQjIA-im)`Nx%q(*^YhPlsgLqa9YtnYqBT+;B9P(FD zA^Ca}JRKJ8K)XSO-88_-JRC)+<9hyDIgVnD*46OnE&;gOH$am`q%DFQv8qH{)x7rc zKgeQl_Y;l76Q~6T(PKh06`tkAI3S)k*+lkAeBuZ zYkb4v|97-uh)*b$B`o50&0V+ceAKws%vU4}B0d-^cjVH;>37T+M)@>T3)lr^M`?Ua zb*y+jO{K{^iRFKP83|b{0aBEmMxa+A0Me2c7ZTfI2`N^B&b(-IU_JoWODsLp5D3zZ z-^OPV>;6g90mL}EV9}WApqSA7*Ar*(DS$j>a3#Ou2GR4qP08{+UmdKu)`ngJ$`fOx zZHkS?tY9g-E0(KF9;>`gSz#km!{pZdA2Ts6ZB5zsF9-L3fcX@{vas>82#;+?zU9NV zG>0)Q%USx8EG*VQgT#}U<^45I2=3BsO7*V>J&czeLZ{t>YGycj=a`?8e6#JeC4B+?lWvdHg zS652rKDUL5k)*S+%(`PEg6gr2KF+<;LSvS{6_W0oUjeNoeRXK)#4%~WU+mgjfzK4) z!`WRR=sB5wlxTBCDh5o@?;*Sa;pCGk<3StZqvb$<(uO_TCE|+ZaiO&>ktV~5NP!hL2`2UQciFnU;ebY{~xeQ z*HJ6blSmv;Qgx{07%u+)T5-v4AdIoKU3*a-@M6AFk~KI>Cy~NzsutVo<=-#+Ta-(? z#y7KwZA=ZW(wo}8Kr&SBaPcAW z2Xx<7J;Vtgsn;Z|2@Cr3fg%0SiC>!fj1e|A&x)n)Wo){*_SIF+`@nvp5^Xr808#|J{EA4bYw^s|w(%$jL`8fQdoF1AI^at_IZqO5T6Y1gYr` zqOQ;d6C^%{i#jzjg3fli$`y9(=*^f$^;{C@d?H@T>JXdWYkV?62F9T@ z*Y`m{S9gS)hMBi1(}13VN+;3lsGtG!)fzz3p-96oFZT!^A$tOyO$ot96O00F85VHb zWgXZ(PilkqjmOpgv?O`jz;hM^>wbw__)H7zMl(;zIQH3!vef>!VYSDt}AXEy~?nd-pnGGs^OCx?W1ba=6eFZv3O-t$*X`@?nUdD1x}!ON;3le0z9UIx_d@ zJHdy-n)czLS)fL{QUM$%*0W^7S>~kx2<{Vrc^-JEB1WZp(m+63t7Jtb=(?=|Wh7dk zh^r1cDd({kA9R{XVsjkIC$r$SUKdL?h7U&n@m5^>Fyc`{mc8N-OG~1GS~uen#y7G) z6F1GHI$fiTA**<>@J$0e#!-iE8hR!BWwU+2fRj`hM;SrY_*P~?9bP3`>j7tUPQ7H* z-bX$f?B$N$P2}?b%FAe8YaFU)lS%0PTw8=?&ezitXucbIND@3B_h<@-h8+bmHy@nK zEJTX_c#nGHjGvQ?glp+Sks&RDiN*S8rN*AYLGvtlrl7zm3%$%gP6N(S_5f;sf-Ap6kcKuZV5jol1y=ikSmsg5OA*&1r7JW0KW?1W0Yd(BqN;Rrxq|w5JXW z;(nd|W`jE89t-1^ssePRCvPal;>}9oK}bphiO-ytsJ5faJsi?!8x(e+*a4+%Vzk+6UVycQOv_Bpg*}=xHLXzh zeaBP?SzeIOZwGEJ^;8c|pKx53weIo+SG%8Eqx}**&&hlW`_a$!{rM9{Ul6iX6}s*? z6!vl9U40M4t18Wahn>D@LeDmr4k@nS zxs%k-SHuNLWDzM;tEO!}{=eJ&`(ngJ$if+XrJaWP@c1ZEIRs=*b&Qs32}hHx-8}t2 zfSy%)&aS^r_pFp!L40b@vKa;ApI=gba7;HVsZdJ^Z(%Ql5-twR@W6^LbqSkIn3D9w z_hF(@U&itnX9;m?S9S(TUebZR7Ig;0I96U2$K55Fdw9ZYeU@BJ=jiBBmxDX?M&O|t zA&$LHTBX%MgHm?S978swPTOOQIjloO12Xsgp&7drw&B&^O^2zcnF6mEc<;pqZ3{U& z!X+Bfek!^)_!{t!9qX&JNGxO=+knN8^$Aw6h%U;=)q0DccsyA@0DXSOX~-;HI<`%E ze4HlA{+^n0LNk8W<6Dzetv&BN ztUBOfSNN31glUmg2H4$C&jF?I||L=nfT|(1&-3H6)D8%giy_4^3Gw zP@k%W0JZVJfqz&Wchc8Yoga|QfJq^HgGHE8`M!7GPOU^e51Nw*nQ9fu8krZ65k4r> zoh=p@=$olW+_i|aS5UwOEZeaF4&2+C(fc=k{aMI_IY!N7t4x$~oN`(-fIqUR6i(6E z>sDUBoBH8B$Peu#c`kt&xFOJXI%F2FeKnPF@Sq1@kP)O0iK%tDs+aXnxb^I8nRc|l zXXe?t3*!nHH&y`J{)9WKm`HpTWd|dV*7XCXQaMx9umgXpa#SZP|V}R0NmlxEl zb;T3d@0;1Ru{ii_5pV`M6J2aXt0LZY&QsWbs+`fg?v|_vTK(?flZ31bSeq@3=tt9~ z@*ddACSHL4Ied}3<`^@`Q<$YN1kPEN5aA!uf!_x&$x=Bw6Wd#UM9JlFg?divk+Kf3 zC~DF}3S$UsV?kQ}0L&?VF^sRVkimOce(wi}57liwB`lGbTTEefFwnSTe^yqH(7L#S z-V{d#<+Qknhi=KNyF69OzA71C6DPeF^s>wUqGo>RGcV>7d0CS-kyyM(w;p;C^>pkw zJ725{;eh_BjqPa|Ng&y#?i2yiHx7W{8)s0YE;P)R9&~?#IN5A6qYcI5NT6f$K*{kA z8Fvhh6L%XBag>fRitR0cU(pYE8o<6_zOgySyyB1?GL$ge_9KrR8DJZ9 z6d6ozBM?j$1LC)8sWZi=7KZsWDIY5OsJuHFH3u3N(fky1;!}T!Elck)6KWQ*?y!yp z))n3qYe5GsLLUMedf(R_qU)96tcVWH_wU;#boER^w_MEs%yW@H&u?i2aFg@bP$gu7 z74Z;0GsdcD#rwn3m4q46Dwqzl+k6Bm`j`{fDnar~4`a`~?b7`m|DpFYN{5P}X(>9& ztamEEq#*rqjO3=l_GAN^iFSgd8WxM%zB{NKiK(->_5+`Fh3-#BLVrJ(@09-r2QyEz zVH|;d;KMpKctc!!M!u3BJCAjvt^sFR@#S93YBX$_i=9d-nNhYpVL-0~Gjl$x5T;

)7`r zN)nD!bV~wv8h|t>dKOp=T$yasnfdSrD`>Vy*@XqA+qblF{we;QgN&Spvn! zLvoqY)-ZO#q>;3tinJ2`IyEN*(VBL z@F0x+vnIveyN(szJwCw%iih83zNULGkU$k506K<|a`vx^8N&plsty@5tO%77E82J1 z-#N=!j1QJkaP?(HB4^#idvXf8%w>b$v|>cBFt7?K$<6TZTDS=Adudb4C9%>fV3I|~&$ zpS30m_j6t>mg&)Jq~Y&|%8a`8R`_mNDzb~?;IwnPU+XAdOC%LqZ%N3%O0jYDx`EQ@ znRFE$;==);8%Y3)-?Zq`JqXD}`V|Nx-c01{&gcTd6iP~QjpimTWy%lWtsbwI;Fw$?JqWD!-FuNT6{5Lh~9Q zzE^aktQAM(O6A>bHKAv`V{ehYN*zstO5-Y^LnVFLP1Q7k(TOp%)eG(H@AxMrDLqp4r`FW+L^U-PZDkpP5fkmbeq4TY22W#2oEzfj|*aIp*gqxD0GNu(!X>2@#4??dNz2e*u1Pmj9z(uZ~uK7 zh|sd1eCzwnBkdpyO7l6{5^}VWf-GmKLd8mxYP~CXrdMczj{^CzvT?2Sz?gfU!qv{@ z+(r$AqtbyOzINnXs_z5;7!=z36ts8ztU5Xr5p+bsgnWrK>#PqZ75Z-QL-Y4Cuo2~E zzkC=eayn>m5&fvOoF%@zX_r#U_enc~@4Dc2Uebr%rBSV-upN>d;36(ttmh!KF{ue* zVcL~xeEGY!FOTI5-jJlBRw%-wF$2cJON4JIM;Gwf_3Be?LFkpSNo{7(Os<}c`x$5U zw}WFd=CC`l*2iY&swd!#==p_4gWz*IbSd)cb08ijxst~V^K(wh{h4uvt=y~ft3gK5 zO`4gffqf8&%-Y!Dus%zlKW6zb=BE^J&XmAbzsa)knV4}Ohl8E|qz-nOH&_4+ zD@NZL3cEC>})_!#(LWcIYpFQsrN$0^a{WrhPR$U2liJ4X=HJXc9A7CB!oUx z1>czL3Kh^9O=iYo_MlefMMeP)ajlp(7H8B$??H zvgCdKCk}sQlWg)~!f388TD8RRHh_kv_f%wvYD*kV_q_k^C%FNo(6>WQ;U_L2Ww^1d zv>;AX%a*mPcS7CChs#7f9DSXKWOx|o8SNSp4sv<#Vm6TGUYzeFjf{$L9KY~9_2(TE z&q{3(yPURQl zU)eGm>h<4x+?fww=igB`PzxmxrxKa)J1H)1XO^F@qX9F+gi{`Sn?Lizp|~tMfTsrB z9olzD(Fw&scy8fS2Pk5P%RckrD~7-?l@3p=z$F9WtS#x+hK(L>o=<~k)8dmw znZWP81##8N&EfR&*?bs|?h`~=CoiT4Nc{L)*;xFExhR}C?x;Hh#P(-po=65BGDx$% zmW^OY5rfNScNw$$cqb{;^TYYg!S2Y^;6Io13}Jx?0vV*FwZq<&D<-n5R&%e$H-;4T z1;Pz;y%#KgGkb`20@QLLIl9>uB~+L9oowAvLU04g)0Djd1KEa*QBe;qV@RqT%({2f z!b0zMVO z5~zW=0!P|%`}bC5K_0wN75$R>o$V zh5Kc4XX0#Tg7%5I!@{0P5FG(pM+boYdSyPcaGu(EI(S&@StXAlc zlS!rAq%=Aim<9c_S$~}Pq#x;}c-5&qVx=CLe2}dpHBYR??yzIkEjI5zmNIhe%2dS$ zKAz-Dwz(elWe;-7)+JNRKf#;xfM5n26_Bd89NJDD0MOAsR^cv4N+L|137r9c0!2#6 zZ_J#8zfXzJV)g*&_mCVfH1w4~!}08pGPixS0;!t}0b3X`89^-k^Oe2egQ$4+SX`p+ zk1fOovq?ccz8AFk8t;|keS(j}BwAKX?H5tYG2Uuy_p>22EWA4dV>ABuy&#ziA^R@Y z=6lxokp(wUIA(tWP2WuN>o_nQKbtJkFVUu@h`EkIhf~L)L@|lxT5ayQ^k&MTobH}Uwyp%@li z?p&pAur0X!JhC=M3h=lNNJ5!>!^Vi$k_0aJJLP{NP^Q7E-w}-geY767;+Mg)-on%) z56c4qZHXq;m3risOGOz9v`E8`*t-{8$YO;CT9!4m6$gr$p!k6(<@|__X!RLV5_+%N z)~d&0{UtR*Yt1c!joO{tOxGHDds#s__I@W`iK~cp)f;c+tb+DEhQJLBdv}*pebXKn zn=)^%_~g&3vTDy>Lm-bRIm`t$O!S5{*ly)SHc-d!r2bU%!W-|8Ged)FPB`pM0>%%j zV4HD566#*}1Kf>LF*#;pf~GkT{j%zh@Sj=aVdm!^mMm08nNkM{|uX z`2|XiWsYs(Vdj=Pbor^@R=$ni9Y>hvGe5_KFREjHT-^!;3dh-dTOIFPXh`T0F0pq8 zrM^tZH|%mrJ??PjeRKm$y3b)hx1)+vP&+_AbD@oS85}o`ZGY{%*nelNF^Q zu@}Xjd~IJ&u#S4fh+`~FO}32rb>y~5odAEHY=hKg45~@fyjhk~QQG2K=^mdxdpS2x zigAGa1?E6*VRevVXiVxP14fRRgq%q!V_p&cD&aBGu+0wEn(taZxK@^8<7uc-@vZ(4 zW!hw@f(f|zq^wnQV1b5^Z{?4rCKNBP^5x=d1O& zO%*>*Z;`a>5Y0&EO{?>{@-S3q!zKwgRp)w3=t*W`g;$Fa<`J`^bCH!ELPhSEqS<_4 zdz#sX(=U%xl~?w=Qk(;MOgkKCMN@L4Ahlu$dyl%1=b8#SBX3@`q}OxnUw>=k?w$_+ zpL#tZDRtjhP_q_ZF*zYQ*SIK$d-VITu{)w`WQ4_C6CPmW#FiwR@gF2^(l{DjColxI zpVf(Q zEiMp4=@o>YFk#Mq-^ZJ47-cxicXR*0&ySM4v7TCrkwa@z%`SrS9{kC!XTdAi<3L^U*o>M0k2kZ|FQn+ zYNp3ZEdDgZA)(0W%&I|2?B8=7>d_6YzQlJ zeu5gvgFwqBmo|eCUg`?+XP2_Qho?ts&N@6KB@9|5bb}hSN0##k9lGrzU2sOc3<=_1)NsF02q+XDRAsBJbf~(ysg_lK=H#* z>tYs?v~pSR~W)f6-PaHYHtcvV{anFSu-M~+m>>D&00LV{0vf3FtwJ-xo} zq(O}cc!yD7-(flgBu>vk)a69Dyph>BHZ{^9c)Ev5CI~#fB>K@Rpod>%K*7?UCxVKG z*7F_u?UIf273ihEnt^kJ!0)b++HK+RdEV0Pm&%pz84Me)HLl-mj=X={2um=NBb*Mt zX1DUD)5y-5)orCR#KE=iH$H4S3mLN0tPN*SG^K!#I@j zxY9?YIF3wt-i1jbcV0Rsii)YmlldeXUH2v-Fk3lS-t&z}G;~$d57C=#4JOiFarncr%qKB6ef7mahwQd_>Us*~yJ}b1)dXA1Q?`?)ELZXg z)9HL;ek%EEVPRPgO8a$UR)S*qdow5d6@0q>lIq}{K!GlBEX<^S%L?W=oFQ7O0M8Bi z(u!Jbs)I>8z#AcsjF$`RLVdVot|E;v-Z|pv)Xm@Q-Czr5uEjDu%P$#dc0B(wVHPe@ zF{)SI;WA9BV29K~t13SWD_lki+^iYlG163dnu@B0dpn==_EJ_~7${ZG7%8AOt*-e7 z=z8DHsLn${Ef0lp3T!OdCV4JM;$bWjBR**Fgexj@q{g-GPFBR!=5hGmOg_bw3Hq1B zH3YH~$gNVa-dwv90?xeJD%xMf)eg%HM-K96}me#q+4RO|^DwKO$5=A?M`9S!nEgsC?@pX2< zN29AAg3Er16SO5-4cfjM&j!><*ZYXjg^&o*-JEyb+;#}uev79P3txY)MSsGtUyuK{ z0#CZ?F95Xg%-B&Y$=@PUrU^-=plh7 zoB!MA@jy$23(g^yOxUognmW8n`b|oZFskse!9AzQCy9fJqR$BBqEMl`iJBTZxs1l* z!+C7B=TdrvI_$gR(It|KciE}z^k^B8kl6$-Bi8;NGt$4Hl!XFOE#u!H(Xf}o{U+hc zc7H)m@K{yDJa*$&q(6TO{s6z`SC#=s2!p4Ps=)g{HZuvfTt=RMh(YpmiyFPs;$_D5 z_;L;fWQ4G#?^GP?4k+agOhloh1p(jjr(%?vl)d=R=r)^7DijPKwDV2>dpIPH;Imfy zNm$D^4bF!w(|xhR3TZc|(r=|}$%tHlLebF3aR6I_7cwZBGk9$T+v`Uwc(cIhovLXC;d3k{WEA<5l<*cSiBx+cH zRVPG?)4#^UVN?1s=HaX9sO0z1Ae3f0ob{*8Ro2NI5GN;_j{+S$Ii}${?g;!cb8(S+IpVTQ^a>$`l5^|D@B*vr?i;n z9(1OOhNP+xrlsV&3?1uTQMCpj(rfIud< z_i6QT9<26qe&2Bj9yHDO zhI;T=cl3rPa2+jF%k4WqMbJ5nc?6HM#*QPN9)a@9pjSZFtsz_SxiFfS*JHfxb|pXNWNqGN-&S^BL^iNj?f~y> zl4;X!O0B*3?vozQBAkt>VC?^)VPO|Rv zipOV*Pu?Wvu7;CwN}0qN_uT@eQGS#2vHBOaoRcnLNfTZ$Ue7?QgBS-{Xw_G&hX?u(eCo7D=Qkbt(B|fscz4 zwwapKqRbW7fEjx78U<9|jyxx&Pc)T*&?zhNy_=}U4Bag)pctgi*!-2y2dMxGG|2@quJBL~g z&@jeu*^!L3pJOpPcPc2h1uuw0W?mRD3R6%`{3w~roS}CV{((w%gy(mB!@G8-$>9>- z2eU1X;iumOX8bnSrFze=YBfa5+^S)T&x1RI*jI6bQrVA-I(BTS3qQDReO(6xw&`CG z%s)Dprq%mrdK?(qCk`>a;)BtZN4r*GWY_GfIIQ!# zPmyd{6IR^?cary1HD?Cjq+fErPEay8Ysc*hQ94-Gdb?Z=Csq72eWVpr3-ki&+#)968v0Y_~4p{d|1o<rxdeH_4(eAO3Hd$M@J(4QoH z4LAOftMqI(O@CD%QN*X;rlNs%EI-G^f0;d)O?H9PyW+o}h6wHGYjDt02%>2JGhX3| z*0mEyXY|TqlB%Dv1#53oN}i>pHA=A-BzS)$uW?=zzo=`+s00o^W7;N|;PUwn)yZ@C ztxJRpzhnMY2p%2y)0co`!}@~t#8BUU;9YU7H%N5DdAnFM^;m$(UBx)qlA&%w(l~tH z$M-Q<7mKsJ1`5+;JvG`j-L_pIRCJQ^$SY1IYI{K&2*m^V2qaf|)ZYtSWu)KF_?%mZ zwTcRInF@NW@nqh1CT%+>OC`M7_YPTPTjCpm%%N{Y4gZ`p7e2?({CB8) zNTnZGv#$lLsKU|4gcq+Fig#qLZG4i7-&UpP9}cBth{0&kWJHg3U@|0xE$(8fZ^6X0 zh%(_Q_sCqxU=CSvXE=vU>@ryiSlT5$d)28# z{MA?9e<*6nZmGQKy?(o8=`uV;?tM;!k%3E*7Ukwk8eDKWEYM#Y4pW%fr1sQP9C&fd zc?vE$Ch!!9o;t&%jZ%7Z(iu-f1ykyg4n^%yk?XRAhRKuKp5BN%bqB34Ugx8FO7t8A zfeZnhi)n(vvzSy#hVC1^2z+3J7iMFsa7-(Dl3gkGW4)C`8X2{}jas}Q^0B3{%fJa# z&fl)Ab%XTw3I~@mpg&h1BbwLh=eZoR4$8xiipU|9Vldio^>V7ATc3`cE1Kb^#s7vx zPkT<)Sy0`+Nla{8GAF-$*S~5?S~}<>^zE$zEvxt8^gwZc=MA&wGK;v|V7UIOQA7Sn zoVmo$hAW}ggv=Uc@GqGEDb#w3p61R%N!-G>QTQYCr}VBhq8ObU+jiO~1Z4)Uf+68Es?lkM7C}C&Ke}iw>@9(1&w3K=7=7=Tu;4>$Xyte{glB@n~Ps zG4(+1LH)9WPW*A!Sb0=k57Cyj*t9T49`jo?1V6Q}s{V4}^Uc_-$6*0`D|a{G;Qnvk z{MAvzUxtaO_5(EnGFC1LD%Ir7ms^^8&cKo|kR47ZNK7mBHirDynB;0ee6+onE~Qj= zp*=2jcUYjb5YS4L^PV03HqL(Fn`csmuh|gQBNE?Ko@iK$=YXN2|JSGhfnh&KkEMf* z&VY-D`rYv^C}aq7>?GdjP17mAxjgqt{Hm{D8Qv5mu%tlw?bp#{^l@>}jIwOSLp8Q$ zjUPi4&FL%#em*bqU%9hbz1a&itXAz#8I3g41hRHlHN>z$lL6aZSw#e8W^6zf(!R-;%;3 zEq$<%SiifzUf*HGY8$Si5wCu|Sof;O<0Pf}iqqY{ELLLXB(b`&7f~@x$~fCN_L#$O z-^654)PGLGI&XpXqVL4vYeparCVN9pnv=?14&nYm8ThDL;{S9U z0^XA|8ygUB{i{Ya!qd^$SZN@W+lk!iE&vOmz{E{AK65E=cySlM%IHqoI}olRPDSNA zV`}_1s;ws-^(n?~=ajx4oM8sS)PmMPi;fsUGH%~qXSawU;A$CpQKJl@5QCX6m^r60 zQE6xp;c&(in~O@)FSFqXrY8MAcc26T@ta@Eb*@b}mYdc-8DR#RAr~i{nI-yN2@vAl z|29Si%r_{%djHPt9wRxGYu!+PX&mHg$*mbN`wh0A1XUK`q2c+w43zRnrd$R8)i!E< zDxj6qxE+mP_iO=3BS|1O9kf4qL6%R>eFVH<#_iUKD@%+JtNrZp%Dh=c6NJq=g4N0gKKOp>v#|f5*_>8p+sziX3cqiOq3$6|0v=uIC8M+=(ntlEs%di64n~#?^zp9L@ZyDa*jbq`BD zf&kWlANR%J>|~?t)PB~y}J&ZI^3ViSWYY> z|F_#6aR1B$R+yOHEv`n@z)4tT6#T)@{X^}m*`fc7IQUC(J0Z6rn!wME2=xjGFF)c{ z8a-CZs@Y0w!;x%K#gg&Q>FzPt#YO39nKLMq^}Yv*s>q|lO|6j{~QB5#zqd0##&#kZ3wyhKm8Z)*H&y6 zd@`He)Oo!>`lh_nxWoBn`v7P13Kj;LWs0zkV)-bf16-Dy5D=sOJF#;BZYl|^4@VTE z1a%Fz3cWrd^#}wkQ@^kJL$5Ud0ZeZFe@)6nB#n3Uv_3-;Hj}8OoT0h;BKolf8 z=L2qmKRLP!!b#d!@m|C=QUJ!qm*2fu_y6}_Y*PV7=Q5C>ML*@CHQ{Xb@l@akZl&vug^+4IkD-y zpPc1)%|-!g(YZ zU$1Ft_yV$>O%~*nuZMNW8@kyA{O<$?Abb!564=A`<0*6~WaVl@a(GyA~+AXDN4Nb7HZI;JcleHx)R`yH1Defa^R>5|W;1wys$fJqgO1=2|X;0EN) z!TyB9qq!4aCHes>|8v&5Bkhu)ZHo}uN3A|U`y@T%c{Wq%$$E8H$$d;OQ<&~~O*j~Q zC4@BnyVrIrwONkr94o!MGvXV|*v>!i7m$|8q(!~-pAH1nJLogZvu_>DftK)334r6J z&wn(nyCgSf1Te`wC!WJ%Lff#ok@&^CTD-pR#nL7u_jt00532w&k)tOxbmvR|7{?f9T&;ls z`n4i(<`N(#353!_bTKt~E&Gns{ck5A(3g|_$6*h!rp<1s3kMk10}h{z*`XgcZy9OJ zJ99X%>tuGNg~ta0YC^!`TMExG!NA6Y9Ir8ca-*7_Nh}rC@kL*LeN?v?p4*4u{9s_; zK_&edrFj#7;XZ~nY^)=6?!i;=6YgERK(V%g|3G|bG!U@aG$EyCK>1ik-THEpYHYff z{2ItQg`YTFZ?5SO$~TzzJh`HNDrlG&cjBk~f2e!wx2U?de^_vc0VJiQh7gnvC8Qe_ zK@kau7-B$WXrx015tMF_R1`#|VdxlF*lv>$;!s`yB842fV*<%z=!1 z?X}lB*Lj}%6H-qnF1#{<+Qmdl9Wu`JQp18%BNm& zKv0N5)l8wvdtbLQTh<={0Y^ALJdfUk&1cRTH%{=um79Kc{&4)jb)#XQsjgc(d@|3C z5k48I>8tUAzq8er|6aRI{w#7Ao(&s)Irv|4nBmP5##?aTLSnJn#ka_j5hmD+a{M!Q ze`zW$J$eZ%57Zq+AR+f^OVze;z>^2N?#hwB>>~$HqhlZ%1PXwb;ib&)P3E48kn@me z+P$Tln>tzd(hOveM+|k_0Ug1JvP)*pnj8EJ7VY_z;4lc8?()VH;K;0;^V$39(`8A% zK;BUp|1bffOeIMhi$7h_)N+3bDfc2M?*O}qC+TWT#NvF@KutFDTVakA(X639XGIX6 zdMyaOAPMD<$Ua%MM_zskfWD4^2w8nq0813m!bQ+9M52B36i#!Zt0vrT<0`EUet5Gd zMs};$TM5ZF&1|K9eFQ@9e@H>#U6Z@`?I#hjYj8YJn>!Xk+fn1s4>)U?A{--ViPutd zpl`lw!M#5xVm3H5#jg-s!>b@+b{2}fkJO%(qY@Bn8hf9k2Q)`hA18;oV=laYOb|%x zGBTFD_hQZDH2wQ>_C`1@tl#K;>_z7%jFIkc!=W2unC)wa>V>Jf>e3Mb53Ab$Fe< z<6X+vKVm(4e6r-_ooE7OPnW&Jk|W8=pczw4z^HeG(ecXoj5E!Pd?x4FrtItN?#1Bi5;h~ zbKgGF=qjWN-&1B#Jp95kKt`-^7(DxpEkVQfjU}XY+uahlc*gnv^7RFA*jMqb)Ot0$lOp5W zvjRa3>iiHhUS*rd?~{y{fk&xOu{V~+{2ER}sR-y6;&0<8il-vw_9G<$!sq2nZk1z*fKA1`SEp}osHEoR0niR1RYD+MPmO%mC{IJDi){S^1Oc+%NLqB zAjpp^kl2e?OMXPh&DW+!*{boW0zLr zGHch`Wb8udS2P_rZFGkG2zSKY@=RZIy^tRGdr;d;A8=IQL3T5g!-aRo9TwUFZ*q`8 zlV2+pa=d5P>VLK zE0wo?R!xaoD}rGPs8!=VAE#Np%bg8{>`y@o&Dk>-t^@r&Jiq#!dshYz*}TjRlEN&j zi-re!2-T6gH4NNOjyeAYxwmS{O8$6PLu%?Z`pB=Pau%y);Ni-Y*{9b=~N;*elzUC8}9$s@?5B zTXyF#WfPKgv!MN`kZl{TTi2I9vF1Hshk?bAQ48}lC(>F)LKj^~;Cv(P&g z;Tab~U74E33iB1_uJ&%cayPT*j-0gTjlHwKV|pCs{U!Z9j@%RHb=ar>oeo2Fb$;rr zG%CwsDVo_y&^UWB)~`b=y~E)~EUWz2z4E0W`)*yAK%%!B_7YuPOcKyOHhetz4g41WtL% zNQ!7jQ=yg?4aEhPWR9$QNKn8iw1fk#w!1_*xmPAf=``M3Q^yR|Qd`0t4KMlaX|Q&E zQW>AviWif-?65#mF%M{$=P8N0?icykea?^(=#_AX2jLKuHwk49epiwa%7p4tF{Sk& z=O=0E`!vPQF#GLZBXp4Id5okQnwg6m8-&T82a1+#lG$JRVS%$PP9{3@`R4Z25$eLa z+zCY@Y+vmTxE^DgrH3(38tGh(^0q|`YDQ#D9yLy`IgO$?(LyZ_gR6R8wfA{bm?~Ny ztt$G>2T6MY0yzp39%Xksc2gVBDL+{}F*$v92NBbKR%(xuNpDxGPIgq^FPQC zTP``}t;?~9#RSB=PLuu@5WlO*ezK~w6dkEj6?ZPZnKvUDi{v4D34wneu%KqHktDTf z3>7vFH@T&I2}(L6G9BA0;B4biuQI@kkg)9FtdZ6X@>c zp(1kb57;Zk=N>^~Y-gNRrH<6a5`SJA<@u;n0%Me8)Trh(Wg4Q0t-KdR@~-2+!#T{e zFtGIUvQ$<5b$Pnw zE@X3MZzU>G?juzIkM`aRMfF?4k8I%&ktIck|8k*Nkd??)5?aIX@$q# zViYLENdlORY!iD!mk>o1(*PS2+mIBeMM2^=FEs$4eXUqZ5_9~lZ@Dgqn$AeM!OE{9 z$^7l@*(>MyWclHe!^-Yo*rn{vW*)-%JHMhsOG}$`Vh&$j9Gx(bG3{KX(8=e)w&8q6 zM`Q(KK4%(JTiQ0JC9Jmkqoxi1IbjxRY}Vm0E}+WkIb3fFR7c>=F&ZOplXMGoMd5EV zd_6)=R*&#Xv=(~_h2_XGv(GCNHi3te4xYKIFu%(?JxV2ao;K)9QynB--s{Xt+h0ct zC`Q}*?{;FTOH2=c2F>A?Y`iFfn%j6}4nxnu&*cb=cNXD4_C{YQulsc!)5DYDi?f#w zN@YKE$?lP!3O+6`4%zFx?jP=1(tiBMKo$Nqe)jH7N}I}Wbo2`H&ml3aS}!3|6&<0? z?5=`u9ncbqkxIEeuC7J_;%1TcuvZ}^y&cO7CBvq7^ZX9Au@GY>wLT&kJ>v(aiT(re z0jkUGH_}5GYz!k@`becfx;sZjvQGR9%WQMdClxIjRC)P6ez$iQO$40l-X6(v@Ua}I z@X<0)>vm2F`pPMeI`EcV9#}9Vsq7O<37O-gdnIUJAYQEa7QE;Fpuo#@v!=97U zW}@jSF&lmaCac@~9dNn@Wl8F^Nf8{(RQ7 z{z;2?B!toz*gzFgr6mN)b95B?$Z;%|OlzuWPa!RrvP0Rh4olTFI-(wyH62om#f^_6 za+qrpGm$emMm{dnV(Byo;`5jntLFAroeC>eliZv4lXI#iZzqwEZjUJMrl#DFL*zuX zjivI8b-1XqqTzT!5zaoo@_Q;eo4PUt{Psqa_j!4s<} zG1q8zT+5QR!1Lg!$^;VD-JsxrS@k35u=NDQ(^AGcFaJyG5fiHqftz^it<};{`83PG zhxp$7hqF@cu|AGgQe)AL0czhwBFlwPm+Kk{%{@!|ICt9BWNG}jp80}oj_fYGV9XOK zwkOPV*&(Y&T$JO2D}{Gvbx&`T1P&e3x(||^S{2MB-_y|9T&1N~uw!8aKzQziNZuBK z536kVRcl0)2^tlY8mt|s`^ebB7ZibU5^bN*Ka_@$^t?J5Vfv$2`@JH|&J7uhljm|}@9imBMe1QA0lg9i<(9=HP zuckrDEw;g+(s~|WtzXvUE1r1Xs3>nk2o6nXN#p3nYYbu}6GBqiodC@hbki@)!(hngIu3O_b!U!>Y;0>Rg%y zg*NW)9#SzR%F(Qcri=lfQ11H4)uezNn#G}pZl}ssL$fNXzH^Kuk2u#vLz;rMm5uA8 zIFutIk}pHzx%1n6V75h9w~fS2cOMK~fze*UFF$ev;DJ-$r^9fIjH5WZLb`L#qJI>+C5d0ev1a}YGYW37k-tol*u8+G`+|Agr0;nE)Q+6-l}OdPE>h`dBGyug*8%9s~fIewiPT}H&8QH z(cv(I!WE@hsoP%fl)dhu^}ER^AYA>Rs?m`36hoUcRd#Ru`4G=} z^yBC1T)PF$X)b1MTtuq6kX-gc7*>tg^oFsc1a;u+cBcD!B(hFVuaKEe>zM0jWvxws zrs_kV@%CqzB2;;6O;Qc%sm9gw$kR#a`;F6RY|W-dJw0r48i=8kdTl+`6yzj4r=s+z z;1(8E=b3Om9uzUL?d@!i`P|h@Y+wx;n__W^3 z*c6}HK*w_Vcf=BopAH2F;uR&8g+)s*EF0uCJ_>`SQg!G)YxgYZKfW%ISod8|{(7BF z5o^e|I;BX;n$ocO0&~f>lJ)?(yBXc*(5x8s7wf3SVr;r;P z5fMABjMtEk`QgX)>_BBdLngoH&g{2|Yx^q_SEkZiX4{=i@6IF~y#w}aFnQZCNQ{8V zqCHKby;Fp8JtX1`sXRuxr@?Of2E_s$v6D9=y(u2w-G5-JE}aojl=7>_80W75?=vp1 z>axkkK|OUQ$9n>AQR`}>aY$)0sNKdABdZ>nr(RD_@_y!{ z=6-ebXP;D;syH^ zmm;*w?!!URe4%IJ%8=h^chxG_Jcq7_6o%;nagg(28p;h5J?w9e+HzF{AP(UVL@WlL z`dV3}o?lIdHK$TMk`1EN{oQ|3l;T5Mooe%2Z}aV0pQ#4D3ilUV$G+73vNQJl+F19e z+}R#?5kK>= zoMM8I7CeXUxQ5#5T{+qyn3h;KYdz)XW&0C@#+tW|wqJ~5i8!isw10$`$mO5)r5k%p zrKUM_*;IAp%?fNKg`jVy09rJM&#FD7>Sj5nT>89{>+chA0KEkAbSYnRzCzg9|;pac#!r0O_N(t#Yu z*mZYKBIzl*8EAz0Z^bEi3g?w~04KP-pawL}|k;LcE;E&hjm8f5p(@s#X4wLAFK2t$pu@5-bACMAb zU5_}SMM<0Qo8KiMh|VicH%C<+OmIm#GX3e0CC^v~CQ4pawZnzuQcuV~m(nGs-JVbS z{M->OdHHw0LYZu+Fi*aR{#0QR<=f-0vF4;5f?rTsV}e(nnb<^KA9qFwCPZn}n%S@m zc26G!eA=7O4>=w46!}xTTj)GF9%1-81T~a%O8u7D6u{^8;jxCkQHB)sonQSC=j+dD zD=#*}BFwpO-;ep=hNlf^RvR?w)U0x z;fs-5*Msci*R21on+}>uOD)S%vbtrQd%ObUr)(K|YZ^I3V!8czJP};>WoOHuOwi_5 zLI-XUk5(`Gbt#!#tJrMQD>q-|e=G9BwRnuw)P^_Fs?XtkT{qc>_F#x08}wSg(E8O! zVs%)~GAV*jOL|n<3A}EMZ8rWwIc+-UAOl&~LMCCRmU8b&hB&1Z(UiRmzXXqV1O3I)R`Ikf5 zFPIenurzimcBy{DJ=&&FL)(KeF41x&7QqlsG>7PL$y3(~e=~n^qD5uz!nKyRKi!Gs zn=IA%KAF|R*2jZA4^AONY!g)-A3Ey zxNg!ew~MM5y$2XH}oZm4vSI>3;oT8nno zM?tKy+;QqUF~3Geed2?hm08q8ryAaWnXJK0q^4ZzP=BgJtK=s2`yj^Iw5n4X{@HcE z8G9#aJ;ZU`#v-nJI`uF+z$JUHP8;ETnpC*bV#0ICG#D8w+4-F~odkM90nI|Ct_Wp9 zLTYrUdYGTb-I3bBQFw+F7yH~GpBlV3djXo!o8cNo^2js6d^TpNHIJ2YFIhyhZ4B-h ze{#)eRlKRE=yh?p49}OmE4PnFoX^*N@l0x9s~{wZ6BeiIizRi)c3-X9 zd#JD~*0y!fRaM;^SW?MIqf54*pcwSNe>Ekry!{u`l>AV8V;PjGud{)(wM<7fiyHHA zKBcg7I$E5!wa@e}UtL)#>Ty%l^1Xb|Kc?C!l( z5jflFgAH$)LURUl*6j9EO8XmA-c>rWj4oX^AXEE5H3M^zq&Zou_X}Ve+{sjj6ilud&c1s@wjy2pS zaifA-m=W4yi#LEdPwM`BfsbupT2l+6@fDQT&h;z8$d$iDnf&=-BuS>d!%%lysYu^J z5lYn0Hafj{zN%?O-m_)*#HZULaqa$;;oamLpG5bxf`)kamhb`Di%Jv)!D_RomUt%oV|RFzO@)!%ULuMvDEyw^uGCIQh2eZY6OJIQpD*- z*fhI1dzUbca1xK+)h)@^qc?4#FT}qH5>`QcvPRHHA2Z9nzobAM<#-6CxkJtJu*d<-lnSk=-0zKDT6uS;H}{ z9v3UkGW|>vS@04nuyXAmalu)z+BIfn;oH_s5skI_-&QP2gE1@W4WnOt=DOAV_~8@w zuGZW~GDZK^enO!T_<;ucGmB&@T3Iz^P00ub56vi*zRBSS?{4TsBZ=THK0o<1bt^tDFmY^lY=(yUC)_E>$8>5(BOg%GBb=p7c-@RaY9eK^v>Z+1$c30ii+uy zhS)!C>(3Qy15`Qo8>rmUU+s%HCc}hrTf65`m)&~EeLcS^8ljoTr^yIua}JGk^Td3Q z$cxTsU!Zw+aZ%UWMJV>7p%c*X6iMLuP<7N=M=MMU%jtIf{+}Y<{XD$c$oqatJ84HB zuOa4cu||h~_p4Xwu?DA!LFSLruMSR|Q*usz&{nfWDdHo@yW8+uYx2)~ZkH|#u;9Ej z#@vSkFFXtQK2I#)-sZi4F1@&dgW94RuHvIvZ_@6TCxt70DV#`({wD)2G0<@-k))$% z|9ua>BI|*p(ir&JDjJS`C+B_=cd%=59!HPO)+KAY9HADZ{igpv8Ceas9wt!7AIk%G zSJV=JENzWZ(Yj0&tJ^OrHj-=AQCNMkKoirEKB?t@;OdGwtPDGeAB!#2G|W`@Rh$y~ z-hDReeehcuzkrNx`>v?N!S>RYx0mTcFJnIg?{WC{Esh;f(%OfC(@I^(MZ6Obhm9m5 zq5g^O^0xIzL#?d_(*FztaXCaJv9-#4{0ph|nwdCgAO7dHRO~b&9^BDq!vW*xqkBsI z-Jt2gwkvfn_xa!D;!^U>>UPzB%O;+?*&P(5fBQ|~BK)k}SnMq=P_6jDPmUWV#IToM z{O1d_kR8o`{%+Iy19(d*#wVMqa}lZp;5o+W5N0)W2*QevzTSm4mYVXGIywZFD)tHj z*D18G?Cv839W}HzOGw|~lqMQUfku3r*5v%L$wJQ#$puR!G-UNGr#OrUYs(IPgEd3Q zWXiY#*0=qW+Xp#?rr`ED?NXe{T(v3-aP&vMCFQ_t=?ENp=?nlp2jF zx;*Hy&{W&0n)pnGhC z+*noG9>xIr)dubsq#@5m0fnDX95sh7pV5BWv=yl$KqxSQ$V3^j zy#v0nZw??yW57iYg3Y+c_a|TZWF_6B+n3f!TLLP8fIbwS{PKMYY#}?Q}2oOL&#LcxnS50?{@iGg2CFFeV)t9#)hl% z-xrvL=)kBVRY`W0>5tzDC|MG-1utX--{DetW2a-qCdtFHk`f_6xV$>KkHp!meh!AV6_B)>8n#%NBuUQM;XP4t& zqW#k_C*r)MCpVV}zRhxva9d-a8he+|dYQ(l1GYN_yqJOQ>0Q4xUhQc1mT2&9X3~-F z4u7?d3ofN`atWW26b=Tcl}#R^??|wZ8;?O`ySA~4*vw0{f8oL;kgL#22JIuG40nrr zCC)<3R$vsMilx{~iW_uW#eN%ohnPM}?AqMx>(gAM_fHdMrsxr2+cRYx4M~ zohRyChj-;uBvOy=mGRyVO0epT3(O8WJ%}plV{Dm^%rQ?RsEF6409(dhx!I05o71q+ zk70_dRs=@?-$~)y;@2$`i#ND7ftv5fBk(e2Y}MxAh+SxZT8v>~W44?)gqCP++ zZlZ7Z#Qtmp{Ntv9a0Cyh#EKY(k!TO6+++aWE!gD@NZMvW_g*X>_LP>i8#itzG5Mn~ zIJ?OfuG7u+)$)F)ew+Q`gORGn;o0oJ1710sR6Z1QH!<%hN?j4i^f2h24*JEA-65eC z_F#ozYBy=&w>Ioq<3G#G^?2chdAiL3jna^US`PtsxngHpGJrTk$!{DH#+!5gcnshN zM}EZvkg7AC|^a>9?tgrKAHsN-w1<5Bkcb7s0pDBBK80OA$tQ@+35grE%0>DI|44c!CvLL@_4{@LiQ@KL&;bNfyBCQ4+JUmeGt=^eBEg!MBOINVUA(EBgFPdO!lMsrZ1afB)UyHc3QfXBc_9Rb@)@RhA2Q`!t(s|IrVlauS7RVz-e z5rEU{Soxp|tYHrT4h-;WCL;47cr4?2q9Dw4MJoOIuz>^c9RKoq|g56lAVfB=3~ z9T3nqCW+XED)n}s))20sGL?1b>7T|TRW!k%p_m8Tf>Ey%B}aqy;J>#+6TZ1(v0qE@ zBU?E=EIz9}`qXszY41QLXh&vp>U3=i(v(kHCXFNnKiI`@-8T~F5To4En`!K!x6C-T3iBhDWMf%8)Fzx!wlcDHW3OQ>!p zM!69VOucFe*504UOHi8+9SVmVfOY69L3-cJt3CUtlB%`x-QQ`=Vqg|DaANHqtXA5N zVOr?c%e&T}PZe9%Y0wDS|M{Qq5@jv~Ag|S5q&!HX(+WohH(VZvzgan?SU=>e4uYuC zMzS4x7FtJ^J?<+_Aj~CRzmwoFv);HFD&|43ov0(653N^zq)gWl5b2+Oyyb#mLGty_ zZjXo|m{3eY1u_P*E}Ygi9o4OC$<*HSB4Cf?w>x<2Zj08;)_yuYF28j$T}1pfb_zz$ zPqb=^t1j~*m?-RLZusY)7)}s;7WVRv6ZCEr;B6D`)B@e#BElK@JHkEm z|Aa6z!yJ3IsZYQ$c@K^yzTq6z_zU3eWqO|1P}6c=B7WIs9)h$E}X+-q`ATWtluq-shXiFB@zbAOKxN8paqtwmfMyJ`+Gkh z{I+F2ckb->O$}8;;P9xpu}APqN2>fiCZk`=Uk|D;X(!g|EkzuQ_gJ8t4&<|0@$XeF zM?!-9Zssssbsp|PU63IsLlZdr?8zb;EwU5fX$yb%p@vad`JYwU&M@b3NZnTLlbh#= zDfVs^s!eG+o|Ds>mOb8V!RKeIZST8hA5E;A_WK%n0k%ltp=kRy*LUiBF=B^(VF_E?@AdtEF-!tml!;9L?M}xBCl%lIx+QqR zw*C-Y=`($o3mpAlm?zjAP|wVWEA8%+DgVK)6JYgTKYSJnUpqtR+ZawtcW^X)N7^OV zu9zNub}c#jqQ@#mTi0w8a0P6PVNT zcP52^jj+D*$?s(BA+S3Ch8dqXIcfo{=?mOI*^9>L&P$aCi);PUb7^7BrEs zqqo#ZWi!Md)eG z=>fv$pN*^_w~5hBn;vc4s}vCeF>o2%?fVKsHWLMz>5h5maW1=(mT0$1^Gg58kNw8| zwbL!Gv(g3;Utoo@-Uv)zFy8OGI!vNTp9nuuI0~XU>u-Qs~4MJgnrY(#k^mGcW?g9G?U0h$eEMR})Q|jL}T=m`Q zmDz~CvHW3A>yg-podELTMXc`UJx2LW96Z?yOJ$95*>{`4SR(rQouE6!3vHWSQa z`JDs%%R04(EC!9*1b#i8P6Qtp<*WMyYqcX_FRwhei`{uWa*;LqP$Pz@gM3 z@1ZfY`*kPm_CFbzw`6nY-`vJJ7R+V@R%O!pBQG4|GH-GmQhyY*bMM6cX%^Q`<{3!d zEio-}XGfo#+#~y}CY}g8L?2KQadP~-MgCc2^Yt2K*B%*wQOU;FRMEFN9}H( z9znKx=?Cz<@Mvdu*Y*2xt^F6LHdla0!u2V`vwdX(52*OCF37v0UGZe&c+ExsY@EH@ zk6_m&;vO{oz}Q>{UlcRe``;<>wqb$x0iWX%aUFi|vSuS+Ynj(PlKCg2aDAyfdk}#qP$t$19Jl>SkdW6pGczq80?U%gF5}U< zAG<|+xUGvkViMzAk0~tM@CR2XYAG%gO6FnJB z#yJ)Md<`1c@u8u$^{eW5aBLjy)g_H98@I3fI^Vb)bB~(h3HD2>x81ibfE%py17_u=r7?9`Nm6OaemHWCzYV2Y`Qr zJ_DM{?cb=5i!p|ad~vgYg+#Gh`=rC9y|8I9AVRQ5rS z=4I@-p!^|7+-v0lRcT%Wy~`RLh{yjJ2~_(9jvTh7X*`=dvcXYm-!B6NDWN=+ObCd* ze%fQN^!+%d#}#zfZvCy#Ko9lN|FyI15_QD4H}hl~3KZ3k2;RiEVzVJU|?mcXvUel^? z2=8Gpb{KjrtOw3Ntv2L)N7E5f$bQ|_iIc+_!O_QQCQ8QXxn*`_2vv!L|M;?QR%5Qa zKNW7cyTW2SKE)&5srE7a+TEDII4QT2KCi}dzq6yMsiGrb-#tFA)kf$|;iY{>@qtPd zkjs4D+l1qf5=4|iLTL+X-OWF_>^)cFrU|Vgq@v9Dqulk)78+;B1zZ|M2kE4`fl$ke zrXe9E``iAAN`#s@rWr}A$uL5-hESih%oHL%Q}wg^6);$@a6(o)cw<&Mw`0RR2oyu! zhK@|>j$40Ap%J+AWCK`Z&R=6A$!@wh9#ziaF;;V2ZXMhrLQxQ&01OlFux&{z6WoIU z0pe{TgmvDZ%R~0h>F)*hI#_&H1jpDK!S-~WU00 ztijT$X{H#mCelCtku$87;>3wh|``Hnq!uk|`7(!?)OZ;9(fW%?t&A2>f5j1_KW~1BO^BWD zY`MjUooDgu6fLUn^rJ4-L(){_nGt7)r{=!m7ri$ovE@ zN_?G7d-2lqeyKvqkcI4^z;a8Sq{1qUakt)x{>JZ{;^_++!g&sk#h1y}Tsh;kEaIws zm5lg*-vmY>yE@`(FARA$b*2GAQ6a80aZqC#^{aee`JGmbA3I&82ppcIo#&w`@92Y> zG$l1v277yn{)->rqEsk-INxbRYONcc^>j}`;+tY5L>}^zNys)N>9V>WQ(I|P=!o%X zG%?|@$<;&Sglva-lDuG>{j1zlDA7`LrTlVez?J?9=?$EQyCE(j`1K4b%AAYfYg(?K zzu+|k zc!BTL003NhdI!kTF4R0^)zdI|_N{nyiaPk`a{RPl`^P3ZzG?O5I912j(GZ6^m{A)$ z5x)>TIIjQHD&m@)u8aUlb>+z)&|ya4e-uuVi>ZC&T)U{i+ZLYZNfC~;Rb*CVfO>Lb zt1=%pnTaLforShVX$_(m-jUrDUkp2qtLG@cfF5(7b+&W4=GWlPeZp4I+;pNaL!#p5An!yZzjtc_!2lZJ5S{ zPbH*-`nS;}-sDPe!)1BR#&ZImRy*+nd-)Odr?_NCKdG8eQ+w9$3~O{s3p;?pmE(hA zrQR2iI&C=egX00iyFL6ZCt{zI%vX>Qk@#go3jlsHd;3M@Q~yMe5BacY(xU<&rDy_@ zfr7LbPH|SvE~!u!bnNg_$EaLwMZ5E!uQWIir5YL@6CY7ok#GA>2^)vFtN0yB?k{FC zBoG{q!7;5Zq@pO9b(cd{t1%QsQ882)`?yYLX*{qWxUGzgp)^H~BA6EDjWs-3y+e0n%`+48P?1>{R_C$#Sl{m<;9Myd zkpz^5geRfiWRGs?mMq*)x-71tOE*t}K@~DyA-K9a%~BIRZF=@qs%<>@9M6Ex+qIT( z7K406V*RJy62pHD5+_Kc!{4O@3{&Pn@-RYf#}>EV>jrFPh?Rvy;)C6if?aq5BuVEp zB`Y=A6nGujINYwlMl5D6l{@Wf$IC14) zFwf9zXPlxdyB6cl_R%gKV2U;iJmB_$tj%w5PFr;bpBE`b(%E|?ln)}>g}XA)Y8ov zcIOEl$RZ3wBT*y{>Zy&>LG{2^uRaafqq9zTNRIOi3D&ZOEat zS1pf2pe;PWHO7r&d@k#uht2KE_lGwah8_gCUBRDp6-xR)DKD%1{?mEkBgcCAE*w4z ztWmXWMPP#Ehu=4fF^5HMnwf10O*}#oZT<$k5oQhwo$n7nWR4rSW#67+2EF&(C_W^aRM<%1s1G*5F@pG^r->plgcW6Kd@`W@6xz`_XGP;@ z0v9g1V4w_%mZZu`sJ!D;3sb{&G_IW75k*UhWf|l*I>;M1m8u+d{2)d<;%yCCo!#O> zOCNDNJnyNC&ZKR=dVAzyvYDM}b5RVj+%B88st~=X4GOE04)OCSJLHy4Oe@<>$cVgP z8hPpOX{3SfJ#X9QM%Ldd3hZbxd`e!(mrUE^quKW2b9mBF)%5C3v zyN0AC%h}qWE{p4RU%0_QuTcBn>@+ciZZnb|ny0Okgdi(WL&^Dm?OB%NSwb3+CpI^K z#P~tTI~dDC$&cV#W9jjZVe^j^xda%ldJ}X)hA)qrmn4P7PDbdpggK8zXeW9J-oedJLS9SZ&~F!rYhtv@*v@-ZC> z$z3^X1%Kas0h%<)f8Nw{_dBDlc>~i`TE!DX>M#Cv_{kzVL-0pvjX78yfy!M4JZ(L^ zs#`c-D?m1Ejfu*dX>MYg5e_wO0i!f8B9jV#7BNKDIuHFlZ!XjK=#_IbZ7JONtC$d2W*P3=`}>v5&@_C%C$g*zgj0%98~Ayi^#!mM(0&XuB0>dBk9HKf4U zO-ieI68R@y(HvZy4JA2?hgN)J6C>1~?dzBJk}|FQh8OA`Dh6}KyKF5hhSff7M>4|g zCMuE~k@92rPv4&{b{h_mKDQW2DjW(7>^KQm_|+f8!mx0x*RU6VHAq7V#TNgmaCJS) zZyk5?UHRm`-*+YaO7Fqy4Zi~2x$3?@v1ER~ERvt5@(9A=u*q4~_CkbaHL+gx&ls`Jo1wXYoca=Qh`k--e zCdq{|MwWdk)x&oj%L#*5YWA@su?Z49xA&v|yQLZ2p-XsAyd%CSw(FH1$=6YT&(s7i z(0*dOsXp@6m+5n?31xT(Ls`#A8UZoF?)SJTy#;k?yS^}sjJd2e+o9Y1Mb1Q-d`CvhFU#&gTuwG`?bn0|6raTWR^D@;|#bOs%4Qu^zj<$62b2zY4orSqoT*Pt z2B3J@{@Xir6VI6W5I2o(jw*t()5?c6kx2h`9Jt9Ocd>+G=r?%bzIjqCOazNJn3EHe zy_&z`Jj!eGU=%j!mier8e_8F-usO1>{cM@(`3G&4Jkf;-%M*i`rs0)x%dC~5!pJ8P z?!%2}E=4`N1322{Q$lsw z?W3{|yTNB&%4Z$SG`7G*i>=R#%}Y=wE%f z19%xUX%Fj=wD1UP6f8bmwlj~X4)wxw{Gsp;>POOvCIa~`APm7X*dcDPHpqN3z!i{6 z(S-?LGKVr<-@S04#h@c1#Y;3hY!c3^bJ^^K9a62yZGPw#N`Gzb|%VA zJXiPsu=U16r>mF9lm{h-h1D2zcKtnhnSe0efC*<%{hMy9r#jJYUC|U=wnpwUH<5%onpWtxCVV9RX{1kLx{Chy zvmsZBj6~3OsB~DM6YWi;8>l$jhV(u?j@L$zoD?-%rbC+>A$>5=RrFw^rAgU?Yi)627dT^#%TOf8ix*It!Zk zndC~Jr*zNEGpQ5mEY)BenU}ePK=TB|Y1?1pFZ}ep&!o_ujh7N3>`zIv~UpaYKw4s##gdrXPp)SOAf}mdA}Yh zEyp7YT{#BXDs$8{vXJ+6A_NBTODeCh%F5Kki!jD zbB}VJZfIGE!Af^iJ$IHH24|ols@*8gj}FLk?|FerTvjCA|J+}|E5@rFwa6p`yM11* z<#{Z2^8#?|&6vfi7w3QQ{CQ!M^!meRGJ-@m=sTEKBqA+T<XJ#?vZWM^!=h#+-Ff=uWOT_za@eo!>%y5av`>#C5y}O!@eer zWtH-@(M@{@p{4Ea?Z{$PNRb~$5eFYSMVm35qJ^Ys664+_Q+9WX`HSl~^YA7pSN)^= zud9Hy=H*t~fmcML$*v#ec2u+|6nFcl00gF$bv3C(;7W|;?C0{>l>L}cPim+pCkeHw zL7^~f+erZLDm^=CTtSLGl|d%$*>c|EL0kwB2v^vo=UKisos@4yxw%@M|8qF zl3(|<(wZJqKV8Z8i82*xy-pYA;&tM2l`hQCs}4T8ODQ5cXH3XMG4E*n;UJ4|6{O3* z(5CdHd{Fnfd?9JPtwoPzQFc2Fk$#|}g=J`e*)Di^<;={JYJt1YD)Y^Eh3jvr_{4lWozSQ9X*d;xk@skd5a-H*`k&&ptc-zYIIA zO}wCO{&qeA)e5y!5eD1HQcHqw71g?uvF}>cwX)B8`E$ST6e<_m-Q1zfv&+)>%hzkUmJ8ea@LdY4d-VpdH=-E%A2;qXm!-bSvZt!>xj zR?&FAVso61i4w0?kUb5}A09G49%4%}<-R+}Y5 zmYcOX_mBc~9`I3J)MV+kkh-~mW@Jl)0|s$||6F(3oq`xwtETqddZK5=@@XO8L%Hk! zcXI-Y2~ctV3KJk^vLOuAh7D(1CMx%FLI-dE%{aVl{iV&B|e zUdBX~|L(UmidKVZ3=OVjF_@_q<8Hm~_Y^XHSd?JF=@xMy;QWeSD&dZ5@!*>5x6IDf zgn~zcM7&E&;k{j+=ZCi^a+jMQ;@F6ay1Q%?ocJkhL&b?YgZDK(K0VU-^`aI z5A3xsa`Aa=+&J z8Akx>tm@{lVX0+|Wni<;k*?f2H6H>~B<%2S2zN!GH&U;H;{wUPTaL(GdjI33q&?wNO zxEPu*eU z$2g(9rAopR#zd+%wfN@m2fSjTIl0W&;#ez+r!Mw z#$~eEd17*xfj0Mr&nE{a8TXZ*{7J}}LTn@f7YOKY-bDvyG+1r=|2~JhlwhgW1qqb@ zwe8;FYSf*vl(V=Yn{9P7)qXKA&dY#=u$*7jo(4N55zS@D#fkO=!8kXeXA7_aFj^K5 z!aXeOQNCECC-6yKPeT9y-)nBi-$x$R^bV97q~zCe)nYN8g&px_mG4Zy_sC^_{cOi+ zTAhOONRuo5{4Ol&7mUjpNNoSSd`P|Qq22nh_RUc%6rmh7o4LpT;=lIK#M^YsmBQR3 z+RA$uRD~|k!shwj&Hd)Yr82zU^A~?1^vm{M(p=%yn`h#c{)i@^D#o$Le%W(G0@pRJ zFPLcjOBQ(Wn)sefifsJ~YQXpjVDoOd#kN}fPrLG+x-iE#NM1XXq7*VvLhF%iJvl#e z&j4pbXK{n{_VA9B!IU>>QFfkqJLjWZ(Rrr!Pz41xuuRI6lytgKgZ%B}wo;>cBR~lM z4>6dtQ7kYFRzLA=p@O;A(UtB_@rsj$s&Rw>cI4x6EDn$rd(y-xAP-zCWbj|43FNHv zxyZ^&LdW!v&18Jbo&SJ zN)LskA0DgD3(Cs_^Q+II6bTrwdB-G`=$#LcJ<@)bG$Vk6uq263cEiq zr1-tQRqL1aUE5A6 z^(aW%jNZJ0I??~HMrcl_E=;tFFG*Md_Xlf0=adIpF-7*r{vf%C+K`*XQ8-gyv6m?CdrqL5o)`Rhkax z5^j>#PgZejJB$zc)o0&{$8CiIq5f)mT;d(7f0j(+xBnI6ySN$8?!>6!xUHXz8pCGd zD{3rv0fe)9R7Bx$S~F?OwX{>*mYep0QlEubt@^#4M?2d9C~A{rGDBD5{M8D4wr38> zf=ryfZC_A*xNA=Ouraak2_}A?1S_8&B@)-A!fN|nNHC7JOVUyJJ%bt~#ZKYxX-4Tf z-y351ps@a(9w`&&yZ1BL9gq{fcR}~37UJ4I5g+O{;bk@((%LYsXFr}-lc;<)tq}l2 zhkk$82+8xh>G>NvKpz`24kg{TOTt{=v_ENAjA_4Ta?rQ)O~k;~*At>9!-=+>$6TIs zLL2%2tFnu9aVHjXV&jg>wues9IqCKzKgW=E3_nwrjrrPi-)ZX>za^jADUAvD zP`Ac98JvWCHF|td_gLA3R$d`*Yf-Phiq`wP39`)l3O)$Z+_>MFVgpz)#gGK6v+$Wb3$>)!5d_T`@SG<@s<<+utMac6G z;-dpq@zg$F2{$Xr&5x2O44&$fMwDk45dabXU$xpD=1 ziFXmxTdIdk`#<+BA_n;W6pB1pl?3A&;_>6ap;_eyy+tNU09En~p1N8I{7O{!j;2?amY^Sx;AJG^uAE9BOXXWSoi>DNTo zk4*-9!=})}LK{x$5|Vt*g=e#!>}qxE3pzxXh_`W)OAK7gDrPhIVEL$O>o_9>qQL00 zUa89Vn-n<;fgJ81jzF!OF$2%MVskf?{?}>n+c%KRZN$xz5+gw%b}zw-9M}4Kx4Q z5PMr@n7SkSK{sprBkfD-Bj4tNo`e(@3|jOApV7}UhkORdJMl~C%GFAXjSaVX$P`en ze0YB4<-y>U5v4y1@4aaKP*_qk)*WYDL{Gi1Zd5U!o-B-E`ZMbVYN0wD{M`x zkF^){buI8*StnnUQ4Ha^U}4^PKWpsc7yVHLr=7pB`~QB6FF1qHBVJb-18%>yyhUpifRsB8HAG-VlPBuJ61gnXnEfE`dYjr)S_xzj zt#0?abR=Wj{X7EP@;fch~_8gg7t{3(4k!L`h^#_26HBImOEaQRpjzW(wPA?9g^ z-MH{Y6CKOLwDAXXk7P7+YYV?Pjmwa(+*jSM$BQ%M1g~rY=F{`z?O_KYk}c*xO+7`W z_|LV+bzRx4F`y^#&n|gZ4QK}wz?v2TJr07>s-XnN7?$eLhTAJ-j1viX=M%a71s&HO z^0tR`c&##2su)|^(~80hyISA!BE`?$L9i1hYPQJlsOZ)Tx16?Z)^>bJc;1?ZNlz;= zS56&1?-1+<0!pL!FDtkYrsNBohfP=sL}wdTj>$j|%V0>xAMG4m^|qnfK1Ne~0od+- zlpomjnm3_L;(gQJ!YKIV=J;|FQsaB!l!#ha91UkBvqO!eZ76DD#{BS;Mx=&>XsFNO zAyc=9Dw3b3BZq;BM2YGnKSj6Ie4xNsTTFqQe#0NT@^n{BF(`k+F1Mt@O3y7*9nLf9 zz8W6e_Wlj22fCJM+s3FBr_><1T`rs1Yt`nxZS5PemL>ViNzL-#dt_*%Zi~M=R^I4v zw!Ee@T31Sn6Ab0SUA$%;Ebz7Dv)jS|a!o+DO4~@KBhSc^y4)nG(EQ%M*s$bLr{J|o z*F|^z`}s>&Xj|ONZVn+CaZ!is41UeI(($c~&9LwCly&6h7WjJhM;*+(KE^D<}uTI0#ZW z%$OWnUWFl>US{PkM!f3ed1h0A9>L|cnGpe8t zPy0y#uC@yTMYEAvnBf?3fB(A>0babX?@SeECACLY8i}2rKOVnZzfytb^}4Q4`-uz( zL*cSGzBiJ!YmqiYSq5il4Jj7iE0SCC+8MR3@PeU5FL$*XW0KH(bF}7`UkJ>Zc>kivEa9JU4Rrpp9-mL7r?DmQrUOX}hyk^mmA{DK+orG9EBoD4XT zJ`NKj6Q8tvILajc&7Q%))S*#LTHsYux*Y?$HGVV|136SHejq~Z;4(kDzINS$qjP1k zF{l?4r5N|xB_qOGSgAe>L2Y6RXh0gg(6{k@< z^9HNpf`ewkFX<~oJQR`YQp`317nmMn*NlEpjkcOIgr|zNxJws5UQRWkFOF&$;;gjz zCBpEk%16~mdle^9Z7<>i)$HFB1T5(VuJ&AWi}bNp{?2pZe~#o}O_i9Zammc)65cs`dBqFxrH<3FnAb z`<`5&czeaJL|K&;CwSPX!!ZOSH{QS}Gm;QnI#}S!2V~mu_bX9r3o*Qu7XS z52x2@L&->QIN2+qI}^LCw6Fh9109{_c%`v%{?-(KF?|mCi)fb_y`kH}{KdpxynFPD z6c|)OY@_4p*YiP8?+yGY?wV+;c6(o&20Y3vY2YNZq(jQDVa<<_h2&;@uu1wV!I(3V z)Pz=VrpJd3RKgB3k7RAKBT&6KvGnPEv&ihPx|9Jdggd`_sW*QJGW1;iJ`Cm^1bYTG zAX-k;+-TkJr;C4~9vu`ETEKk0Dr2`BYFDWJO4kT}#_Fwm>w}I=mfr@j`w7i58&MBb z?Y7N(>?SB9KSM%Cw9{Gc7QGb8dl2iny)4$pM~}K!rkr%5 z_B{&!CBs1-Ti1FyuYQ>h?U1*5a=12`MgfY*g&A|Z?PJe033x1h)N4Bg%AHZwA^(i!3*FO3o7HAxT=!v~X%Sg7@0`8^1 z*Ge=i&C?e|`Nq^4Hy$TakhvvxV=o_mk(80HdDfF0T}#~{8y~`Z#h}f1HVTTR6PUx8iXnHTvbk9#d`jfiS0bihT`(BWN z!rLW#$W7*V$d?5PY&!AR3*@u7b_LDY1P0x%wi$V3U|m0HZ!7Nk&XIQ05h#uSX(E5U zNeMpFWwf}({j3m^b^ecvi3RgZNvPLE972t>Q)F$vUb0difPL{`DzCP?`fXf1ges?>IHdmiB zr-IH^-SUSw&~H09t)AX`rF*&{=@f40^(HRePfmU~*bzRxc@<&Zg%K9&7 zk6Sbgz`k|`G~|+qu%GvPcz(?Jho8>4b7!H-$WpPsnpOok1L3FH0FL?KlP0D~bjqzM zDu7ieM6~a2{7hb?MbL6gs+|b)FP_9Q6NQ?NcCE{zE<#LgQ_SZ?b?2a~_Fu~v-3-d5 z88gE>!u9zp>Wp;R)S{K5(LkcEC%~+1ACC^h-@B6r;kVbdirkx~BT++2NSgpus7W$xDT87AFD>8eBDx)|LhPPCPgu#IY5EVFg|kyvDoZ}W#pqaQ;xEH zOlxbnRVR{ZzK;?fBerVi(qwhk?7MhH!S`DGh9vfZ4BLea{) zevwhXV90N{TUoi`X(#-HrD@2Is|L4trU+c5KVzjBy1u_u+A5^nM%MA~w+cxe!1&gCc zAqkoESb^Gt8Dp0PJl2$m;E;>Au4eKwFR_TeUT&M^a#VkB{mAmEr2=gy-icpqK~W=B zEw;6-b}|0KRh}Zttfg^bJ_ACB8ifZLEUr;P zT>R(4$G}+RJ8q&w_&I?gI1m5BDDTsKvnrm6jR}~1vW5}jB-gg(zogxB!4D%QtdBdT zoO6iIoefQYj}!3@doM$D^Hkb~A5#lWmlL{P&YC+U)ON`=V_g1pk z*>Gp<rHn%k(=^qo)!$9rH)+#Fn^GHDb_DG8r!kyRwWE|ws`O0zr9zx z&i_cJ#=PNPIX`A}19kXSqr}#3TQ%gzf7OJyq+*qRi0-+co|<}^@n1Jz`z<_?zt}8f z9KuD~?GaA(oaMk=RNY5RcN#b~8*IBWv$2uy7}ofoM z74ci@{Ey62|5L^qp&uJ8EkxZTz@W~|^g3#?_trlVDhLYhlIghT$!Ts;@@;K_&3(*q<%lqOvg5{BBn{D3%7R6NjiJOa z#F!}4ctQGS{{Mm<;z4dyso1Bue4NwS^<;m}9m;oCnMX)vMgKhcX&CWajwY7@gw)36 zRvjbl`!yw2sO0yiR&z2Vo^01TZuqy@?o*rp0qN+vJ7dXPSa0)f>Ks%2%I3?!`7-1mPcNFb9$E^9Kzyk)j6+@2enGNg!S z`Z}r2L6A;DE>lS z+9?7&h!+FZGvuY`73l3`wl3)z_WHffZXso&0*iXHWrWhoU(Bi<%HsYT@6x!D!Jf0L za5xv(dzS79&`w+jLrWm6juqdbdAuVtD`muw;*wSm0ipl>Z<6;NstJRHBEVRrk*xwG zUYYPBpgXgfevZ}*&L|~4nVlkAzo_i%MjXK05EpY zt76My?(Zn=1>BnAj}3dVXLIWhPZ>Z?HJVAX`%Gc2Z%y#`P>7Ql_0FBz+RZLfOm z6-zm5RZ93u588Ej5WL>egH2q`qBYuoJ=DZ-Ej&ALzFS8vPHY(uUh#qIXrXk*GCo5y zPveC^*RWWl?^Zh*+SCi&e0=0hEU!-6e~!FgSZjlUzrrf(nNGNCHMLQI9~ek+PSo?I zJK9V?^?B@;snC7kT-2ouT{b|DpyI6_tT4A+VtM+m>O9#F{hj4cUq7Xj6&@~vH-&&b z#UFdz>5jWWlo|^{NdlYsrCp0%lG9-!l>1Izd{K& z?XEC0{R0;P-*D-dm+za_y}kc(t)R$Yb#J)+!1&a8iTRURhm)+srTUX4x4qNX5;bPK z?*6;(i%H}rwF1;b z)8-E;;oZ`H+j%DC%l&^fBM{fMLDc$h>-m>2@{0Q8A;)tGkSe{HXDZ)ym2~!ecX3Ir zw#PU6Do8XOS2$`?aQUZMcuc5A1)s7)jo2zRxy1(p2s=M`?@Bj;{PL0y1fM})Sh98; z6?5y(&QBRyfN0d0vu^vpuvHJ_=S;g9Ekw>A9yL4JmUkA zZ9rwmDp+wx_F%ZB4LIcq5COnVr~r080(3-oHqzRNe*6U2%B(I?0YaFy?+p>@be7`- z8ddA(RfL|8(l}TZag@v^cfYSs3I?1RM4MZj+)}#vuB_J;dLJ+_)ci4jU!?X??a&k3 zn@9tpKa^-wF#C*3_hK7hlav==x`0?>gBl#XYwIslR$ov9(T^OuFX&0Rf@LpJ+zeDG zJ@4-s=qmCJSuayIKLBK;fH_p`bVJU|hg1*8YR#R&KZ1K>zI(YcQ@Umq9Gicp>phgJ>xt-^u-E^6#b zf?;3n6tU1Vw+FHhtF36JPIpgFOhOI*Vl!+3&<5IiFNM}+ewlu6TWBMc;IWm-K0ZEk zRl7sn93H3@xw4Dqn|`zleeH?LRGY2Z(VkhIPh-w>*Lbhk znh>BYz5dPNgB+=ZeNZ)gGE4L|CxNDD#;=!~;&k6?0)AArD@1yEU(m5yX8JipLE^x_ z8&qtFu*+kON^EX|i88OF4d!a1AH04Jjj!S>z}g;2G1T|-=q$fKVH~IhSBmOpa0gF4 zaSh-&R#du$BF8>@H=JYZSuX2PrGY8+xayhsx*k??Q*2-rOB28`3gtdzU|qgO7YySg z{uS(X$EukQ!a;_7%NY9U`L$7L)t|kCt-m$DEBVm`#shF>$|Y315oOi^s5`lbM(3_R z)in(?UCpVqK$c0UKtLS<#L@fVnyh1c_u0qb>rHRe#e_n}E&Smf$lkJ}IuG4Qc_E6; zSCoVoGS*aH=|Layt>`n$G4kVpB1EFx!N&6GN~w_E=#;kaqRxs$0JZF&hAcj?G}%v{ zYAhar9Xs;9GFA5oSZ?X7X-6|W?oeD~w^_)qL_l)TkOIv?TD8;f1g_@lSMv(!z{n10 z5>*h4HBO)aL8?mx=aL7-vl-)5+v}~s7I_0;*m;+nDWo%hy0*IyQKVcTi+{CPm!$dN z8qx60`|04jy>MJf8v71taK@(QbRkH;%MyMm?j@znVZ#fLTUwNagu-P3px zHg+T;X|s5$lr(gD6{#u7D{9E-=0F4M&#ccOx!L{P>~ZaJcZ~j)nMHh z9ZPzFwf^^4^v+MNO*-#;&x58Jx)2a3Edb#;LjnfZC{y*JuEPeDQaueakP z=WN`({qH|F?tw;98dT!`>n#`ow6Gf@*ZrS=F%5Vlo)87+Uq4|Ac`LM`V&@XHx~mjU z)+5Iu7FNC&VegjGXq!Q7&xs>*Hbj>ghZti^bxiC%0=_-Fpmfaf zC5Nd#FzE;f=bMUg=+juy;|yg|PeEPKe>4ms)^^-!!pQGh*YA`Uxq`vv2BjjItHD=k zEd*76B1hle6RLHIyFf++Onf}xQQ>&rNu5MXW~B_eRdHoM0QIlm7a&$_b{(&;dII0y zaGmlKhHsUpyZ)!{6gX|!_3x{fiabV>mk(YDl{tI zeJX&&jeW0y1kaMb^s)cxH=h#-)8Pvqnz*yf;`ErnAD zw_XnrTFYtRqPzcf^C(kEeWLwAuO<0`7Isz?;|)fyxPQ`0khq01;0$1FSeFnW zbgE8)<5t37sK9rNERAG84lb5r+xo4~Lgg<#!S-(Jd&@&r4ygx5FGGt@&Vh~}0bEhO z`QG3ZF$SS(IUD6j1s7T&V8>N!=`dNj{Z?&zimOBt(vLFww_f{QT6ib-dGl|P2pK<7 zB`Q6p4G1pqz4t7WS;kZnk-;n`~`k#wBPZn0mTKkgs^#P zc56p>SJTxVKJ4$CMV^|Q$|vA$>c?DA_q*rW4jX6t%_$O(rX&~57YL9G53bfz0o``( zg%0@U2>q!;h-w3WzyHHLQVu&>y}vhViuu<@F->{)Ot5XxMOu#zbGCk9IC4bE6l|tc zn(E93Df@#Z?>V08Po-5*cwopITp-srbNjDpbkcVhMPMHkxddYsO(QiyrS90+bM3 zPG?C+4~$jk9v68%cK@3)xYY6nhS*X+0%W}T_%EXMv`_pgsEC*Pi3_$`*mFhlGIeN!UZchvs za)LbLwWyPhuU*h|s9H_l2eX@RSGlxgeETF7rE5aIKa!er!VO%jiC zR@b;Q3C+Iw%Q$-Pz;?wK%rmeJeGUx{NA8(|O%n9qpskqE{Y8&%j+9-J9-$(NxbbZ8 zPj97XY^xu67w*luPtzxB?Uap~o0!{Jv3QM6hH3;<4#jJ-^3d^%nSZc_wB^l@ zqGPi@0^}Om60@}RW)z}HQG};~W6={3cWV3`*aSe*8&%+#R5%{k;~=j2`eI|+4LS|@ z^3PVD^f5V5`L97U)K`JgMUCQQ!Qqc}RE*~-*e$9o0|Z_bP|e2$iHB;;k{a}Pn@wde zk0~|Kw){O|LT4rKbcPY z$hM`AiaOf5svJ(xQHgZZV5CcWBt``;u zTuj@yP60f7flA@%Pkhqf*fxY#Wx2eyyYwi%?$P1B(=r2@qxuvMp_KtPR6&VE*A=~$ zL9Jl%1h(im&Q~1F@2bh(nx1mVm!gGCRVOP9UlP!S9DYe#Z9-k}#jC=v_6jFWa@D^qR=O0-WW z(`I%{agoE!SN#K3`!qf5pQ&1^7T;VEa^3Uu2I_xgAs?1Z+bA`nk*X`aH1}n^GTjXi zsVM$HYmasjimTDYlVtG)&t!O>#XX>Zv71_o8CY+HLiw)~?k$ZqS9y-P_*@SzHtcH^tBPBvII7B6Q>N-=+0~T1n2@yLVGfogbD_EG z1iv3u;AWdC-pelCSU2*Vf9dXd{D&2b&n&+wUe423KK70+&~CDr2wuzc^HN{i3ObsP zbwn_%s68sb@TGkF55$&C<}V{Lb2Mty=iS_!j$9KTd(jjxqWB)Q(r+xP1p3=U*3xMG zXZ0PyOE7oh?U+mZNz}9Ge0rm;*EXBB*XJ{(!{r`oi7#f(EeZ>BZM=5RESM0V<|rbM{FxOn<9QSW&tr~10s zl@I1Kzh6Y8gr%dR2zI5K?m+Y{usj(2yoSHWE&!j831nHg#QIn~wO_uf)3^_X+4k*3 z?b@0Lj3cNIR26VWNo}SK9Y!ekRPidUZwe{}C3ie)5c-OZF1%=s;;=braO&3Hz&vP6b=M4B(mIydYCbv z`DQYVw!R&=S)I-YCs3{e0A1(RVia*z*vNa5t;a95Pb@x%FH?K}k`~SK#^pnMDrv?aK_}F)NP>Mf$B3i)kdLb4^_8>zH4u(4#(4uZmQR+Pl#% zSoKr1^!sEFha^`mq#krIY_=VhuB1*Rt=%I#Njw#H7?Brm7CSnUWR}QrXi1c9B^;`U zg?rk_hGm|1+HTrh^-bpMaFh;!wLd{hQvJJP0@z)mTCaPBFEu&%6sLt@spxZEVf~jF zDRN-by7p2+jRA^ejfw-3s*UI0HGH{dB1J^mC}S-U1s~9DxWY(pM=lD&*!NdxG{`+* zP3jp_?c4Z5%Cldlfcu;41$;)TdxY~L5#=yN8FAl1;0?z*=@sWgU*73)xOdIKHdyiYnJjtV8*FXjs%S4KIvkFlbZg)mX}roK ziKHHO(S#sH`R($9BH6Qq%eMKwEv+M$&nX25os~Ark0zfhSCbNTK|5}15t}#q*#!Gx z>SsRJTL?s5G?da7$48#&br6O7EbzROQokO%;x(PE0C%6~P2zN26@#PArKhW&*8|s{ zh)9-8uSdU)3?q&&4zm}3MbIF`XQTZL^n0z(=6EVP%-63g ztA@qMU+dN%=a)V4#J7V5MEWH!6uIQ&VN%EA}^LKV2Qw&08s7TlhZN{!-$-IfN4oS40Z)Fra>I}iOwd_+G?&!)*IQM3de z>r^myj(zIhN@fX{`S#dcd2U3ds$CGIEtLGAEc@XEV=s^S)36a@FYA;tvRJj(cG){N zk?V}GQxydPs^oMF2fNXGZUf&g`0^%-S>y_idinK#dzHRlV)}9XK=a4IBu{GSh2wrI zx1gGN34-RNY@K5I`Rz`Y8xhpqtDe!J=^S83r#j zb|pE^mf8}V6+VtQlOC8J0Xx@prC2Eoa660PFQ275MLprxkvjP3H*p_#7Gmm-or~@;F&TzB6=;OcFEXo{x(* z(RQ~IJFOWPUI z!Bf{EgY1RyjDB}KcSz|7Vnn+~+< zN39yiEf0F`SS_j)!!laBeG0MF!G1UlZ?|E7gVAgoI#lGUjx--{Mf=%nqS_0EYilmq zG6iipabvU&p_I7XW=7Oa_h_eQ&Fi5l?$da8WEGgi9v$Os`oe@$5%Td81^HnGEF+Fr#4AE#$R> z@p7io&FC|}gVYpcv#*GGk0tDhMSJ}=Q|h=#?PQs9>7|N@sfRU4e)nC&6g9l_>vHLl zknZErXv#>n%QRvP$*WxT_wCV}b}(#>){-pJ^da)KGTF}dA*$^6#(q*427Hoi=dC9M z!y;MCjkH9hG>SQrx$9;fLjn388F$E@Vp$dghM|i5tvneZg z3GjT`Vs^_saNIs~i-L@*g(<}=+B5)8#J5M6PbN-0#FGEApdobyCe^=s4`~4?Qh=W#L@&~8xD4LUr?(ETGl&R9K)0Lhs=N=*pCfef}8sab_ z-B)Vme~se)Y8-auWganCfbjTdlC5F==vwLUYfQ|{2cJ({ zp6tVUv&fGun_-9BA6b7R8b~i!E(F%a#2HZ@MRAPPaHut2K|esTtD;-)_1sawwf~Bo zdOu+!cHGDQn|u+#NR_7CHU7SvbK4W*fNCq2m@2sTW!K znYFD~Q1p{b;aZa{?Xdof;%8P$FY{wXuJ@=;Yh-;c+F~4G6i-akmwop}V4(1_+py$i z65w1}=Bfmim=ZDfk%yb(hOheA>-rLV1T1?gr0qL!2CuPO1yc^LPsW^5v0&tjg%+MH zP_nPFas5N)EIR1H!KVxG^!+yrvqLVtqS6}dpimpVC>~IkwE5X#mh|*SYMo8#9=b02 zx6ihw)MD8g#fX{0Ff-Ag$z@4$AE+;pJfft_2Vr_h>uCHMxcU1LakYyX zffvr20p>|UWN`iKCM}dox6x7IPP+05?_pv-h05Z&MaP*ei^4fzAmPFt;nas%fr*f) zhHOPD7j@JBkG21dYT|pt{!xjE^e(*@DbhiyN=HBtP?RDqNDzh4o0L$33QBL%ixffW z2$2r4KJo)NB3o|G>2(4&J?r^j zay?TU6_zed>b1=m8w2wdS-DNej=HqInB+bMw9)1}bWm(EhA&%Bv!7+=X%|vYI-r5J zQF`-6ZaASQWTh%7MIimH;jq!^dq%Hit|C(O0mF~-8*V~ckKuqr(A-WD{_%X2$e9x zhL2wWYl^*Xbp!UuQO;1X5Adtnj;1&ohwJIaX@VX~Yr z@pt}~>SEfe6F;`|+YH8@!Ypn{Er8vPZXTF&W2rzA@?vzAm4pKP{N2pZ2qoQEbi}HtPF_s3vJWh6ICnNejA~e(PHy zl|@Ape9@Jv&tt){!yN$)$oK$g6akWZ<+`n&^i3W??0^K6Tu8-XVi0J+JM&Uny=m-Y zA$Bn&Dn;v{zJj) zNt)_v)p0D>jO|Qn+xP1`PFGQLV|1Z47gbcuQF0+00)xZXiGv4(8F-FQ5%asR)N9(~ z3vfq(x&U_@JGrujNu^_;#xNQmU%l!u68*P9J#;N^c6?EeTM10q#rtuMdeQ}=$6xu( zb3R_d5+xIuwFSy#)w4giXjnz-(Img}76X>=Eq_HtU%0IQ!|#+?n}Q+@4W$&^8=1tp ziq*mDI(3zzlAItvj9>OhF|1iiZ>Qg`Qn%DW!witEvT%%GI`?vx%W`ARC1TMp_Al%_ z2Q(3$IutP(AzhV5d36Qx93Fd- zeS~9P@^}8kCo#CZ^_o@fAUxw-CC@I^c*43*YsX|T6RtNuS%Tx1>WM(mH9LlKo?RLl zIlo7+b)TDTtDoebT^jaIoOq9%tFWn*d)G58bwG3R$T{s>WDmi`Si^>R$CyBiHmK|o zVkEVCYFi_Q_`=OxBPtRp0q;%4zGP)Q7;a7~-tp5&UqXKIiF6@EZ^`KH23#$*vs%g| zzx61w@C7dxsinqfjcHv>Y8&Dkdta#TR(paB54exXpADk)=_&S}e@e9%Z+JRbx#Le9 z_-S$Do)J%HSk-KncqxH&Qu_dJj~a2CPc+(A*~QG0O%%KBCHc4Wm=JG0j@p$*jmWos z&(1WO!HaI{!h0VVx-Vu2t$ISv1=M zg-s+kQSy0C{rgY$J8z1Onu3iCnE~tkjqJXZ#;|K-&tbo4G{P@@k=MQSGMNz`$gL~% za)(L8Yl^ezf`t`QjB(T(A3?*)DoIkAPycGJ9LCo(%Uf?O-Q}rVA~A85?6RTxEq%JH zxEkMklS+?BL`x*S5!c7hbp(k+l5DDb`0Wpp;m>!nB|bZH6s6Utc*XR?wSgej2VXOe%5R!Eu}cD zI#*RSz(Kk|VBDT{4_6pp>FVTgpMuuluZ}W`D`_QJN7*h+C8tAm%}2i6uB1gs}?e5&+G72 zJ5M~5_ab6e`jX!3_3m18-0Rg;-CSl4s4wK&`sKRRv*z63I-R2lT_c1Xl@F~f zSh#j6jtak=nPaxZS_OH+E2zrVZQ#zxcOOO7jU{Sv9#5m?6W+@%E1=!Nwa0Nfu2#e?>aEM#i2RA)T3!_1WNFC>!9_{J^L`{=?E zMctk;iWvhC9PRs`l~D!pQIyB}qw&2ljhKl$VIo;sK9rW)KaV(1 zrK$}&`v;)Wtd8+@{m=0FvoD_3S5wYwD=fF_D9*gUIMpRoowFuUVCG;-%A-yyo*j6p z^(3#UUt^zTSvQ4Vam*sDNTpNf6v@TmewGma?ZS5PW@oCc3n^C-tan>X+TvoI>}`d%)Vr z>GhwBnB%W(Cpj>_({-&pJi^N3+?(7 z8cZ;|tRp^|F^v43lJeMn>3)5IIGloJK~)d49w9!jmHvc}4K0g}fTt94F{dwo60f?@ zv(kE@1+5d_TwbaAp$u&f)q(RTi%8El*bE+K#$$>pB(1Aj=eN$!X3kymAmZ!NZfH_3 zUlG$*2nWfl^*jirgVwvKnjgMx+JSryb~B4$M$t|pN1YYMGg zF+La5g$p)#4$=E6OX+E)cbhM22EB|GRg_|7?0ZN>cjKY@TZc6v*;u{(F70;QRBw}b z-;?-8P1P0eRwZ@wJ`PgN*TGNbq{#@&QL}?L9z-f>hoChb0gswDfIQt<_~y0Bs8WTy zlu5ClJg-?0@BEnFUTD&EBGghb zepWw|!=5tt^)>U$Y+P4^{njhO@Nq|>J*yReOH3olET7t)c6zpQ*-R4h;4`SsudT$F z>d9=)*hsO#U`KxfPZr`Vxr&Q%-nnHty+%Mc@RqrAc-Oh?`C9(Yim58s-f>^&3*@M~ zcwMa98wtMw&4i`)@r7X~<&xhlT{uv%36DD{Eb*fhWPo90#T_U z0x@e>TeXJwGJ**_#~MZmBR@U%<}dz3k;4}Qi*3A>-etz4s#904-6G}>&TrTfk)Gwb z7sqn1CWj=HKy|g~hre5X|v9@r#Y6~%g*cNtO<@>;1bWN)R-PWvYd6c?b~_#Qtot(-sqTuY)ZzJ&^A1T zJ`_Kupc=`Qzts7oVO1D4lE>~eGh(^0%4oA3(e9|#&*=TyjZ}T$I2P@A2#*G=;2Ey~4KT3!6Y)eNWsC(GjKa>$;*HvtKLXdf#}J(vU>Y z4z;44$9j?Eyoe%18hxWz8;Y!42_=Z_k%oK@%Sh|Fj2jz-kRxD{l?yR2J_x_7Hj<7M zfsuvC=F1v$VlH5KI4?x@9(lb(+n+L$5l91`M4s^muJB7~L}B8iu1&bK#ABLLVfb4l--_2-U^u3)2egGiOlEs@K%%~xG z%I_pwsd_j$#oPgK|Kj}8TvMA59UiSMrv<22lErKlOD$Hr(6OCrr0=~7K9rTcaxu`k zEj+BNJ&ade;F2Mz=!%CF0$oDnyl0DM^Zft(EBTql=+`Wt^ zdt%X?1_%9Ifo1(|PUn}py3(JL<}8{bP`$b%fL%35pAIH5RzbJ_I`Qt;T$_1;-L#xB z^R{7rgCp5>AWNhy!n*sG9l`v_o_Nb|rNs2(cZKaoOUoQ;cZs*0@Os3~{gk%%RlBk4 z1yv}NT-Bw$Shu04>yH>Ck7(tSZ@g~!*pKbG)Z7yi2_2+=-l+~K4Clybk_9xNu%_(% z{GaD$@uWGVPG9uB*qKr&saUDmgs{)^FN$h#D>`bBN1839X)!+$%^Ud;1e0%LJoG-% zD_cuej)a*FcqVbahyU2){J4K)hngr*Yh!G2NmC^nO)A|V=QqmXyU+Y+Lp2W){57;X zl5#lCf5pE-*19T|i0J!(3{B&N-a+*3D;ZZt)tn_2=j)Fn zqnS=uO7=x3Dbzlf#!k$cwyx~9sy61f5ejQxN`!^UhlxHx^MC%`!=mX zXYGa4jw)JZzS%2Mu0?9Z+ipLMPUVCqHbw##$|5E24~gdQetJRe+dN=Fomk_QNn%d$-^d+W&NWhCpa-bNwUm12$nL?Y&Th#v(}Br4?AkK5D8Ub_h(X^#Jh*D z)9h%6qRe-?jv!ojg-&$|FB38E^EprN3OA0(?C6~1U#;*o+piJqVS^;aZwJ|bTTDrKGCjfl-zC9DusQRX@G0rw20`t&f!BpJi%?V|XTzdjsrFE34 z966-5BQN+Y4&3Yp1i0{G%>+?aCTj|9dbc)unak;<$rtBIGd@{7x=VshOiZQL-3R8l z@v_hn=5s`#965Z zSKbXPM4s1oUnfT2@4YP0!Ay$hpD_=m?9oa{ggab|s|f3IR_kTzi2`LgXwX(Js=S47jw}KQ@7umDhYPpKQZo; zEfR2i+d9_;*$O>GqV8ln{X+4;1r|ce`cFT0-u7a5BI0*!+bf6G{GnzE+>|d-V#hVe zH&lV*5z^|$=W@fz4=kj3I4G=4N)NOMX;jh$?$HgK>$aB5 zlnQ_eKnqBu0%Cdu*$2mTL_Cy{Pb-M|V5bwZeDFwx^5U<* z8^!juQ{(R$)c@NP1HaFQtQvs-8d*74V-7rcGs#%*i83~(Ja>_IxVDz5e2e_!)0t|Q zmD0^vnC7~Aw(bi8DTp2Ze@n{&aKG}0jNmgcy$gUE{*Q1S2Fy{uHYCiR{Y*FuKMDL1 z{QnZMi;)Al2EyO|Y57V2tST|(nPki&Bma-49e#y`eE$#7!jv9O$zu2XQN)~v|F{1w zek+R&dARx+P!n&gO##C50ucslC~FHF7=!10{MJXUa)W6X;0kbw0-)9(_)85#9DpEt z{cv{%1}l=eIxcpSjdq4#GawiGX|wGZ^Mh8+Z<7>6JKEbLz<&rgLZ{LnBW!(>TJ&27Z3>-NLS-33okYCl&3J1S3x(MRyK@Q{W&lzyxyy-qvJ89tE7QlkHS^yh7&-+IX{7s&n_+OJ9r{ITl%hG z!zON3Wr=f^k^EQa`Dydsm|c7G-_MlieEyPLS@OG|=1K&|! z0PzD5s|I_1jFxu~r?Qi^Q6Swy>EMl>z72q2@alzzE*sc2{i;VTaf3%DQ%&aglJ1}8 z0l++9|L6uNFCV6oOAcF?uKv3cPMLkdbOA}Hsq^M|B8{_(53o!*Gd2_V@0TN}cKpxU zcZUs{0n@%F*GSc)`DF8)Du?uT&c&dAr{9;6nS2}0xS{fgIB<9ASg_$2&GdQOzq2jK z3CB0{^gMu##}k3R&aO+~bt}Sw>t?x>Q(a*T&>fr2AbWefd49I(mkl6|)1Wfz7Yzyv zWAOp0a&xYTK|L6Fo?yXAwsBj0p19p15JFt>PpS-%C0o;=!fFGM(^~HRLsnLg^g_Gb z!LOQo`Kkv>t86cL2n4oTg3-oxPT7(GX0ZXVNNfKjRG`n5Kd9ka|MLp{o{E+ z?(sB;Qz~wQpHXl(goZ@*{A8yYNca5&x}RiLO@Xp_Fj;gO^a^mB_8oIwI=nquXsoN^boQ^S@a)h=Ms9pL_x0$*DDePvi>uBtz|{P{3bBskQnGcasBem(Rc&yM#q^8) z`x34N;ZT5O@$cdZ4F-K2d=;9$$5!g1dyPRP#VuqT2(9k?5JZV;=Kwl9{V1C(YjF|s z+}n5GOelRQGke!MG^cjHqt*<{^<0C@E08J)zq5YrzMKBnJA*mY2f$r=+&#$-wt-&Q z*}(qe!IO=~rCe91`*~26Lw&2_R#75A_B`0Bda?Zpd|#;i%8`~^7xDt89K32K1fQi` z*0Lg!n%GJmKLep3**3Gr;!kB3Lx3afCN0jY0L zFSEZxi~6s-O^(yxKTgg&DZ0tgXFPHJoB4!>F90K9@=R9R8ai#R3yuM;L4H{>Fnepy~EB|v08y2=1rb6{F8xa6VsmvaHO3o`@5SUF3Z ztj(w$+JN0%KGK3`FZ8?_>w@m?a88B~PS^rn%=BRB+0OnjRi5u*=-;VF+-d;D0qg)i zXl1eX&^Y+{sjWV!+rW016IEXmI&=Tve|BPo_grcNOg&e@>_$JZxWZ3T3)Ir)_2g#-qD@2cJ;Js_TK}7K@+@e*Fbx_@?eCBS{i}c4 z-q6c4nP(v%+9SDq-T(InzUs;!(>d6+{`=EO`^)n$*q^SW$gl`7@8f^}#RSyfsS*EXp8pOsyP=6T2dz5( zcc#S_8M&&y6?;L=PrsYJbk#E{b zS{YYi82CQkvE!VlGo%G(?1f+A?03>6`}fnKRIBD(a}WodeCkaLiu54lqa)7qv7^l7 zldq4khbgM&HalD&&(g$rI4`lSYaKueW~&Xy;w!u{SJ`3BAT4+sVv-GebdygA!f8 zpsPl_`wswB3i$nkMKUw4I$-w*7>z9s{^iC?HmR_%TCL0dJgqU0+gXU$wIO|c5tY9* zzYDl%6va-`0$BRuAn5IakqHK}-lzXWHTK8=_~pNMDj?jHsZPL{lLm4GWDDoRB*Dbv z1E315WlJy){=@jMIN|(hIEz>k7}5=JjP*4a=lmd9L`fbD#y7Wu zgF_p@+V(3A(LV!WMdZPQFzi-RFSuX2F~@WMjMDH;7IbwJEO$D%{u4z%IP| zSj_IIrvP(z+-xy%{ULUYo22hwBsoB2ZU89TVE=7%Gt$(pyXU3Q=RQkdQAXLY+!ws- zA)0>&;S@s{x%cJS(}>wOXB1)mQi6vsq=N1L(e};6l`^YIdvA@fn4NzOGiq;v_AH*~q?tZFQ(pO{F3LzHcCL60Z z27PAC9eVU(#8|DBzG=MU6d;1DnhYcxi;ip-QltQ+Rc-2I$kHk22gsyW&@Oh}3$Jhz zW1bjbj|9AI%T-oN3p39H&vx==mvFamJJEEoyWl0B3-GK)M|CEiT%y zBuwKLeFj4q#h;1}VqK=On&M-UGsDsg2Y;fa+(=fzI(MUS5ao7Y2aKI#HZ>k5X}pnh zmrsy@Si7PkYStPT=>=MTe1d0vlwj!A4+Sa^S8VDTuPr4PSs&AclX&h{j8mPuMhBe! zVtB$G6`;msNyR6SEb&(}MUls~?c{7;Lj?>)aE~(I#3zkk3f*~89$(%I0@^z3o7U>? zG4VPVlm*IUuDY&jnHc!Red8{%=Vc^O`{TT|0?eCyMg)j4hc!x_W1Nq@RgcF9F*_j3 z-3+$8I|m?|pm1*vFuY=%IPvGDo}*GmY-zWPU!7iitgy;W9E!vo^_yh{fl1$bnBV{E zJaD{pjbpCM`_+9}YIMqkCP#iVcRQuT2ShGDzF>AkIe8}29NA7s%LwmTs*Pj+B@ciY zDyGa{e!gP980C|p76J}_%&G(|hznyn9NO@EUyN5L@8$0%#^yyE=TH-BxU?6+f@o;{ z(@aQz8k<1voB?36sCzv_a*w72enQXC;swl0`^d95z}NAOM!>{K?$32#bZ|X^WiJrQ zN4@pBIK2%8(#&>U#j+$)1bC+(XSuSo*-|lB5Al>O!~E{G10veVxaq_Gn`zw=s^fXZQp#$+Z9yesE_7Q6yoSfeanYSq}a{3MxCvW3{sOIf`|sto}(#$%g#cElo5HUjq2dt8~$6 z6hx=*qXnBl9@cd+hBa=Y>-Rn*(&miAhu)(%G&GkLW}>OCvOKL5X~q-P{ni@3c~DkS z-n7jR^+Q|WuQG`5S9=>yRRj49z=FdLV5`~#SWrp3cw}d-3e0Q1$f`kqYQGczB66K$K0AiQJ53Nk~9b%9YkSW)^ub{07AU zy$Pi*#zXQto~cQo*Bgjexen?5rFc8OmnK|B7h)X^rAmV5`Iyd5%>=3pB(x&bK%vqG z=-k!Yx#uYB22Vq%03DvW{IR`Dm8Y#BNJ>;PwN}8qqi{?I1#IN1bW{HMQ63?@jZY%`~rW@Y4q#g%ICxhw!_m;6| zzeg^C(cl}PrxK<3sak3TV}k_@b1#KM;U}T#sPYpWYB5ZvIknj5hUvN(LqU>S8ldU1H?0xYw z_VUY7CVflY`EBPdh7+jmXxD7_Yt!mgSE>SCIqFaes>3YX=I!O|ty{zFR=6Lo<@na& znPK;)Rh8}Ul93@-tLAS|6}uyDFQxppzUeRZmnFR{vTcN8{VmI0Urvo@p3Dy(-{C|+ zcJqO&@&V0F22LwFllHd6_8p>Op2SAF?(V>&LBOEsG*qJDiov)~k-@AhXX>1?>wfz& zE(D)`xo$d`z9o}%G4t$cUM*@f1o6|tQhWT_Tx@gX%{6;hrw9ytn!TT%-MSCm5ZUX< zM7X1hlhFsQyzbsVIbM5rOx%0lvk3Bu5Ov356k5lYYMp45wenUh9UQvkzek?=_ISmv z?u{SJOFkR>S?fxC=eptxROUBwy#?w;n56F&_4WZKB8?PgIKgf7#x zj>-pC+98(QmGuvHKe%WNz2#Om>@CBF(yQTM-%oUcttk<&SpBYp6@K(p&M!#yQR$#6kAQp|Z_IPSp2M zzgISuZ6i`UVeLagb8ej7gHwC0F7>*%#?WhqKu+bnHqUzcBeiiuSCwpC(5JM!Gw68Cog_Ck0vIwTT0*cH^1+&h#CzXCf{xeUTJ!SJy zgMREzZ8}!C_bW6)9J|1H3jmRd>DQs=+5eo@WM$lg=Qzxjw(LtgVt3|)6-DA+MAV@y z!d}L7_weyRg5z*9dT1pclBi>)E0g6dH(q@F2pLfFz8CX`_g3{8kablB3*-D?JSaKI z(B0r!$ytd31P}vuLrX0|z^>B$gwS(=s}Me4&yJ|+z}1Q|2rEiJAkLz?5(SA*Vr1hb zg{X(;V8l2wm=DRGLpdu)n7smje$4%W=F+}bJzjForx z(kX!UAT*o^m>4?L+l$OJ$m0?PW)xJ9?1JU{Nu|8qq!5Zx!V4MmxW48Pvd*ay+CLNs zZC%)^&)R}iXut^H5`q0@8mgirPkb3RUTVerbl^$VmN$UYZ_b=O&RUN1?leenkqHaQ zkb{IuCCWGv%G;I;w|REbyXw|6dZZQho&w9SPoqU@KM;$lpm#H_OLZGgL+%Hb7_M_% zTIznzJ@#y+>PUTXxjF242t}ohL)jeYX@}Y4@ZWo?azy(`nW0a$hK=UnLqx7-xILsXbzo)NB zC~cAK>b5R8&@DWif1HQv3i-~YQiaz!75q4!1RuL<-rQ|=jAvaK=9^)&+8cHmbllPL zF$@KK5S%h~v55au=rXZ}T4mBJK+(ywMT&FdiZ7e&{tDw~hZN=FzU?&h%nd2ZIMO7+ zmlOkN5h^$Zs_R^_4Gnf# zC<{5P7d30rzQ^)P3@t2&n6!g6CtRULPO zIDI-!=ix0-ZKBcx4k)gZUFr8MAyHn);;ap84a`z9Uj59PW-bbUFj>;Uahmk z=ja=OOCjM`Q8nJ09Nm5%Ehq8PtfmeQ2Jdv(vDv&spTBW!ctrke<1g~Lz;>CCVY(Qr z3>({Z1NM+?brz%R1WxtB!|uaf$`Rg<$UdGXWA4T1u={idT`^gzBP`)3K!y5~EV6^X z54NBP{oFI;=bgHd{QJK0ZMVu|r=FBl&w&>C{l(PT3}kHbW1vB` zB*o)yEspv;E!TW4i#vTevpCPKG zd~lD_E6Ryz=yw)v+>M$iSepCiF_fD9Z8iF)dqAKR{_sQZ;jq28UTBPPf!osatzzAY zR~^WjZ_I!X2ae{$Sc|+}0*^O_S(=Uz7&rMD(kMDe8FQn#&sIQq;!b4iXzz`BT){fx zw*L`@tk|TZAwi8pf9y3`CM_=Y=r_0W95;&JAzI}mYQL7RGa*Mqq<-dEYDM!%&c?STXIR1ZixVm$|mrVGdFnM+U=)ME$F7dn*5OgZgFMtui{*NLWhrWhm#*$w(N)?W@E5HxH2_7i>%Gb#*1H;Evxd!zPfnTjC=rPf{P!UMi>V&Z zX)T5`!K_7wp}oy97_!Ag0TPkV${b5KVxSx>vMfI26y2KBK=yPk4}gwC()sVBHAz30 zo=(gMZgXB*&w2%=6o+X+cuq&{G+NXxd5eR6$q^@m8c&7=i&=cshn{SZ6JxWsyTep71$;U*4*KaSS$z5%5^65or;EZRGY+q3V<>o!fwHA% zjCt-lBl%ArXigl3xQ)TUyn$+)`64gj^%*ZwFZCPLmsNOOegN^dAE}gcz(H{-i(fyMX_X~|KCviS^FEojt_I77VqG7Tpp>^p zUTJLCyYRGa&uvVkZt_|ACEE(vuVo)EX`*e6<#FvW(xN~-XBI`}b(#~>9DWvuKQ}D5 z-ZO{eIoIXlPV#g#+fp~2BO*d9sNhmPRlpmxgkwvbrv=2rJ$$BKd}8t`zZ%AF6q%kV z%)DkDQ94UT{hbCltejzU2cwPMK2`$baM^Tl6Xv6(-@~az`A<&)k?Z0GE=fCjL)Dld zU@{2=RY;4GX)DTyi|UG0&z>j_082FJ8)Xd;eiAh&v3!kpbW}8-&`GM~Z`dxIlv+s( zH7v2Fb~pA=QBWyaoKvrE1^_=B zPT`WW*6a|Nan!qxh%Xhqx*R7Gf2(^c0lOk9jh}$0ZQf6R5}wQB8tD3r7f!11Q6fd*ezg>On);wWiIUfZOYPHw>5WiKzqsvo}$>l;_fZKFWe8(*rHW%kj$@Bmw{Zc!~9 zCM&-IJ1teW@emJV^q}eKwIEc%jcitc(OoOPPe~hlzVV~|VanV1&KKhSQVya9C7~!T zQ>h?V+an{m@I~}x02*{z&JED#0U@jx8|hX)lY2h>kH{M@zh!?O#?-BT39)W%H>B%& z?H!oxnq?T9Sc?k=(hQYy53XT4>AoW_(kWsJamlrP!r^T?8LH$$L8pN5)Be=2Z81^F zAT3p&mQYl4(CT++do(WwcVdb8QnPML39x@qF7~jdEe^2dCe#?9K+M*`9e)@*) z?F7-HidogUKP}Tdi+oB6^pg&K%dLP-m~Zkb=+GgrhSzTD9+>jWeeylFhj6|O9U`kgB?-VlDE5~%hS`ORu5${nIG+ovm zsGP(49FrM@&*DYuBa=Lpsosqj=(HX4R7QaQ@*ps{k&S2Z*8K&MZTC1W!5V;)JTj` zt&5Pev0<<#X@}pxz)Sar`ZDXJ@^veQn7?FR&}Imw2EEg2c9^cZ$+{VHi5PB<0Bc2y z(Xbt97F>OH9|JewyOI`A2@I$t(B?t*WETO$rzAE02owyq@j=?g(#kvGgQN| z+?5&Zm)fbI4HVS_x6LM^3RYuhf&oCTvqe}7HNssKZSyud)$+klq`vec6OX*W6n9DT zc~=zoPx%A#?QxT_nn+Z_b*@LIgcO+{#;zK{I3H!gjJ2NhvB+VG0dvz@>9SV4IJ8@t zpCz@%QEHj`ULh5#I1TYUn=chHn=QNd3HQ>|UTQs|`oh(VrPDq-RyS@v3T8=yX4&nQ zGk=V6(r6`9ZCy!*E0@~J+b2Lrgb$v4BI0%0UQLY)$!ko;mNbo1JK!Q~C)cKf^{Zu% zgxbJvKu|zSB|G;`ImHdUgno3{ zjfm-4RP1^QXg6(ULv~WmJ=|{^+~i;=uOQBTi$=D~tR7RZzZF|dmp!zO&r2|_SFy1C z-#*o2Y7GHh5iwlAenj4Q*u{ASG=zrDhQ^@!i=~k+TIr^x(3od%woN#r?~_OeU;XMG zh+qciB%V%2BU629rQHvhB&{~5KG{2v!!kkdt3aa-bkN;a9^n=}J!B2Xbk!Wfu5<)( zVRAEt0>Sj}Z#1^08SCt?GEmK5RpDhc*o1!GjWopN#UQAmrMnvWLeECcG~}&BJc{y& z5As8C(MU6N$@Pz3R3nv>6FmeHBY0-MzlM!RaAMTmik%OqWwbX`DRY zy-y9_Bp%waWI|VkRSMRNNqaJB$^Fz+ifO!uQC}t&tX<=;@DPj7G=^NG?=3!8PVHAs zB1dJ?5EVEW*0T49=mj6VV;0px5T%WfVcT_2D+TeaB3k>&XElXLvQ~alVh<*DLxP$7 zC-dZnqjSFv(avP^Q38ByMTKp-{XANcnkKzLj;qrp%cJjYYUdrFO9$NRs0?6nM<`9&e zJYM<1M$8)4Tnv3!$^m+L8f!XHJj4A)|29F3W9wB*S(-O*eJctluz#CwC6vSz05@!f=My$3-gilP_6}=5znE+&A4~Nz!GyJxYd$mv6R&QQKdSqtrnE za6#5lCtgvAw(cB3YqoQtO6}+j9xq-F*k3^Z<)dEFl1#BbVSWu&nJR04P<6g^8~uY% zME5ftE2iIi{QyRQ+7t*+I7EgY6`g5_Og`d%3EtbLy1Ig;=9St0AOV~0HyGgSp}~pKV=Qyp`&ej;82sE0r%Q%k!jWRpdawL8Z8ByAIFK#Y=3eA|{V2K2SxAmLFp!;kk^ z$mMOn=t&Q2xN$NL=hH&0=6D;Jo>085=dfg&Wt-GUF>?NdY!3V3yYfNHE+%bzIYEa0 zn&`-(0HnBVz+Bph6o&WHCktCfr9N%BN>=E?RC@5%_Vh}mD!G{ympXd+9Du?7CY$c) zUR9Y_spSt+7QiVSh3Eu3Sast+j8>F}f6d1atS5 zckjjrZ0kOx7utVw_9Q|H>DhVsli%Wpiy{90xCh3P4G3~}q1PZHTDq-{V`IOe`LVm^ zIV-gmVb9V+P0bSFbA?m<*u~F=f~?ND8EW(V2JUxDkq@ym1K-V`TdCAHGB5U-?!WJx ztdFYL=}dAPy5k_jMGhF=j7nnO2Iok0tyQ`l3#QwYE!CFABEtf{b|yu7UfKzFe^(YC%{lMy2J#5b?wp|og+7}sB_Yc|Y9%|>i`SN_Zg z&XgH*SQ{Hfp=C^8%E*19b66k~S$^)xlKn6xe{46&ma>N))hq)om{`r;tfL>m2f?p z4x#yp^pz%7sY$p@Pq;g}Z@FPhHxPft0oju3j-;pep8k`2A&Ux^vwpW-tGPS*RPJE; zK{v(tBc5fa`Y){Cb-Xz(`8SCnR}Z;0Gz@QkF*t)L?TuOWf z960d;-rx4tNNzf~^wSe>-(rT;na?-|jafLvVum6SWh0#Cm0XZr?IYhOJg2^DH#I)A z;O`vGKQCps!$hCz6cEDw5^5R;%_iL{)Bss)wl+5FJmyLkX&`M9m2{iLRiLnX4tuL?sTo#vnkQV(b1@+M{Zb7qp&%a%!s^6>2B%!%+$wOk;B%|Jvl zPe{W`F_=hlmHB%&^LMw`^%bU$hrPGxsy_%W5 zY_bw@jEgB`>0`Y(_ukMeEfoU~yG(u$Mlmlcu=zq9eRF=|u+#-Gaw(5dljY~V#yxM` z#;l8cdfAXI)bT^tvw*hIl6?;&wCUXZ6kyig`%mU*H6($*A}~W6Ay4)$mZkP#h7fAx z3{uO-p{~1|hP+)>H|Y-%S)zC#|Nl_+-houU@&A8AMae89D}>4>BQq<6P*&NFnVrnz zP&!r}qwGzHtV1>j866qf9FFaDjH6>5$2!*UK7HPw-}n3VA2}W8zOUQXO6!9-c2SX9CjuDDj27^ zh?4#F;pulSw8c(TKM?$4p13n>!*%4v^}56jG^jK&9UBwv=aNIH3FnwNeMx7Kv$^{| zbCvo9Hz&F~xmu5sO0{4xM6#91UFhn8{WPF^&8WGgv!AZ-_C-T5C>WqpYz19mds;N9 zWp8HbmTjp7Flp-{@rFZ-rP<`#xfz*|Wvw@iQijhkn zuOp$ymYPVny!9y+iQ2b690xBGjZcWfeje@eU=U)reTGjIWB_Fp5~+l^NgR&4%k^!f z*P~rFxPSkxauaRt5MX28nNt`xS($X9_#6rnoayw77ld%vkLaCda8(-E9``1b)Dg8k z2dj)ng_g+YQ%p~YFQ$KT5bbw<%Xp%OxusD&tPj&&fuM!)d}>f2fRJh6@YAW3$JNkj zSjR*+s%iGq`n7qkzwgofPe~!_rAi(Cqe#os!TzDL`m>??Kb9WJa<_{_-l1a-FsrIn z6*@;pysA#|GP9H*`|@4ox-97Y?Ui0}s;6aQ*Tz2^6QgKu>x4aW-?}%cmN^63NV{0Ud_Z+> zjWf;pJy1g$caKW+qmsqBY4_Qf9n$h~Ln1!iwGs+{HV{8Dl!lB|3PMmk$#QF-zq|IW z8Qo?K%H@35+F=8*{_M)sF0*!x{z3&cilu(- z&#FA$7QPC*B<(lSVA34?Ijv4kpQbQjLna%YSMG4JCP(B|hV;-SQjweVBTHNXW}rG8 z=UAO7Q@6~=@i>)E*S_l=wOr)n=Wl`Vr*-qGjq@{Nb-gHl0%$Pi@N9k#@@V>5q6-(w z(1{w8>WCDJ9at?+^-(|nGwS?B9{#YmERQIR9{r4>&@fcLA!bX%LZ_}_Xz)3e_wLm% z7e3r(q4zQgT{p#mTffY%%=v7z2+a6opS`Tz+t|Q8v9vsb;L113^+}fA*{3Blq^yt% z<)%Fxt|=*1I(ce>W~omth*S>NB_TZ-ui`MAKB7I-4RA-^hWDSEeXwCL&G z=S-;ju8O^(xN%cCQu3ZuYhz07x6{1MK?;Yd+O%#0vSyg>79gm!V9wrJ zAGW^0?d>hKq@I)ITR3s^HgZz)?gr)MUw zG|YC4XexiCwBl5!h%`phUc88UyLctKT~Ms-xEK~H>vqI#=Nzr?CSiB{R#NVSGKtyf z7Byvi+_!+Oi>p^mZY8DQCH`E+5_o|LdamGJ?01Q!KQ7Zn!GfaQ(L%`V9abK~=g1Sj z_!BV_w~4^x)Yrc>TgDC3vPxmNmxuXim8>NFRRL;>-ExevG}dUZq#2@w<+aA9L4%Vt zAKn*MNds0E*X=P4CF(0{uii_vayUJD((UbHG__7Di;}Z$!tr}fqs!rOa&jJ_N#h~d z66t5AzD$}gN<;|7B;81*ul=~iOsg9mb+3(s!r$QGtzsM_rdJ#$l+Z)F*%cOhuFAd! z%qlG`hrYrk92Q`gkLK?Dzcd@8gy+QOo?Q0k7+ofj8Y+_fccl)aiy%qnRwLufUe;@U zkQVk)&oT3~B$W4dR}K|nbk6rT1YMz2o(X9-X~7oi@z=tG8gq{Jd@AZz*B?aVtd~kY zz8M=1B*ixMjJCGs#J)eSN!a~1E=0aIg*eC3Z&ep=x53s z)8zzw_c;f6G^}X?(nfrNt#5;aYGdT+2+*taX5CbJjP6kC_oJ=1<|!P?T-TpZ3qB8> zzn{>$sNi52y8F63v4!MP>z9J_yyGTsyx#sXtW+&9HUS;RCLJLV^K zdKGPouGMEh)X5)6i9D5gKBf(pEka&adFcAxMvnbClluz0doIj3^lsY&QqwM~8Ldj! z9pd2Kx;JtKCrA2=5iFJ1hYa}#PSi44Prs@@J@vBMl~D=aFH|Tk!}yJfChDh$5sC#1 z;2Xx$c<$fZiVVq0$e5@Ftcto9CAZLdmI#DRvhYhDXA6Fc4)nWqQ=a5iY|kHeK6cc^ zx)$|z>x+rrQq9asO`}9FkkZ$CiT6g6^f8lmoZfH0^PrxA^J-aHU>q7+(go{G7)iF=NTAahz?045ba%CG1 zJ_-t%@GNm+a3bmM+I=;-7r->B9>dJHmSYw0C)_|`fg4(B7DZ{L1WZagRZ4CsU9#f; z{$=FvI=&aFR~kRu%??ADgIpNM?*#l*)od@3a_`{sHrsi`n`rViA-`4#%oCPEOW*!K z-$5M)%_t%Zb;y^T{Li*iY80D*2IaXZ@&lb!)Bp8;EtIk6tk7k3lp!Mt*$>zQ7T$FN zn&#B_`1mdV#e#&V=?%)<|MO)l9uCkTf+m4p89Fp=C2gVb_p6T!WSn7V-L!}N->PoT zPCz|B0);{yZo$q=(GcgY0YTh#vNp7G)^EDD%5HzwzpW#Xii)aFo`n~A1mglUUelF; zmxY#$>WKg-f@?q!lJ*MUojZ5Ro-SOPbF2OxL8i@6Es!z_Dv4(9^v7fw{sAC+98abN ze(Mh9N>1qMm_Mcyz`JGJ0!QTRoPbV;8t`G!!s%qVxor=_0o^^yJrltDTzkpl$tF|A z6G&$F%mCOv);YjUSGU7n`k;#$KCl+|?|p^F8Vo_v-oH)(E3D@MpfQ)lUgC#h=&gc) zt5i{VApy9Yfd>1*Ck8~&TcC+I6d6$j7!=&GQCul>9fYr3yuo{*$W5}1HxlsXUg;!@ zRF8p__&%?L#YlaQ&G!vS5x_l>bWlhpVhq~moy>yz(}4RZBs#P25Fg7OChTG%#1l}5 z8FRxtWe(Li>h4A!@&9~5FZr;3UU@A*T&YgZ#a5%cyW25iqTpb(uUNNq?dxyjoXLq>wS=XjZyGKd_lDTZ^AauXo)8Pag(o8Tr0hF~OD>xsBNe}vEeAgJr_f$uKB+{BrMx0Y!X zj(3aV5MSy9F0Jf&n-#8wT{&qNYlvttoCs;sbPeUAy;-z6D9n$4k4MX#Dt(QO zi`$)U-FLWWlI%ZN04c6n4{+~Xc@wDHae6xWp{{!^7Q>XV7f!bv2P^^|nUdB#4X`)~ zub|$AVo)9H2UV_m<@tRji;zQXD06-HwuBP6OK?&49&wU$#qfxNrAY@>>UzX%k&nA3`b!w=I1_kr@ z71H{u&$G5-*_*UC>*r;VRZS~`vroF~KqrT_ZS#?GMa2OSi<|@!Tz{Lr6fYOCRu``A z!1^5fwt?^sVX!u~pZ%n5X>4D-Hna(&7;Bow{}Ya>od=5ieckR4v3Vo=FHixQjvSji zbsVZ@3gpSYoY~0K?qCm73oY9Mc5iv}6`0XWm-V>dO5sn`Sh&=(P|v%&^Wx;!4hky2 zHzX8;AdTJIN1Lk{qr1VP7pL~U(;>wQ!z*zlAyUKYs4aA_+o1b{QV7=v?^Bj;s-3}- z4-49;Q9n_w47b)QM3oC(j9*g? z-AGlk0yut0uGZmS=26{n1pyAVGY$+!Bg?uwc+X}3=zjJla6wiip_P^Y^C=D)+7)XR zdlo9;Fh*IWSpT)c6dE$}HUfYo=C=rcUot{`FrOD}IR)o9LYPkKHZcaoX$Gfow(9O=%(6Yb1=eok38l7IUf&z1xZ3GklzTgeW(QfG`Goo3ee7I z0cMLITLLT(S@hxk2h`^JbZ%?hHw*@J5|XDp@1*Q#a}3G!Uj(-)ejT_+dVm9Szz4r5 zn`~d31_bV0Xyx=^GAGWHqV@0hK6I70+)3k!Q+Nm)=6lRe#ip-YumZGF?7vI$lIA*+ z_5C(r#^4k|Y;`#PJ>IKt;{Ys%^Vi81EAuVOEoRCTi`UwW&sJktS6TpP5*G~svjqGO zPg5mc_C~4v#8=I-$t5i1#xi5@9j(2z7`$DR&(TS%D;LtbEwqUUOn{M+JU7li^yq7tDSYpUecs=9#!1<590Uxafi!gv zww3U0Kf@!v#|Pk6vdg1Wr1`Hz=Ih>j`1)Krct=4~Lj`)~p>afO=F;@Wpx~>sf*Li- zYnni%v>iyJrMHL(KO@N#e(`4H?c`ojbOxNM*CPZJ7O6S`pY@DwQI_AU#XtZqwguee z(0@kUB?9_}LmAyaGd^PnPykaZY_@JJ?MCQBoYW-&kB4MzCr56-4x_OGca9j&5waGSVCE`{$d-F z9fbR)_s9b<)sQui%5F8ok2@s+=gi_I(Et@TS{N-*XnmSj$X1}bXvvk`6RHG~`cK{x z<(;&_nzr{~04S<}*a{bQ16@0BvW;uqX;I}U-GnlIvRX1+XeWlQ144rJbV{Zo^^h!? zuLJnF{q62@+Z@E0Y zKbljMBLb#((?vqKx!fVEd68sT3TBJ!%hc0?2{3faF3;R|a@UvPrc+G~!__5T@1+6Y3F`mJogTuj4rP{Xcy~!bZ$_27d(*5BbIPf^&gOh&+Zh}Bk?TrrEft8N9 zq9<1$tIvFO{^&I;m9D+&rw><-W0dq z3_jQau-+L5O+e>RR$+-g&N(av^)F^&E4dy~s0X8mlRX|0m^kIrs~D9+nYqXA&8Vao za)73GaSMRw`8)yi-L1+@wZe4TfGeRs5*~~d6mG#)Clf-*c0$l+Z->wIO-p-gG4)3$ z#dvM(t>@cc`+#zAvMuL{urBt&fo+=!9dEV;@b5R1ism`m&WBv90CpPn^LH4pLyol@ z{3_PSEW1T=p1@XWx58J;i*1saM^%K<{EXn zTJ5CY6YpgN9rC{aym-{mtysa@1^!#5X)fY4Wv8 zlKzvKWa@S!WVOoDfh81*jPlrQA?`M6{&!~7ak3YQ%z z{k|Spb{~TZMMIBD*=zMPv*iZ8BSH$-XYQN+tiqcmwIPi5j)d-q7w6qox~>7x#tR{kOZl!EUC-b-+vvB?d=D_K==q6p_KecLhG++XZ}(s*=IXQbvE60GF`d$ zHKQ)YCfZe7lJ>1rgrYuwYwoc%@E=d_IBWu@ql`QuQI(ezGM)^bC%}*-Y~f7Xnpn4} zpFNH*L<95nC|$e`C{%UKwOTpiMGD!^kAQmiklk<6)?NF~W=%>%K=!AGz5YDeB_>=U zB6i!RC*f0faf(OMtUu3>?~kx!BE3i!`&45@)jN~vrGOng;6a_TJv-U=!~#p;{9JN+ zvUso8ifuv#-=aWH@M~~m>L#v7$72a_=^dz+rbJ&k!4OCFb9$#G{gW#;n>Sm_vuZAh z#_pB6-sM`^Sq7NH)*gX`KQ88d8b80ujqSJo4t9zsP|N9O&|8pQfqiWQ*ROS#L@jje zmWN!+Ar;FAnUCNMqk<;p#UUt2{cq{%2XQ%0PG5Ya-C^2}G#JhyXu9%oX2YvXlFbB)8)#!YWB9adVp(SKHL zBjr7fTrt&y{iy9r#T^po?!N3k!>^t=&EgH*NN@n)PMzmBAe~+U zeQvs!5R!Mj%NtMLJkbK&UQKkZzq>^~T}KD`3ET`sysUE8qP|70PmXsVn&df+v`!g3 zj@Hk%d2AoOu>BYO6VyQG;&?y?l}Ldyq6peuL9D$%jDa}c14Xr8Vh)uOBa}5{!iXNV zWGYJ|;t};e@ObPld%V?Il+Dds$)W{A1c@Ay9g{mkVt-lOsqZ|-cXIAkE+)Z)9T=A! zjv01G?qsqK^bX!lghMED-y{wCL{lqAq<-It05F3x{rB?&U|KpzD!0e!vg0BczmbsM zRSVQ}IcTNBJj@-L^I(h&D|ej}+O-$jdt7`BkT)Z1d};*Mtd4d@#B!+|0=2AP!kl(1 zdMFsrQM_OOk!$JMvYWo;WW(?W7Q%SlVN73QWBmCGOL;5#oGVIMF zTSC#aCwg4>>0#a$~VV_^KitxJnnpuDM^8OJcQ&5zvA&6=C3}CPMH2^kV6k%0E4C(8ymzY4g zw|2{|5u4mewsR!cX+PMu@bUGIiE#mDDtO%*>J#m^EBTmhGvvu=Oc=#~Vz==hog!0+tyqYm{h3s=nG4Y^E`Z&ZrYF;G6pm@DGGctsyslhVL5%tlvc`uM)~g>SG0F02iGB|u(A#^|)5)XMiT3e; z$pt#6%*mG4Nu2+&Wxw!Ea5(pv0>O-QX0&4NSU3fC-Cn?6xrjBm>+7DwIf=SJLytH4 zY_&mP!%xg~+jTpnMn?rVYV$cq#v8o_ExKC8v}zf@_{;)+SNLSD*91q|A(h@+Op8Is z^OdflW~A)2b|$nlY-|#nJb>^th`D^TlI=!uh}6BY$y~1WYb^o+>|b?CSNB;j&TyF& zq!vpAI_yS_UseCq>K^vh3WjaHHzP{=rY#P6&Nb>3H5dsn*!60n^V^ar{ou{YG3Pf# z8O=$_J48^ND;+|e{+*@~y&E~MV4Ce~3@fx29OLwf`LmWlF4Y@M7(om5=lVN%KdIr! zGL7=t3L~6E}R+z{JH_e`%iREva1cZcF;ws%`;hFtSLj2C%HHS?E@N4n7i z8u}m5#v}7nXz{^@sqY)*TPZUM72!>+^0V_BV7!Oh&71@2>yByTF!aC=lCk~ZhsNbE=NWCMnXq`y5 zQ!mKz-+-A!@Nhpd5bt8ir+(u3fe+1+yC)vPsypvA;%sud=BN3y9u7i( zLx4u^sS%~?8}<4IfnGk#CPHE0xgXxljPwm30AcMz|Mrg903HP}j`0)KGw~^JcFRlD z@Sr;x4;EBFHs)b3bd0g<={l(0t3H~u`-&BYmXgH2JiP*=W4Tz;T+vE(+{NjN>JYWu zG$KLd+{xS3H#v-s>IuO|*xw_PhF@~VpIkh7$>lBD%(ctcVZzBD2J_#bI{9ocRv+cL z|FNeU=Ls!0rtjs`^DIeDjuzRk+SX>(rPR{Dwb6;o;eW476K#$4iw!QnYv=*`pwIZJ z*LB9LO}q2XMf!eMJ+lefhg4Xxo~{JfncHR9!jN8-zpTtycMIO9M@JSGSg{C(U(n(@ zBYw{{nUJy2ZH5j+PlzP!A@V+B!ieM?!#FzKK#Ja$XMiHzFDX*myL?Q$@e+@5IwwT@ zo(j8Z%l$_$YV(_(Xg(Y_R)nqjx2#)EdtS3Och+A??H}5(D$o#{_AE2?2gUR}0o86B z`h(>YP$JAbHytG z@7ZQ@SplvQYor2vPuzet5T+3}RfP41^1`pZ|B%-y-|=e^Z?B$IuX0K)5y1!#TQOsG zM|bUns*7E$P~ZCP;aAOn%<|M%3G^u?RYvQULoj-o-Y~X=?R`vSxQ)Hgea1}+QEE@< zBYVbiz-{LtIhk1Qsg_r9h4!XelE6<1jfk=x)@Ai`-um%^7xNRDHJe@go{Wm?P(<5A zv^6EK4$pOcYofaVm}oPGpNchbqCb8zzhEWrs<~pSQD}J$RZ(Ig#_nNxKZ3WaAT;Cg#(&!_>@7 z`4|(SB*WBhOtb&}m>9~_K#{o}S^3(!^=kRC`(p>s5-y^D znmNuS)m07Q&O-(pM~2#9iv!{!FZqlxaXZoeCr>k2;mE)Uy5$sdAN7`lo56tqk(qsw@5v$9?+#RNMY- zdx=|td=QDQCx1V5{;K{n{MtD}elQ9F4a$BRM8U=T@l$uM(dCFw3Yktl9JEo`uHMoz zzA;LT$K0I>?JK`0)OjwJdCII5%V6}(#h8RM?4eY>_yp4~3FMrlVAfR}9~Ua#TVEkv zw)hRpdujz=)5|(p(ftJIn6Js)OUD6O$6OOm3fer6z`NW(QsJNxG4V$aoc(#iY+v%E z(&K}S<>iZT20W^_A1ie0X_-~%MG4C5({lg*C7t%ji?{}r(zj&PedRjM7gj#Bs^Jw{ zp^s`9S>2Btjw7m|<{>t$aPY{t4>-94840#hv=u0<98A4HjL9Ou@oPs@h&{*zf0 zG#;$ly5Y)b%~?Lw-NpU2MI+mPG=MKVNX}G=pne^J$Wk&FZ zVOUJAsneHfS?=qQxfapl_eZ}!JM3px!96=$IUuG_K`}Sk_}gIjkW4NOS6shDQ`YHb z4Dn40a=7cTlara8*ydr18*2Oc+B)vvt|$IBb5rfTN)LH=ko;AN`?@>)cvP~TNe z9PZ5MTHvi?38EIhd{dOtcIM*(IZg1lmXN*}ZmO9Kr4w!u8Z5#7g6UoMT4bNQ;=m&v z7{W4<{6=D8tOea!gqLVoKL$K`?FcTI^W5{Jt1G3vqIC5A4JbeL%9Ge@Fz*CPV43<3 z1F0xl3iRD!{RsOl$A4X?U081{Qpi<^-tBw4({5?W``d#Z()u^)J?y%w+i*PkC>@}| z{Wyr~-RW_q<2P3$;`DAyvKr8{LV0{Cj%^mXS+o~Z4}R5lgi;)BW9h5qw}9Q`H={Hd zbbXm@?$Q%id?)+osA>1fyx;Dw6$M))(FgP1$!PXyWU2NhoF4>Z>-~~FAoVqoGTBiy zEX&ElQ0Wj?kC^P$44@)426MoVHh?CECFA18MWbdd>nTBa>)g$vI=$kwJ3Ll;zgQ&$ zQt5iF%+chJ1P+ZxSj~$3V+*+IpC|NFCb$A229&emC0N=a-N*UG`lPF-- zI`Mv2)wyM7_99z=v(x-xlvuj{Zyo!^N20VM?hKak1!u2U>!v+&yiIUs7zc`v zA_SjxUM&$?ovw@r^EtVT-ZT-f1Z#%|o%{F{%+8L}}69@CM8nznrGv0?_3zG^$tD zIf|ut4S87UV&&)t(cgQE%Fr*HpyATox1!D`T*p!|wG|UOLsVD`e>Zy)-c@Y`N!XQ! z{%ADb6jL6PD%tcBO`ln$;?KmT6StA50EQ(>DQz{a^x`V}h6VSrHU+ND?6K~d{E;!4 znFM|U?56s6@pI$KR3?y~7Mn)60~|}`2PZsY2*TOAdFPm2UxJ(?2-3Uti#;V~+oTe? z!(1Oe;5Nqk^rwRQ#d`Q?=d2vw%%rZLN@q5XBM8dZzm& zo!$8Ic9+b%6?7U)yq{%#FL1*1?>NIGW1BX}9i?=cH9!7*_id1K;^Huy*~!DwC#>!i zx7DDixUIG8wB4+F)ckYQRw`d&xOMM7d}bb0ry~?M0C#*rDEwbG(-Y==(9; z70g!j>(myH*+i4Ri&KtA8uEu;NcaBj3OX!unq!$oFe@;H$>pQJ(e`@Y%fV*AEF)T^ zZK+EoF)5lc^g1@qv_Qcy!}A8ih?bZSe1}N7mGnyQP%ZPETDi`aWh<%S z4xhCtV+>4T*O$=-d9(BprN+sNAoWV|?n5LqCV5Zn6PDG=0X5H2D#sAD5l22q$G1u@ zI%Ga$YB;0v?}(2|%mEvNSI-E0j{fd8VAyeKOpJUj%px$Uv%x-7s{LySk_q&QN{iDF z{|q&DU>|(vc9wt$w>HI2#jEBf(IoTf^s@LIO{T=027X*j%F?~as;REbtf6%0!sWg1&bi*tspA zmkuoc9dlHnUF$$;YfIKZlu0|>9;0m@lwf~EErIK0{A-)y4Hu7iJrhwjV1eE&%?L3wFB4mv*2+;&Y zx}J?vyF}267Aa7L@fevmdGy{F#ySpV+_9N)^}*Y6 ziNBs*x2n%lgKCv-nnMopJ{E05kD*PQ(BvMvFB!JN$`0i_oim20uWgT89(k4TR&86~ z$vab83qtuVW=}BBb^;fj_hjm%#CkP1cVZA#|@FWfMS8R;NbxFo8QCbP-plL_*1givlr1HM)eD+q$9zBu29tPg<-;a~V zvP#j6%j!^ojk*H5CH12n` zpIp_OjlVx~6=lw2TIeaz{^z{WRYd-9m z`){q3xYh+UJ@s5&-z2{XOGozR=;@Ng8$2pmp?mI`tNBZZgKHY@>rTCkx8x$ZJqT)P zROb_kR4&e>tk^vM1#8TQdDue1re@f9gw=w&y! zAd`wKN{Pv>d7h1@1R?IfR;bOHHua2C&(D!`qi3@^OFIP&4=Gp{K{H!CGAm7@MB!;f zBa#O5(fcRFj#^CmTM9T!mjAn6-M#7~i(t|GXCffx^XPp;P{k2c>`ivv8w7I)G}ota zk@L-2-+bzAYf$cis$~M_^oEaJJRLmcIjg>&7SO@ULp}i|?R{$9{&^>YkY@0}swuX1 zN%cjbb@XFQ?fwO4Yf$k#O#<^q&n@%W{iSd3seoCEl=C&F#UOxA2z--;OIN9BGsbeS zd2{z;30%Pfgi_<$rmo%osUE&Pl3M1b%CXbTZ;f|7mYHCjm!h&0l3ZI%Rk$yTz45=z zmzbrs9MGBw4!$Esdp+8JNn};V+#rR9sr~Xyj#NPaod$b>R0*zQcQi$m@Y{q{VrzsQ+ z4I7fSy>~qRQ6R$T|><>+@X$0aPJEpZYBQZSmeH za;XHquAvoWIw&jW5nZs}d+m;Jm^PR}Qe!uobItYQn!LWbtGQJP!+DHPM|yYd#`Ki* zc^A8|l({=pqCB5=^v{U;dPWls+ztCP39F;ufK$6u-5EMn($`ag)g1n8;(RM@I^9T| z>tC`4^(J8D9+e#L@e2urfX%Rh=$pOFA|}b z$3_}oF2Uvp1)3C$Vf-Cq8X-tUtJ(Cj5(z3Kldm!7exWNU(;L3Ot((|0-@uc7TRX7dydu5=NUgXo*iMt^)tn5}SSPkLRtDR??R_iZOw<^42Tx%R!_tGqxBZq$- zT;$D@VKTXN`HHQpi)fWvuyLiZSVzE9mM7EWVvCGl^1IHfZ0FB`%zjJ}+;Wn%Y3DSnrn zS86MCzf2}mkBKf9^3ZB?XuD@tBLfWVvL32xiZP-UN z+~oGIto2DIulvej+37R9b-U6bN>=c0q@0#oh?LU4(airI2D#%jTf+Ekvl|H)K9^cx z?{_9uyeVX=0FL$R2TQGXOYq8q!Z$H#t1*BKvy$iyPubeZV)?UJ{pt^p2)jHMFdWCF zUd308sIKjL075Rc*Dlva*z6cB4qnPqWlVK zl(to5VXPT%BK^w?6F#PMh;`xg7V*9ejC-~fyQ&ayJp117vn}u&FJYTL)5!Bn6Osi$ zt3K<3l(*wwvA|_~Z}w*91DE6~(4x0H!hT?y(2}WNIjhW-(er_>!|pcul03GV6w~cv z*;QrqT$uq%@%ro$-UgyiWTl~d)$xGcI_ERgNu?+REywe<;h%k zC;i->P-Pn>;qg)xbHf=Y(-mL6;HS4Rk^_-+OzHo6S?^Sy=fT*k&rX*+N06b%-Jxze z`7&td{Jr|y4!@GQ|0G0-a0BYPrm+@l&`*|7j^$7*I0WxnKhA5C7y#|~NF+JweA>42 z9=1-o+OoQv=B)&+93szklMIPBAJEI!>uS6+-0NI8ZTi^ur<`(@xj99{nMj*}xb$#n zejiD5#t7+_pQ~!oYvs%!vgQm|UIA8zb z?);kJfkylwr+}tM27F$832-3IuG+4R%&%i_mKoTsk)z2)jhnE-o)7=Fot@&(oba2N zh@YCF5Yl|OMKy3?{~K#nyu?Y*wWV)G*>dbbt9fLJ56UW4iU|-#Yl$bTnsE|AnzK8* zCo?{S?q^pJWCgE4rdNko4_`_RhLw#;rb6G6H%F?+aC%n}O2_nhoT>ekVwQG1a3w1x zKE6`-y||464RQMPXf#v<$bhZt1g-!iJOI#(JXKZg7@tEmV6YnPF3?a}zmD zRvJqNw8xyq&H%b02@yaq+<%uvF#GIyMMl4JP}`dU_%e}6v{daom;nMO(KyCZCZym@ z$B1pMMrE6FRsV2k2U!&Szh7lBi>aVk7sfpR6mfi$bCgmi4)|z*!U?o~_dn%zWgQ^{ zKs`*l*Uv_X0!Q%M7eu`Q6|MPFz>IhIiM!xGwKkM)LMdv2xn)&Dk78f+%{3je5cQwB z`=92!%|{4ObMyZ{YHrPQqL$=a{_k!2IC=gBQmb!Ckf*}GmsbAe4m&aa>=f2H!vBAM zmiC7#Rwm&87LU`lH*Yk#GPd)*<^A9HaEv+ACkv}3j<@4N*+trp34!7af4Je~5c^KP z6bp&tU3h2~Iuwvw)_p(7>^t)-LnNx4>?nU0)MRV4>L4=!_Kf9E*Yrc5$VbpIT~AQ= zGD|0qcBUK3V$kbqsg-7iHtK^Z3+aN1EffVL;%>G6$;9QveIV@oaEq+_Isk%T<@r38 zuj0Q#LICMBEm^@G3FL^DMq3?WApk0ahRpVf1XdqY;W>-j@REHXs#iJ_kmi&ormVyJ zeNQ0C0q{!c{cX;ZL$dI13y^LH9FVm{)cvoz$-0hm4#=zb|p*x)Pr%;HX!f(x+r8#Cz71HY^nSOEUl$^STjY&iYx-z?`-7k zcUm%IA;KC+L+?CX$x$X_r^@3>r_t2FjpwwnX+6e@a@7GT z7mGkpk!iC4u*l>^|K~ekq7HkzAivWunQ=Gxx2u(;ThrRtPI7emA{ihA=mmrG!a=bQ z9S;BjxC8>oVt2QDx8m#`?gVoNT9~cU2w*jFv3r%EC+)&>aDa*Pv_jUlv-KZ=JE#O6 z(65lT|F-Y`+2;K-VXs&)nBgp84-k#m0EyZPHITl&pFXriKat&aXYfHg;_J6o5@3Jy znFKfwkwC-NMt1AR#f)DWR0G)Zi5$J6(f03@jrsN7Zd|L_VXMt03Q3N?N;BV5l5> z0V2?9s!L(L--o2`sV`q$N)S5%1~Lk#wl%4_!06Mpnr^Z5(k183h_;@=HYu4B&z&_?NJKB2FG$#t4>Wcspi~SE~R+Lcu*8)Bd0*cN>a&q_< znesCEx=%QgJYUM&2D=$-6Id&f2y|<%-#4{&xC{qlWaa`U?LG>pQ%=Ngthel;UCjXY zF)y%Se2f6hH)`b8yWt}XGn(MGqgi-haCaXs>nOq)QAlPhWW4*G$`sTI;Xf+6w$y)T zuD}2`x&@IFislQD25Meijep%2CyNQ~K;uA?Si<*mAxommRfX@+Z}VhJNRvD2Fku9@ z9~XBM!k+zP%@q!8!(Tk-X;?D8OM=`qNn|F;-h{`MK2`X^FY0(dj7l$o9l8T3US!w- zz=trNbDG)m&G1%TeT(}fPzEB%p6O5&7k`qwZW5r_FN_E6rx<@W%FZL5^x46 z#@+wEi+45Q?w;HIZ39jfWt-$1)1rEV-V$BW%wgeG?uQ;+e=(O5l-hYVy)&>%H_e@69Oj7s6rc1Sp=R}k(MHTCJYT!LsJdIyVq3NR$o`4J>Kf9bag zMIVN|A*<}>1V4Zad=kWqC$(WGl8?<_RUC(7dcP_r>42L;#y9WBe#dn#jr$H?CX6ZV zxtQWNNoEk0s30rU&cIShegLWJNc+}6d0pA@SUI|e^Z_xRA1BF1{}<6jgUg*6F^+hG zDso3XMvr$V4WF0>0^3Ko|9=6wL_Mj^ld95J>9ERB1M^pYmi&|9CCpz`?R94R32+#n z&x*2Y!c0BsNHUW>A&ySJHX6JIW=fEWRT(%}FEpwX%d*qeP3Gn#TYluNz_yU1kEgj- zb*6O?G_nhC`EB+ASIC}1(J|`^PDMAsJK;^#bk$oSz)F$w=(en)b;(9{iqdNC`}BQd z2v+ls*|X9Cc*rimXdo-5%OQy=D}#Z_i%b+Z7u#LG#acPvK>%xb7K5WgVi*0zJVf$t zouj)$8Uf(PblL(i3QxTMQnUaKnO$MtTTxDsb-yK}_&dy0VYepHEHpl4CqOpIa(4XrY>Qdn_xXAN9EJ}o%Fg8&hsbp)V_=eK%(>lVmoTFvoaq3HW;38$9=$V(<5Tp# z9jgcm-fF*65B^m`<-P-i7&rd(jfD^lXiws*{DD;J{FdC_?ItAJ;ua|ytfxFm+X^5l z>W*}q*Q-O$cI8pShq#ig+7#D^Z1iO`xDw@i)u(@^)&L;Zb>UF_mx_vvkn)q=D~CO( z-Pbv$&Efyg&E*RtOC6=p_bfOROMZ=Jv@3`5)6(T3D_eooJ2aHW_VMv{6CNOI{9a!! zd|pQ-p92-lPnQMNq|l!N0%XU@(6f__D1*xp%8Pwl{Fhl4mu7$>#sxeanbu#Ts#i%+0JtuB+K?O|SG3qtU zlVcq`ADGC5Jw5TC3tS;9!<{?A4Y(f#j8eL;(T(G@YZyd(zi~u83xgFC7$gTJ=0KMA8p<;*)x6!GKd?8ux4AQ<3Xtx}bnJ zpQzO{&o2`)M3sIMiXE%^E`MDv5e$nKdv4 zD4pXI_5bSM-P>rEUw|$HdCQbi3;Ez;=6MU%6dPV5WfHmm{7zVpyaw|?9s)+c=?lY) z3P{OKo50^f>vy7}BszY-Hh1YuV2(YYi@VLOfPh7N>p!AXRp(knK3d5Vr2UG`MU+Fm zS@%Z8&FO_`9eACiF7AG6-3jQVl69W>1s)2s&^Tss7sj=_aa5Oh zJ`}xBz(0PVMEDfv)-9xG5~|w6mQMA|t~Pmr&_o7Kxm|#nT@crNd(?85zTdn^3Go^F z^)+x5Dr&2v@Fen)u@X;~7|-1n`<~a%N44*x82rO_;n8Ge$uUun>vOasfNx0J6*I?a+_QOjfuc2 zrmMA%JM-r_ZCUYcvndthnUD*z4)Eib5jOP&=T`r7t#w%Df+--ICqmO zo4ha?zhFI8=UL3}?^SC!=;Pygp5Cj%l6tpc>bJ*)I?X${0yJ8JkWDbtDZ;(F5Y`<( z$&3f{8rw|shGaYz+X&GL{IJlUD9<%`#4*&>x*`&1aZ zrg?f*drJ3>O&yP!@~A)Aa8k23;!#cS!f&K&?+iv69m!f-4~GW42llQ4b#je!U8UL_ z32F*IDpKTJJyp}=-{`MlMs9ty@#aVnJzo~OdX2zneG>hY(>fc(NY~3N%O8rGJkxBx z@<;wTz3v0^USWN#xA3ktWD!^hP+Mdq-0TkWs?PTAdDO7f?XD#KL!jAV{C{d8mTFnU zZj$jf1)W+B^RP5;oBFv=c854K3i-#CVhuVJl3mx35-RFubTY}Q43?lwwX*I1ue39d zhq8PBxN54IBxdGYgvc_ZY$K^GW7IVAjP)sr!h{|q=0VvDCEG+ib`nw~6tbt0J!MJB z){K40*4W1ye&-(beZK$y=C5A8-1nR_=eo~1_w_#4=W`Af*l@b7L9|x+yhFlsy1)#H z>x)FrEoyEs7>ZuNSFXQyh?((M&5k3(2KyAxTQxdA<(!|H7wm|nRDUU@qVC=m7l&VB zi?yX)ZFDo|-)wH2Y(~qAu3T<-*&~OPDz*{#le1)L=DEPl)*8+Nw^($}>b5hco#D#2 zScS%$RHNKpLU8=;rLjd5gD%f242{juNS3Du0cmx)@r$$+wLt6l+HpZ2y7= zn9O7(?oUAH3QTV_M`;M9Vy||R{xMFPH1z$Gm;GJL{guGq_$3&DH>)hO!0p055qGq9 z?W`nHHpgd7FmnhhDCmeYb1$XfN3innOHsQ6@NMDsi55kn=A!X5`1f*mjpf@)OPG7F zrlzc;(5uOdu_cNx?h`CfjV64vLPQhvfA@9Ucj0HRAG8I1crWKDDUtA}<@Muj#zrtS z${*z@ZTX=RXKC6MOOQxPWvOT3*0DWpfX zqH=oJndnTX$NW(x;ap=THZ6-$|yEz&$GLqvrfj#AYbO>q|kO#4SRi? zV&GVZy0~Ojlm+ZDc_(^Ltaok}=mMr6KRLA&DfJdMqU*Ho5g8NLFZi*Y5i42dT7p?%(y@ znpH019;i^35wZ&NUUtN#JO2~8I_mJ?{vKe)`A8~W>q;3YnBLJCwQh06M*9eYRIM92 zmk?|rPBcHbSqrbKR3j^(l6FR%T|ny8a(~eZZn+4vmsl}f&C(?u$$h+vzE^u;nw_YF z)IBo09qrpHyX~a0xXHn2vUw3=R>x`lexl>Mm9_>L2m*V4T)3k1K%E7ns_602r=Ucii= zg9=pr{`-=mV2W%yUOQtOioOQp5?J#;dhBb6Mc{E{)mPH+Wh*jCA$h0Y>BIZ9{|KIZ zbAh;PZX`yw<*$S5dv7`pu|wr*`Uv%x-Zzl)%J`CDZx+Q$WrKQw%VH4pVxgE-< z%hT^A^BC{)J5Ubq=x9A3*S^1s5vyF#Y(Kg4Vr}9{NrEw;1~=yvQY~&)vS)9;B(K*H zSWoe*S-0exV=HW}){P=gz9?mUYT(Ki)NTR+;?`m((MdY^99{Kko}TA3G-5S%V*EqR zn}%1pM|ZU3%!5Z(9qn+mh@Ue1NJhd^R`0s|dLzLa5`y-IRDNR!(b(%5*0=vX!AM>Y9pEPf@Bb|D8}btKo1So3QsyhlH0j>r=YTkdt;BJcZiWZwBxic9*Q>hhU18TtX)1gsoE9^j@wAF=P<*Lw-T93XU-|qxJC#1^g9;9bw(~;b;Ra=+{x0~ z3$Tr$th4bh_V5WK-a$Qz4AE3YOH}NLCtW=}r?=LOeTJGQkCk4q9%T4)ohQ3w7x+vH zqQ0}S2uD^qNR8#+`-cYLKY4{=Qp(J$p z^5Jtu;Vx|{Qt@2klEMOfFCWQfPy2^A~xO6S=g++6>_s9yW0 zR&jZ@oKeU_R8%eZz0)uFD0{8^B2#gC^#{L)UT-u% z_$k)LtG5trV1FXDVcYK2sgZRr3X7i+Ass!|an=O&Wjiv};cJyd{Xe54ks_&8{ZeJL zqK3v>rLe;TXVXyo7&@ji{>ZV|sRuer(Opt)!TYVk;lpwg`#j}~b{pUfo~+kqot!oA zDLUkQ?w>2YEczbO{?|9&WT~#YlzY7PG+N)MAVRle{qKTLf17c+r$@Sdt5yY8+8k%qcS77>k8;FdT`r;?R+ybX zF3KQpPHaZ%^bfQXl7Tz~OvHkk>06r1KFh{D==q9Gk4_18e^pdu|3oyQE5fHJ0)a-W zPYh6G&*b{fAAWmk!5k<5)n~Qg0X7AsLb1R165M-+k_K8TM-B}m=08gObr5sywkj{L z<-qR7H+ygPDh-mo_By{WoZkL={ zR|*T8uQSq`1u{Q#Ul-{~??R^U%pxr9q(cmtAgi;HHuWjuU75YP9~Pr|(TesyxG>Y_2tKA>oQNT~Qm}s3qcBo{ke;A?wgZm=l@$gQ{BVF{W2YFx6xJm6XHu`(%!L4lkU|G&PW3@4%)|)wA6Q%(_3xf#QoU+oexk#Is%+)gb zr0RA1Q57u}wuGm41>*(da-XZ&9dAux*PA`jx$hr%K!-nnulZt4+XGMX@^7n*mm&!) z#r{xSq{S2=w}(n4WE9{%15}wzT)(Y(TMY=X}@5{=fKU@-vS+n>9Mt_cm~@mHI8&Q&2glk3-KDGa(;l^~o_! zvslaA<`&7UxVZD4v5ez+$p_hcr7eFnzb93UG*84^X8`aLEB;%aCw?dC$tYS~P3N%J zc6 zhrO^}D9gqaL`~7R9o^Sx1-9Pp&D<~Odp~B32DGcZKMg=ny6!Y$G0_;e(m37MD)BGV z0i1_*MJ{M6z{%ta1X+Gb2VFx7Z{42rAJzu6elM)REDWdjFE&a>RZ;eh2SkARii2l< zU5W9tOZ%;-V1q!ZvoQ5N`_JL%UBO0P+zdjuePQV~}FGRph z_v!saRa@HSGsHchB7IKra|%FhK>#0MIT}Ki5B;BosoqfjkyjIVmRH?n85ot~*=j=t z)yt28Y!LVuA$$y>l>JGAnU7K_-7fm{N=^eHyVxM_#c#GrgUs z^SO(-f1Gr-oS)pG(wS=Rt-f_!S7x^v27ykybwQiQ^`*Ye>9DJSwD^|bwt8~X@~7#| zFPi*3z{hvIFIwLu3#bD@T1?;lAO!?gL?Q%jYQ%zs=Ss>qQk@B3)Vpa zx9h~?-~p)5TkO&De7>}Je6XCe>DsEt`UdI^yPUs#k?qHUmpU9VE^wC%x)%pt7JL#Uurm#KKs+qX1fHT>Dz6Mj1wo9^ za26;(r0jz-0D+yrJ-B8(BZUBw%}_3AfMOMX-zi_XY!Uey8bGJnI(}Zj7fJ%dy?htK z*wk0#Uy5mHpzf*+Bt?QaItw7ra}v@ck<0Pmh(}S2zu9ou4kUa53MK}5IIY~GzXvec zpq2R2{S&xw2z?LC)bNUSfI|3z^x!>gF0Ne~WYU?7pe}f120~n{rO+8*JE-gc?pc%b zc1rcJ=l29^A0%-CV2IN1Ab1F$3UH(@;VScgdV+d$(J4^v&I^P`6N4bE$XbTd=a!(( zS^$!f;Mpzgbef3`+Uk z6EY_C0EOzxFM-Z!4afW3O15RMsq{LqYjNyy`KrfkERZi7dzzWA$(h1_MbiAfdnyMK z%4ZgmmfS!xJ_S{U(f<-+7TUrpQ6E}MXt`tK0ep&8fgp>4K$yz+_~PLNzKtKY8fuW+ zFw4_IC$0Qo+1!g35P4#hjR7+dq~9#~}Nd zX6_&9CcOum)qbd0ItKIt$rnb*YuNy7Sjc$mUJx?X3_Z>>=$THk4`665houaSAaZQ| zfbx{~pT>f&K9*~K-0}iYLb5QKEv0}n! z(oywk6^_zc4yZTefyz09pjc>5eEa2`5D!FpGB!S4N0q}DlTIzK^=nnLZL5$G=C4`B(lTeB3^t@Q9>HJ3d8r8{{$1!(h%!ULz1^#x; zHst{hjblz=X)94$<-f)rZ-4hxgCfp9}JPgL+aI)(Yz~r`d?UdSYp~aUbWoU*J6V3b~hvbmg`ruCi>x zD3_7E^WE%2M?8MysDYjD)#3C@uKNBCP^WFSR0ln+W$&zE8UrehGj6r02SFf(Wo-hA zHm87w#BQZ~!UICk?xP*T?;vCq50tOB+ThAi^rNdUo`nelbM)Ihrz%#Op`#F9%HwHK z&nf;V$jY4EPLn@pww>2T^rBvu$G=*q+;Ii*$^*Di{Y+toI#qeO|31@qWzo-bOEb}i zxb^%7UB_GxArlv$hR6$sflbSz;!7|&v-kK0U39KzLIV$%*@|ZR@dG)qV-etNl}_F# z^`-6spsxkZam+sMF(?}SziqAEl!VODOOG3I6?aO3RM&HQrDn>mGs5RNUz@;L*DWbW zXD6aOSUaiS2Zof{ 40 km/h). Apart from that, there are Stop & Go systems that support lower velocites (e.g. < 40 km/h). In our case, both systems might be needed and it might be reasonable to develop two different systems for ACC and Stop & Go. +The threshold to distinguish between the two systems has to be chosen reasonably. +There are basically three different techniques that can be used to implement an ACC: PID Control, Model Predictive Control and Fuzzy Logic Control. Another option is CACC (Cooperative Adaptive Cruise Control) but this is not relevant for our project since it requires communication between the vehicles. + +### PID Control + +The PID Controller consists of three terms: the proportional term, the integral term and the derivative term. One possible simple controller model looks as follows: + +$$ v_f(t) = v_f(t - t_s) + k_p e(t-t_s) + k_i \int_{0}^{t} e(\tau) d\tau + k_d \dot{e}(t - t_s) $$ +$$ e(t-t_s) = \Delta x(t - t_s) - t_{hw,d} v_f (t - t_s) $$ + +- $v_f$: follower vehicle velocity (transmitted to the acting component) +- $t_s$: sampling time +- $k_p$ and $k_i$ and $k_d$: coefficients for proportional, integral and derivative terms +- $e$: distance error (difference between actual distance $\Delta x$ and desired distance $\Delta x_d$) +- $t_{hw,d}$: desired time headway (duration between the arrival of the first car at a certain waypoint and the arrival of the following car at the same waypoint) + +### Model Predictive Control (MPC) + +It calculates the current control action by solving an online, iterative and finite-horizon optimization of the model. +Procedure: + +1. Prediction of future system states based on current states +2. Computation of the cost function for a finite time horizon in the future +3. Implementation of the first step of the solved control sequence +4. Application of the feedback control loop to compensate for the predictive error and model inaccuracy +5. Sampling of new current states and repitition of the process + +### Fuzzy Logic Control (FLC) + +Provides a unified control framework to offer both functions: ACC and Stop & Go. + +![Example of a FLC control algorithm showing input variables (relative distance, host vehicle speed), fuzzy rules processing, and output variable](../../../assets/research_assets/ACC_FLC_Example_1.PNG) + +## ACC in our project + +### Current implementation + +- General behaviour: + checks for obstacle distance < safety distance + + calculates new speed based on obstacle distance + + else keep current speed + +- publishes speed to acc_velocity +- safe distance calculation is currently not correct, uses speed + (speed * 0.36)² which results in wrong distances +- if car in front of us ignores speed limits we ignore them as well +- some parts of unstuck routine are in ACC and need to be refactored +- same goes for publishing of current waypoint, this should not be in ACC + +In summary, the current implementation is not sufficient and needs major refactoring. + +### Concept for new implementation + +The new concept for the ACC is to take the trajectory, look at all or a limited subset of the next points and add a target velocity and the current behaviour to each point. +This way the Acting has more knowledge about what the car is doing and can adjust accordingly in a local manner. +For this a new trajectory message type was implemented in #511. + +![trajectoryMsg](https://github.com/user-attachments/assets/0b452f1a-4c60-45b2-882f-3a50118c9cb9) + +Since behaviour is passed as an ID a new enum for behaviours was implemented in utils.py as well. + +The general idea for speeds above the 40 km/h mark is to calculate a proper safety distance, a general target velocity and velocity targets based on PID. For speeds lower than that a stop and go system can be discussed if it is really needed. + +For safety distance we would like to calculate it like FLC but that most likely needs some adjustments as setting the distance to 100m when there is no vehicle ahead seems unreasonable. +We can just directly set the velocity to the speed limit in that case. + +For a general speed target we either take the speed of the car in front or the speed limit, whichever is lower. In cases where the car in front is substantially slower than the speed limit ACC could inititate overtaking. + +Since we want to calculate the desired speed at each point of the trajectory, the way PID calculates velocity seems reasonable since we can treat the trajectory points as different points in time for the sampling time. +For example let's say we sample every fifth point and calculate the velocity for that, then we can just interpolate every other point inbetween. + +$v_f(t - t_s)$ would then simply be the velocity of the fifth point before the current one. Theoretically this allows us to dynamically adjust the sampling time as well if needed. + +For the distance error we can use the safety distance as the desired distance. The distance at time t needs to be predicted based on the (predicted) distance at the prior sample point and the calculated speed at the prior sample point. + +We calculate velocities like that up to the point where the actual distance is within 5% of the optimal safety distance. For points further than that we simply use the desired general speed. + +![accDiagram](https://github.com/user-attachments/assets/9a7b4572-f041-4da0-900c-51ab20d1904b) + +### Possible next steps + +A seperate file for the new ACC should be created to not disturb the system. + +The parts that might get cut from ACC like current waypoint and unstuck routine need to be evaluated for necessity and if need be moved to somewhere more fitting. + +Implement publisher for new message type. + +Start implementing safety distance and general target speed logic. Subscriber logic could be taken from old implementation. + +Implement PID logic + +### Requirements + +- obstacle speed +- obstacle distance + +## Discussion + +- How to test adaptations of the ACC? (Suggestion: Create test scenarios which represent different situations like driving straight forward behing a leading vehicle, no leading vehicle, sudden breaking, etc.) +- Which output should be transfered to the Acting component? (Suggestion: The desired speed is published in the new trajectory. No acceleration data is needed, the acceleration is handled by the acting component.) +- Which input do we get from the Perception component? (Suggestion: The distance and velocity of the car in front would be really helpful.) + +## Sources + +He, Yinglong et al. (2019). Adaptive Cruise Control Strategies Implemented on Experimental Vehicles: A Review. IFAC-PapersOnLine. 52. 21-27. 10.1016/j.ifacol.2019.09.004. +[Link](https://www.researchgate.net/publication/335934496_Adaptive_Cruise_Control_Strategies_Implemented_on_Experimental_Vehicles_A_Review) From 094d8ed084b2912d36e84251e9a2859d8dcc2b25 Mon Sep 17 00:00:00 2001 From: ll7 <32880741+ll7@users.noreply.github.com> Date: Fri, 6 Dec 2024 09:20:50 +0100 Subject: [PATCH 69/85] update project management and review guidelines to use TIP instead of INFO --- doc/development/project_management.md | 2 +- doc/development/review_guideline.md | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/development/project_management.md b/doc/development/project_management.md index ef5e45d7..ec772185 100644 --- a/doc/development/project_management.md +++ b/doc/development/project_management.md @@ -50,4 +50,4 @@ Merge the pull request after: After merging, remember to delete the source branch to keep the repository clean. ->[!INFO] For more information about the review process, see [Review process](./review_guideline.md). +>[!TIP] For more information about the review process, see [Review process](./review_guideline.md). diff --git a/doc/development/review_guideline.md b/doc/development/review_guideline.md index 840adb48..64a502c9 100644 --- a/doc/development/review_guideline.md +++ b/doc/development/review_guideline.md @@ -95,7 +95,7 @@ If a comment of a review was resolved by either, a new commit or a discussion be If a new commit took place it is encouraged to comment the commit SHA to have a connection between comment and resolving commit ![img.png](../assets/Resolve_conversation.png) -> [!INFO] All conversations should be resolved before merging the pull request. +> [!TIP] All conversations should be resolved before merging the pull request. ## 5. Merging a Pull Request @@ -120,7 +120,7 @@ Long story short, the reviewer who approves the PR should merge. Only approve if Before merging a pull request, the request checks by the CI/CD pipeline should be successful. If the checks fail, the pull request should not be merged. -> [!INFO] An exception can be made for a PR that only addresses the documentation and the `driving` check is not yet completed. +> [!TIP] An exception can be made for a PR that only addresses the documentation and the `driving` check is not yet completed. ### 5.3. Deleting the branch From 1452879c894c9036ad64d07932f51725c559faa7 Mon Sep 17 00:00:00 2001 From: SirMDA Date: Mon, 9 Dec 2024 14:58:46 +0100 Subject: [PATCH 70/85] fixed import error with __init__ file --- code/perception/src/__init__.py | 0 code/perception/src/vision_node.py | 50 ++++++++++++++++-------------- 2 files changed, 27 insertions(+), 23 deletions(-) create mode 100755 code/perception/src/__init__.py diff --git a/code/perception/src/__init__.py b/code/perception/src/__init__.py new file mode 100755 index 00000000..e69de29b diff --git a/code/perception/src/vision_node.py b/code/perception/src/vision_node.py index abbe52a7..1a558df2 100755 --- a/code/perception/src/vision_node.py +++ b/code/perception/src/vision_node.py @@ -15,7 +15,7 @@ ) import torchvision.transforms as t import cv2 -from perception.src.vision_node_helper import get_carla_class_name, get_carla_color +from vision_node_helper import get_carla_class_name, get_carla_color from rospy.numpy_msg import numpy_msg from sensor_msgs.msg import Image as ImageMsg from std_msgs.msg import Header, Float32MultiArray @@ -356,9 +356,12 @@ def predict_ultralytics(self, image): c_boxes = [] c_labels = [] c_colors = [] + if hasattr(output[0], "masks") and output[0].masks is not None: + masks = output[0].masks.data + else: + masks = None boxes = output[0].boxes - masks = output[0].masks.data for box in boxes: cls = box.cls.item() # class index of object pixels = box.xyxy[0] # upper left and lower right pixel coords @@ -366,16 +369,17 @@ def predict_ultralytics(self, image): # only run distance calc when dist_array is available # this if is needed because the lidar starts # publishing with a delay - if self.dist_arrays is not None: - - # crop bounding box area out of depth image - distances = np.asarray( - self.dist_arrays[ - int(pixels[1]) : int(pixels[3]) : 1, - int(pixels[0]) : int(pixels[2]) : 1, - ::, - ] - ) + if self.dist_arrays is None: + continue + + # crop bounding box area out of depth image + distances = np.asarray( + self.dist_arrays[ + int(pixels[1]) : int(pixels[3]) : 1, + int(pixels[0]) : int(pixels[2]) : 1, + ::, + ] + ) # set all 0 (black) values to np.inf (necessary if # you want to search for minimum) @@ -454,18 +458,18 @@ def predict_ultralytics(self, image): width=3, font_size=12, ) + if masks is not None: + scaled_masks = np.squeeze( + scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), + 1, + ) - scaled_masks = np.squeeze( - scale_masks(masks.unsqueeze(1), cv_image.shape[:2], True).cpu().numpy(), - 1, - ) - - drawn_images = draw_segmentation_masks( - drawn_images, - torch.from_numpy(scaled_masks > 0), - alpha=0.6, - colors=c_colors, - ) + drawn_images = draw_segmentation_masks( + drawn_images, + torch.from_numpy(scaled_masks > 0), + alpha=0.6, + colors=c_colors, + ) np_image = np.transpose(drawn_images.detach().numpy(), (1, 2, 0)) return cv2.cvtColor(np_image, cv2.COLOR_BGR2RGB) From 07794547ed31d4af0743270c7c1480c8d0a49642 Mon Sep 17 00:00:00 2001 From: Ralf Date: Mon, 9 Dec 2024 17:17:27 +0100 Subject: [PATCH 71/85] added deletion of old markers --- code/perception/src/radar_node.py | 93 +++++++++++++++++++++++++++++-- code/requirements.txt | 3 +- 2 files changed, 89 insertions(+), 7 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 39ed7ec0..ddff6511 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -46,20 +46,26 @@ def callback(self, data): cloud = create_pointcloud2(dataarray, clustered_data.labels_) self.visualization_radar_publisher.publish(cloud) - cluster_info = generate_cluster_labels_and_colors(clustered_data, dataarray) - self.cluster_info_radar_publisher.publish(cluster_info) - points_with_labels = np.hstack((dataarray, clustered_data.labels_.reshape(-1, 1))) bounding_boxes = generate_bounding_boxes(points_with_labels) marker_array = MarkerArray() + # marker_array = clear_old_markers(marker_array) for label, bbox in bounding_boxes: if label != -1: marker = create_bounding_box_marker(label, bbox) marker_array.markers.append(marker) + # min_marker, max_marker = create_min_max_markers(label, bbox) + # marker_array.markers.append(min_marker) + # marker_array.markers.append(max_marker) + + marker_array = clear_old_markers(marker_array, max_id=len(bounding_boxes) - 1) self.marker_visualization_radar_publisher.publish(marker_array) + cluster_info = generate_cluster_labels_and_colors(clustered_data, dataarray, marker_array, bounding_boxes) + self.cluster_info_radar_publisher.publish(cluster_info) + def listener(self): """Initializes the node and its publishers.""" rospy.init_node("radar_node") @@ -366,12 +372,85 @@ def create_bounding_box_marker(label, bbox): for start, end in lines: marker.points.append(points[start]) marker.points.append(points[end]) - + return marker +def create_min_max_markers(label, bbox, frame_id="hero/RADAR", min_color=(0.0, 1.0, 0.0, 1.0), max_color=(1.0, 0.0, 0.0, 1.0)): + """ + Erstellt RViz-Marker für die Min- und Max-Punkte einer Bounding Box. + + Args: + label (int): Die ID des Clusters (wird als Marker-ID genutzt). + bbox (tuple): Min- und Max-Werte der Bounding Box (x_min, x_max, y_min, y_max, z_min, z_max). + frame_id (str): Frame ID, in dem die Marker gezeichnet werden. + min_color (tuple): RGBA-Farbwerte für den Min-Punkt-Marker. + max_color (tuple): RGBA-Farbwerte für den Max-Punkt-Marker. + + Returns: + tuple: Ein Paar von Markern (min_marker, max_marker). + """ + x_min, x_max, y_min, y_max, z_min, z_max = bbox + + # marker = Marker() + # marker.header.frame_id = "hero/RADAR" + # marker.id = int(label) + # # marker.type = Marker.LINE_STRIP + # marker.type = Marker.LINE_LIST + # marker.action = Marker.ADD + # marker.scale.x = 0.1 + # marker.color.r = 1.0 + # marker.color.g = 1.0 + # marker.color.b = 0.0 + # marker.color.a = 1.0 + + # Min-Punkt-Marker + min_marker = Marker() + min_marker.header.frame_id = frame_id + min_marker.id = int(label * 10) # ID für Min-Punkt + min_marker.type = Marker.SPHERE + min_marker.action = Marker.ADD + min_marker.scale.x = 0.2 # Größe des Punktes + min_marker.scale.y = 0.2 + min_marker.scale.z = 0.2 + min_marker.color.r = min_color[0] + min_marker.color.g = min_color[1] + min_marker.color.b = min_color[2] + min_marker.color.a = min_color[3] + min_marker.pose.position.x = x_min + min_marker.pose.position.y = y_min + min_marker.pose.position.z = z_min + + # Max-Punkt-Marker + max_marker = Marker() + max_marker.header.frame_id = frame_id + max_marker.id = int(label * 10 + 1) # ID für Max-Punkt + max_marker.type = Marker.SPHERE + max_marker.action = Marker.ADD + max_marker.scale.x = 0.2 + max_marker.scale.y = 0.2 + max_marker.scale.z = 0.2 + max_marker.color.r = max_color[0] + max_marker.color.g = max_color[1] + max_marker.color.b = max_color[2] + max_marker.color.a = max_color[3] + max_marker.pose.position.x = x_max + max_marker.pose.position.y = y_max + max_marker.pose.position.z = z_max + + return min_marker, max_marker + + +def clear_old_markers(marker_array, max_id): + """Löscht alte Marker aus dem MarkerArray.""" + for marker in marker_array.markers: + if marker.id >= max_id: + marker.action = Marker.DELETE + return marker_array + + # generates string with label-id and cluster size -def generate_cluster_labels_and_colors(clusters, data): +def generate_cluster_labels_and_colors(clusters, data, marker_array, bounding_boxes): cluster_info = [] for label in set(clusters.labels_): @@ -380,7 +459,9 @@ def generate_cluster_labels_and_colors(clusters, data): if label != -1: cluster_info.append({ "label": int(label), - "points_count": cluster_size + "points_count": cluster_size, + "Anzahl marker": len(marker_array.markers), + "Anzahl Boundingboxen": len(bounding_boxes) }) return json.dumps(cluster_info) diff --git a/code/requirements.txt b/code/requirements.txt index 55de87f0..cbe57476 100644 --- a/code/requirements.txt +++ b/code/requirements.txt @@ -16,4 +16,5 @@ numpy==1.23.5 ultralytics==8.1.11 scikit-learn>=0.18 pandas==2.0.3 -debugpy==1.8.7 \ No newline at end of file +debugpy==1.8.7 +pyopenssl==24.3.0 \ No newline at end of file From c46c93428e9ba3988c2b5413972ce422687a4fad Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 14:39:38 +0100 Subject: [PATCH 72/85] - Added clustering functionality for LiDAR data processing. - Refactored the existing node code by modularizing it into functions for better readability and maintainability. --- code/perception/launch/perception.launch | 2 +- code/perception/src/lidar_distance.py | 48 ++++++++++++++++++++++-- 2 files changed, 45 insertions(+), 5 deletions(-) diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 67a9c2ab..127ae9a4 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -75,7 +75,7 @@ - + diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index 04394ee2..2842172c 100755 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -3,13 +3,13 @@ import ros_numpy import numpy as np import lidar_filter_utility -from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointCloud2, Image as ImageMsg +from sklearn.cluster import DBSCAN +from cv_bridge import CvBridge +import json # from mpl_toolkits.mplot3d import Axes3D # from itertools import combinations -from sensor_msgs.msg import Image as ImageMsg -from cv_bridge import CvBridge - # from matplotlib.colors import LinearSegmentedColormap @@ -30,6 +30,22 @@ def callback(self, data): """ coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + # clustered_points = cluster_lidar_data_from_pointcloud(coordinates.copy()) + try: + filtered_coordinates = coordinates[coordinates["z"] > 0] + + # Konvertiere in JSON + clustered_points_json = json.dumps(filtered_coordinates.tolist()) + + # Veröffentliche JSON-Daten + # self.dist_array_lidar_publisher.publish(clustered_points_json) + rospy.loginfo( + f"JSON mit {len(clustered_points_json)} Punkten veröffentlicht." + ) + rospy.loginfo(clustered_points_json) + except Exception as e: + rospy.logerr(f"Fehler im Callback: {e}") + # Center reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( coordinates, @@ -146,6 +162,20 @@ def listener(self): queue_size=10, ) + """ + try: + self.dist_array_lidar_publisher = rospy.Publisher( + rospy.get_param( + "~image_distance_topic_cluster", "/paf/hero/Lidar/dist_clustered" + ), + String, + queue_size=10, + ) + rospy.loginfo("dist_array_lidar_publisher erfolgreich erstellt.") + except Exception as e: + rospy.logerr(f"Fehler beim Erstellen von dist_array_lidar_publisher: {e}") + """ + # publisher for dist_array self.dist_array_left_publisher = rospy.Publisher( rospy.get_param("~image_distance_topic", "/paf/hero/Left/dist_array"), @@ -166,6 +196,7 @@ def listener(self): self.callback, ) + rospy.loginfo("Lidar Processor Node gestartet.") rospy.spin() def reconstruct_img_from_lidar(self, coordinates_xyz, focus): @@ -246,6 +277,15 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): return dist_array +def cluster_lidar_data_from_pointcloud(coordinates, eps=1.0, min_samples=2): + + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) + labels = clustering.labels_ + clustered_points = {label: list(labels).count(label) for label in set(labels)} + clustered_points = {int(label): count for label, count in clustered_points.items()} + return clustered_points + + if __name__ == "__main__": lidar_distance = LidarDistance() lidar_distance.listener() From 08e21757aa08fa8d3b3132d4823e673f38a8e834 Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 14:45:44 +0100 Subject: [PATCH 73/85] Added clustering functionality for LiDAR data processing. --- code/agent/config/rviz_config.rviz | 93 +++- code/perception/src/lidar_distance.py | 482 ++++++++++++++------ code/perception/src/lidar_distance_neu.py | 516 ++++++++++++++++++++++ 3 files changed, 933 insertions(+), 158 deletions(-) mode change 100755 => 100644 code/perception/src/lidar_distance.py create mode 100755 code/perception/src/lidar_distance_neu.py diff --git a/code/agent/config/rviz_config.rviz b/code/agent/config/rviz_config.rviz index 2e419cc2..998284c8 100644 --- a/code/agent/config/rviz_config.rviz +++ b/code/agent/config/rviz_config.rviz @@ -1,14 +1,12 @@ Panels: - Class: rviz/Displays - Help Height: 78 + Help Height: 70 Name: Displays Property Tree Widget: Expanded: - - /PointCloud23 - - /PointCloud24 - - /PointCloud25 + - /PointCloud2 dist_clustered1 Splitter Ratio: 0.5 - Tree Height: 308 + Tree Height: 325 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -66,26 +64,23 @@ Visualization Manager: Grid: false Imu: false Path: false - PointCloud2: false + PointCloud2: true + PointCloud2 dist_clustered: true Value: true + VisonNode Output: true Zoom Factor: 1 - Class: rviz/Image Enabled: true - Image Rendering: background and overlay Image Topic: /paf/hero/Center/segmented_image + Max Value: 1 + Median window: 5 + Min Value: 0 Name: VisonNode Output - Overlay Alpha: 0.5 + Normalize Range: true Queue Size: 2 Transport Hint: raw Unreliable: false Value: true - Visibility: - Grid: true - Imu: true - Path: true - PointCloud2: true - Value: true - Zoom Factor: 1 - Alpha: 1 Class: rviz_plugin_tutorials/Imu Color: 204; 51; 204 @@ -260,6 +255,62 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 + Position Transformer: "" + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /paf/hero/dist_clustered + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: PointCloud2 dist_clustered + Position Transformer: "" + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /paf/hero/dist_clustered + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -288,7 +339,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 34.785499572753906 + Distance: 10.540092468261719 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -304,9 +355,9 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.19039836525917053 + Pitch: 0.3953982889652252 Target Frame: - Yaw: 4.520427227020264 + Yaw: 3.255431652069092 Saved: ~ Window Geometry: Camera: @@ -316,7 +367,7 @@ Window Geometry: Height: 1376 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000304000004c6fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000022a000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061010000026b000002960000001600ffffff000000010000010f000004c6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000004c6000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b80000003efc0100000002fb0000000800540069006d00650100000000000009b80000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000599000004c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000304000004c6fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000002070000021e0000001600fffffffb00000020005600690073006f006e004e006f006400650020004f00750074007000750074010000042b000000d60000001600ffffff000000010000010f000004c6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000004c6000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b80000003efc0100000002fb0000000800540069006d00650100000000000009b80000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000599000004c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -325,6 +376,8 @@ Window Geometry: collapsed: false Views: collapsed: false + VisonNode Output: + collapsed: false Width: 2488 X: 1992 - Y: 27 \ No newline at end of file + Y: 27 diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py old mode 100755 new mode 100644 index 2842172c..260cbea8 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -1,4 +1,5 @@ #!/usr/bin/env python +from joblib import Parallel, delayed import rospy import ros_numpy import numpy as np @@ -6,7 +7,6 @@ from sensor_msgs.msg import PointCloud2, Image as ImageMsg from sklearn.cluster import DBSCAN from cv_bridge import CvBridge -import json # from mpl_toolkits.mplot3d import Axes3D # from itertools import combinations @@ -18,35 +18,159 @@ class LidarDistance: how to configute this node """ + cluster_buffer = [] + def callback(self, data): - """Callback function, filters a PontCloud2 message - by restrictions defined in the launchfile. + """ + Callback-Funktion, die LiDAR-Punktwolkendaten verarbeitet. + + Führt Clustering und Bildberechnungen für die Punktwolken aus. - Publishes a Depth image for the specified camera angle. - Each angle has do be delt with differently since the signs of the - coordinate system change with the view angle. + :param data: LiDAR-Punktwolken als ROS PointCloud2-Nachricht. + """ + + self.start_clustering(data) + self.start_image_calculation(data) - :param data: a PointCloud2 + def listener(self): """ + Initialisiert die ROS-Node, erstellt Publisher/Subscriber und hält sie aktiv. + """ + rospy.init_node("lidar_distance") + self.bridge = CvBridge() # OpenCV-Bridge für Bildkonvertierungen + + # Publisher für gefilterte Punktwolken + self.pub_pointcloud = rospy.Publisher( + rospy.get_param( + "~point_cloud_topic", + "/carla/hero/" + rospy.get_namespace() + "_filtered", + ), + PointCloud2, + queue_size=1, + ) + + # Publisher für Distanzbilder in verschiedene Richtungen + self.dist_array_center_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), + ImageMsg, + queue_size=10, + ) + self.dist_array_back_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Back/dist_array"), + ImageMsg, + queue_size=10, + ) + self.dist_array_lidar_publisher = rospy.Publisher( + rospy.get_param( + "~image_distance_topic_cluster", "/paf/hero/dist_clustered" + ), + PointCloud2, + queue_size=10, + ) + rospy.loginfo("dist_array_lidar_publisher erfolgreich erstellt.") + self.dist_array_left_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Left/dist_array"), + ImageMsg, + queue_size=10, + ) + self.dist_array_right_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Right/dist_array"), + ImageMsg, + queue_size=10, + ) + + # Subscriber für LiDAR-Daten (Punktwolken) + rospy.Subscriber( + rospy.get_param("~source_topic", "/carla/hero/LIDAR"), + PointCloud2, + self.callback, + ) + + rospy.loginfo("Lidar Processor Node gestartet.") + rospy.spin() + + def start_clustering(self, data): + """ + Filtert LiDAR-Punktwolken, führt Clustering durch und veröffentlicht die kombinierten Cluster. + + :param data: LiDAR-Punktwolken im ROS PointCloud2-Format. + """ + + # Punktwolken filtern, um irrelevante Daten zu entfernen coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + filtered_coordinates = coordinates[ + ~( + (-2 <= coordinates["x"]) + & (coordinates["x"] <= 2) + & (-1 <= coordinates["y"]) + & (coordinates["y"] <= 1) + ) # Ausschluss von Punkten die das eigene Auto betreffen + & ( + coordinates["z"] > -1.7 + 0.05 + ) # Mindesthöhe in z, um die Straße nicht zu clustern + ] + + # Cluster-Daten aus den gefilterten Koordinaten berechnen + clustered_points = cluster_lidar_data_from_pointcloud( + coordinates=filtered_coordinates + ) - # clustered_points = cluster_lidar_data_from_pointcloud(coordinates.copy()) - try: - filtered_coordinates = coordinates[coordinates["z"] > 0] + # Nur gültige Cluster-Daten speichern + if clustered_points: + LidarDistance.cluster_buffer.append(clustered_points) + else: + rospy.logwarn("Keine Cluster-Daten erzeugt.") - # Konvertiere in JSON - clustered_points_json = json.dumps(filtered_coordinates.tolist()) + # Cluster kombinieren + combined_clusters = combine_clusters(LidarDistance.cluster_buffer) - # Veröffentliche JSON-Daten - # self.dist_array_lidar_publisher.publish(clustered_points_json) - rospy.loginfo( - f"JSON mit {len(clustered_points_json)} Punkten veröffentlicht." - ) - rospy.loginfo(clustered_points_json) - except Exception as e: - rospy.logerr(f"Fehler im Callback: {e}") + LidarDistance.cluster_buffer = [] + + # Veröffentliche die kombinierten Cluster + self.publish_clusters(combined_clusters, data.header) + + def publish_clusters(self, combined_clusters, data_header): + """ + Veröffentlicht kombinierte Cluster als ROS PointCloud2-Nachricht. - # Center + :param combined_clusters: Kombinierte Punktwolken der Cluster als strukturiertes NumPy-Array. + :param data_header: Header-Informationen der ROS-Nachricht. + """ + # Konvertiere zu PointCloud2-Nachricht + pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2(combined_clusters) + pointcloud_msg.header = data_header + pointcloud_msg.header.stamp = rospy.Time.now() + # Cluster veröffentlichen + self.dist_array_lidar_publisher.publish(pointcloud_msg) + + def start_image_calculation(self, data): + """ + Berechnet Distanzbilder basierend auf LiDAR-Daten und veröffentlicht sie. + + :param data: LiDAR-Punktwolken im ROS PointCloud2-Format. + """ + coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + # Bildverarbeitung auf den Koordinaten durchführen + processed_images = { + "Center": None, + "Back": None, + "Left": None, + "Right": None, + } + processed_images["Center"] = self.calculate_image_center(coordinates) + processed_images["Back"] = self.calculate_image_back(coordinates) + processed_images["Left"] = self.calculate_image_left(coordinates) + processed_images["Right"] = self.calculate_image_right(coordinates) + + self.publish_images(processed_images, data.header) + + def calculate_image_center(self, coordinates): + """ + Berechnet ein Distanzbild für die zentrale Ansicht aus LiDAR-Koordinaten. + + :param coordinates: Gefilterte LiDAR-Koordinaten als NumPy-Array. + :return: Distanzbild als 2D-Array. + """ reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( coordinates, max_x=np.inf, @@ -62,12 +186,9 @@ def callback(self, data): dist_array_center = self.reconstruct_img_from_lidar( reconstruct_coordinates_xyz_center, focus="Center" ) - dist_array_center_msg = self.bridge.cv2_to_imgmsg( - dist_array_center, encoding="passthrough" - ) - dist_array_center_msg.header = data.header - self.dist_array_center_publisher.publish(dist_array_center_msg) + return dist_array_center + def calculate_image_back(self, coordinates): # Back reconstruct_bit_mask_back = lidar_filter_utility.bounding_box( coordinates, @@ -84,12 +205,9 @@ def callback(self, data): dist_array_back = self.reconstruct_img_from_lidar( reconstruct_coordinates_xyz_back, focus="Back" ) - dist_array_back_msg = self.bridge.cv2_to_imgmsg( - dist_array_back, encoding="passthrough" - ) - dist_array_back_msg.header = data.header - self.dist_array_back_publisher.publish(dist_array_back_msg) + return dist_array_back + def calculate_image_left(self, coordinates): # Left reconstruct_bit_mask_left = lidar_filter_utility.bounding_box( coordinates, @@ -106,12 +224,9 @@ def callback(self, data): dist_array_left = self.reconstruct_img_from_lidar( reconstruct_coordinates_xyz_left, focus="Left" ) - dist_array_left_msg = self.bridge.cv2_to_imgmsg( - dist_array_left, encoding="passthrough" - ) - dist_array_left_msg.header = data.header - self.dist_array_left_publisher.publish(dist_array_left_msg) + return dist_array_left + def calculate_image_right(self, coordinates): # Right reconstruct_bit_mask_right = lidar_filter_utility.bounding_box( coordinates, max_y=-0.0, min_y=-np.inf, min_z=-1.6 @@ -125,124 +240,78 @@ def callback(self, data): dist_array_right = self.reconstruct_img_from_lidar( reconstruct_coordinates_xyz_right, focus="Right" ) - dist_array_right_msg = self.bridge.cv2_to_imgmsg( - dist_array_right, encoding="passthrough" - ) - dist_array_right_msg.header = data.header - self.dist_array_right_publisher.publish(dist_array_right_msg) + return dist_array_right - def listener(self): + def publish_images(self, processed_images, data_header): """ - Initializes the node and it's publishers - """ - # run simultaneously. - rospy.init_node("lidar_distance") - self.bridge = CvBridge() - - self.pub_pointcloud = rospy.Publisher( - rospy.get_param( - "~point_cloud_topic", - "/carla/hero/" + rospy.get_namespace() + "_filtered", - ), - PointCloud2, - queue_size=10, - ) - - # publisher for dist_array - self.dist_array_center_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), - ImageMsg, - queue_size=10, - ) - - # publisher for dist_array - self.dist_array_back_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Back/dist_array"), - ImageMsg, - queue_size=10, - ) + Veröffentlicht Distanzbilder für verschiedene Richtungen als ROS-Bildnachrichten. + :param processed_images: Dictionary mit Richtungen ("Center", "Back", etc.) als Schlüssel und Bildarrays als Werte. + :param data_header: Header der ROS-Bildnachrichten. """ - try: - self.dist_array_lidar_publisher = rospy.Publisher( - rospy.get_param( - "~image_distance_topic_cluster", "/paf/hero/Lidar/dist_clustered" - ), - String, - queue_size=10, + # Nur gültige NumPy-Arrays weiterverarbeiten + for direction, image_array in processed_images.items(): + if not isinstance(image_array, np.ndarray): + continue + + # Konvertiere das Bild in eine ROS-Image-Nachricht + dist_array_msg = self.bridge.cv2_to_imgmsg( + image_array, encoding="passthrough" ) - rospy.loginfo("dist_array_lidar_publisher erfolgreich erstellt.") - except Exception as e: - rospy.logerr(f"Fehler beim Erstellen von dist_array_lidar_publisher: {e}") - """ + dist_array_msg.header = data_header - # publisher for dist_array - self.dist_array_left_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Left/dist_array"), - ImageMsg, - queue_size=10, - ) - - # publisher for dist_array - self.dist_array_right_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Right/dist_array"), - ImageMsg, - queue_size=10, - ) - - rospy.Subscriber( - rospy.get_param("~source_topic", "/carla/hero/LIDAR"), - PointCloud2, - self.callback, - ) - - rospy.loginfo("Lidar Processor Node gestartet.") - rospy.spin() + if direction == "Center": + self.dist_array_center_publisher.publish(dist_array_msg) + if direction == "Back": + self.dist_array_back_publisher.publish(dist_array_msg) + if direction == "Left": + self.dist_array_left_publisher.publish(dist_array_msg) + if direction == "Right": + self.dist_array_right_publisher.publish(dist_array_msg) def reconstruct_img_from_lidar(self, coordinates_xyz, focus): """ - reconstruct 3d LIDAR-Data and calculate 2D Pixel - according to Camera-World - - Args: - coordinates_xyz (np.array): filtered lidar points - focus (String): Camera Angle + Rekonstruiert ein 2D-Bild aus 3D-LiDAR-Daten für eine gegebene Kameraansicht. - Returns: - image: depth image for camera angle + :param coordinates_xyz: 3D-Koordinaten der gefilterten LiDAR-Punkte. + :param focus: Kameraansicht (z. B. "Center", "Back"). + :return: Rekonstruiertes Bild als 2D-Array. """ - # intrinsic matrix for camera: - # width -> 300, height -> 200, fov -> 100 (agent.py) + # Erstelle die intrinsische Kamera-Matrix basierend auf den Bildparametern (FOV, Auflösung) im = np.identity(3) - im[0, 2] = 1280 / 2.0 - im[1, 2] = 720 / 2.0 - im[0, 0] = im[1, 1] = 1280 / (2.0 * np.tan(100 * np.pi / 360.0)) + im[0, 2] = 1280 / 2.0 # x-Verschiebung (Bildmitte) + im[1, 2] = 720 / 2.0 # y-Verschiebung (Bildmitte) + im[0, 0] = im[1, 1] = 1280 / ( + 2.0 * np.tan(100 * np.pi / 360.0) + ) # Skalierungsfaktor basierend auf FOV - # extrinsic matrix for camera + # Erstelle die extrinsische Kamera-Matrix (Identität für keine Transformation) ex = np.zeros(shape=(3, 4)) - ex[0][0] = 1 - ex[1][1] = 1 - ex[2][2] = 1 - m = np.matmul(im, ex) + ex[0][0] = ex[1][1] = ex[2][2] = 1 + m = np.matmul(im, ex) # Kombiniere intrinsische und extrinsische Matrix - # reconstruct camera image with LIDAR-Data + # Initialisiere leere Bilder für die Rekonstruktion img = np.zeros(shape=(720, 1280), dtype=np.float32) dist_array = np.zeros(shape=(720, 1280, 3), dtype=np.float32) + + # Verarbeite jeden Punkt in der Punktwolke for c in coordinates_xyz: - # center depth image if focus == "Center": point = np.array([c[1], c[2], c[0], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x <= 1280 and y >= 0 and y <= 720: - img[719 - y][1279 - x] = c[0] + pixel = np.matmul( + m, point + ) # Projiziere 3D-Punkt auf 2D-Bildkoordinaten + x, y = int(pixel[0] / pixel[2]), int( + pixel[1] / pixel[2] + ) # Normalisiere Koordinaten + if x >= 0 and x <= 1280 and y >= 0 and y <= 720: # Prüfe Bildgrenzen + img[719 - y][1279 - x] = c[0] # Setze Tiefenwert dist_array[719 - y][1279 - x] = np.array( [c[0], c[1], c[2]], dtype=np.float32 ) - # back depth image - if focus == "Back": + if focus == "Back": # Berechne Bild für die Rückansicht point = np.array([c[1], c[2], c[0], 1]) pixel = np.matmul(m, point) x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) @@ -252,8 +321,7 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): [-c[0], c[1], c[2]], dtype=np.float32 ) - # left depth image - if focus == "Left": + if focus == "Left": # Berechne Bild für die linke Ansicht point = np.array([c[0], c[2], c[1], 1]) pixel = np.matmul(m, point) x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) @@ -263,8 +331,7 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): [c[0], c[1], c[2]], dtype=np.float32 ) - # right depth image - if focus == "Right": + if focus == "Right": # Berechne Bild für die rechte Ansicht point = np.array([c[0], c[2], c[1], 1]) pixel = np.matmul(m, point) x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) @@ -277,15 +344,154 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): return dist_array -def cluster_lidar_data_from_pointcloud(coordinates, eps=1.0, min_samples=2): +def array_to_pointcloud2(points, header="hero/Lidar"): + """ + Konvertiert ein Array von Punkten in eine ROS PointCloud2-Nachricht. + + :param points: Array von Punkten mit [x, y, z]-Koordinaten. + :param header: Header-Informationen der ROS PointCloud2-Nachricht. + :return: ROS PointCloud2-Nachricht. + """ + # Sicherstellen, dass die Eingabe ein NumPy-Array ist + points_array = np.array(points) + + # Konvertiere die Punkte in ein strukturiertes Array mit Feldern "x", "y", "z" + points_structured = np.array( + [(p[0], p[1], p[2]) for p in points_array], + dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")], + ) + + # Erstelle eine PointCloud2-Nachricht aus dem strukturierten Array + pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2(points_structured) + + # Setze den Zeitstempel und den Header der Nachricht + pointcloud_msg.header.stamp = rospy.Time.now() + pointcloud_msg.header = header + + return pointcloud_msg + + +def get_largest_cluster(clustered_points, return_structured=True): + """ + Ermittelt das größte Cluster aus gegebenen Punktwolken-Clustern. + + :param clustered_points: Dictionary mit Cluster-IDs und zugehörigen Punktwolken. + :param return_structured: Gibt ein strukturiertes NumPy-Array zurück, falls True. + :return: Größtes Cluster als NumPy-Array (roh oder strukturiert). + """ + # Prüfen, ob es Cluster gibt + if not clustered_points: + return np.array([]) + + # Identifiziere das größte Cluster basierend auf der Anzahl der Punkte + largest_cluster_id, largest_cluster = max( + clustered_points.items(), key=lambda item: len(item[1]) + ) + + # Sicherstellen, dass das größte Cluster nicht leer ist + if largest_cluster.size == 0: + return np.array([]) + + rospy.loginfo( + f"Largest cluster: {largest_cluster_id} with {largest_cluster.shape[0]} points" + ) + + # Rohdaten zurückgeben, wenn kein strukturiertes Array benötigt wird + if not return_structured: + return largest_cluster + + # Konvertiere das größte Cluster in ein strukturiertes Array + points_structured = np.empty( + largest_cluster.shape[0], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")] + ) + points_structured["x"] = largest_cluster[:, 0] + points_structured["y"] = largest_cluster[:, 1] + points_structured["z"] = largest_cluster[:, 2] + + return points_structured + - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) +def combine_clusters(cluster_buffer): + """ + Kombiniert Cluster aus mehreren Punktwolken zu einem strukturierten NumPy-Array. + + :param cluster_buffer: Liste von Dictionaries mit Cluster-IDs und Punktwolken. + :return: Kombiniertes strukturiertes NumPy-Array mit Feldern "x", "y", "z", "cluster_id". + """ + points_list = [] + cluster_ids_list = [] + + for clustered_points in cluster_buffer: + for cluster_id, points in clustered_points.items(): + if points.size > 0: # Ignoriere leere Cluster + points_list.append(points) + # Erstelle ein Array mit der Cluster-ID für alle Punkte des Clusters + cluster_ids_list.append( + np.full(points.shape[0], cluster_id, dtype=np.float32) + ) + + if not points_list: # Falls keine Punkte vorhanden sind + return np.array( + [], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"), ("cluster_id", "f4")] + ) + + # Kombiniere alle Punkte und Cluster-IDs in zwei separate Arrays + all_points = np.vstack(points_list) + all_cluster_ids = np.concatenate(cluster_ids_list) + + # Erstelle ein strukturiertes Array für die kombinierten Daten + combined_points = np.zeros( + all_points.shape[0], + dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"), ("cluster_id", "f4")], + ) + combined_points["x"] = all_points[:, 0] + combined_points["y"] = all_points[:, 1] + combined_points["z"] = all_points[:, 2] + combined_points["cluster_id"] = all_cluster_ids + + return combined_points + + +def cluster_lidar_data_from_pointcloud(coordinates, eps=0.3, min_samples=10): + """ + Führt Clustering auf LiDAR-Daten mit DBSCAN durch und gibt Cluster zurück. + + :param coordinates: LiDAR-Punktwolken als NumPy-Array mit "x", "y", "z". + :param eps: Maximaler Abstand zwischen Punkten, um sie zu einem Cluster zuzuordnen. + :param min_samples: Minimale Anzahl von Punkten, um ein Cluster zu bilden. + :return: Dictionary mit Cluster-IDs und zugehörigen Punktwolken. + """ + if coordinates.shape[0] == 0: + rospy.logerr("Das Eingabe-Array 'coordinates' ist leer.") + return {} + + # Extrahiere x, y und z aus den Koordinaten für die DBSCAN-Berechnung + xyz = np.column_stack((coordinates["x"], coordinates["y"], coordinates["z"])) + + if xyz.shape[0] == 0: + rospy.logwarn("Keine Datenpunkte für DBSCAN verfügbar. Überspringe Clustering.") + return {} + + # Wende DBSCAN an, um Cluster-Labels für die Punktwolke zu berechnen + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(xyz) labels = clustering.labels_ - clustered_points = {label: list(labels).count(label) for label in set(labels)} - clustered_points = {int(label): count for label, count in clustered_points.items()} - return clustered_points + + # Entferne Rauschen (Cluster-ID: -1) und bestimme gültige Cluster-IDs + unique_labels = np.unique(labels) + valid_labels = unique_labels[unique_labels != -1] + + # Erstelle ein Dictionary mit Cluster-IDs und den zugehörigen Punkten + clusters = Parallel(n_jobs=-1)( + delayed(lambda l: (l, xyz[labels == l]))(label) for label in valid_labels + ) + clusters = dict(clusters) + + return clusters if __name__ == "__main__": + """ + Initialisiert die LidarDistance-Klasse und startet die Listener-Methode. + """ lidar_distance = LidarDistance() lidar_distance.listener() diff --git a/code/perception/src/lidar_distance_neu.py b/code/perception/src/lidar_distance_neu.py new file mode 100755 index 00000000..57892ed6 --- /dev/null +++ b/code/perception/src/lidar_distance_neu.py @@ -0,0 +1,516 @@ +#!/usr/bin/env python +import rospy +import ros_numpy +import numpy as np +import lidar_filter_utility +from sensor_msgs.msg import PointCloud2, Image as ImageMsg +from sklearn.cluster import DBSCAN +from cv_bridge import CvBridge +from joblib import Parallel, delayed +import queue +import threading + +# from mpl_toolkits.mplot3d import Axes3D +# from itertools import combinations +# from matplotlib.colors import LinearSegmentedColormap + + +class LidarDistance: + """See doc/perception/lidar_distance_utility.md on + how to configute this node + """ + + # Klassenattribute + cluster_queue = queue.Queue() + image_queue = queue.Queue() + workers_initialized = False + cluster_data_list = [] + + def callback(self, data): + """Callback function, filters a PontCloud2 message + by restrictions defined in the launchfile. + + Publishes a Depth image for the specified camera angle. + Each angle has do be delt with differently since the signs of the + coordinate system change with the view angle. + + :param data: a PointCloud2 + """ + + if not LidarDistance.workers_initialized: + LidarDistance.workers_initialized = True + self.start_image_worker() + self.start_cluster_worker() + + if not self.cluster_thread.is_alive: + rospy.logwarn("Cluster-Worker abgestürzt. Neustart...") + self.start_cluster_worker() + + if not self.image_thread.is_alive: + rospy.logwarn("Image-Worker abgestürzt. Neustart...") + self.start_image_worker() + + LidarDistance.cluster_queue.put(data) + if LidarDistance.cluster_queue.qsize() > 10: + rospy.logwarn( + "Cluster-Worker kommt nicht hinterher. Queue size:" + + str(LidarDistance.cluster_queue.qsize()), + ) + # Dasselbe Koordinatenset für die Bildberechnung in die Bild-Warteschlange legen + LidarDistance.image_queue.put(data) + if LidarDistance.image_queue.qsize() > 10: + rospy.logwarn( + f"Image-Worker ({self.image_thread.is_alive}) kommt nicht hinterher. Queue size: {str(LidarDistance.image_queue.qsize())}" + ) + + def listener(self): + """ + Initializes the node and it's publishers + """ + # run simultaneously. + rospy.init_node("lidar_distance") + self.bridge = CvBridge() + + self.pub_pointcloud = rospy.Publisher( + rospy.get_param( + "~point_cloud_topic", + "/carla/hero/" + rospy.get_namespace() + "_filtered", + ), + PointCloud2, + queue_size=10, + ) + + # publisher for dist_array + self.dist_array_center_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), + ImageMsg, + queue_size=10, + ) + + # publisher for dist_array + self.dist_array_back_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Back/dist_array"), + ImageMsg, + queue_size=10, + ) + + self.dist_array_lidar_publisher = rospy.Publisher( + rospy.get_param( + "~image_distance_topic_cluster", "/paf/hero/dist_clustered" + ), + PointCloud2, + queue_size=10, + ) + rospy.loginfo("dist_array_lidar_publisher erfolgreich erstellt.") + + # publisher for dist_array + self.dist_array_left_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Left/dist_array"), + ImageMsg, + queue_size=10, + ) + + # publisher for dist_array + self.dist_array_right_publisher = rospy.Publisher( + rospy.get_param("~image_distance_topic", "/paf/hero/Right/dist_array"), + ImageMsg, + queue_size=10, + ) + + rospy.Subscriber( + rospy.get_param("~source_topic", "/carla/hero/LIDAR"), + PointCloud2, + self.callback, + ) + + rospy.loginfo("Lidar Processor Node gestartet.") + rospy.spin() + + def cluster_worker(self): + """ + Worker für das Clustern von Punkten. + """ + while True: + try: + # Neueste Aufgabe holen + data = LidarDistance.cluster_queue.get(timeout=1) + + # Restliche Aufgaben aus der Queue entfernen + discarded_tasks = 0 + while not LidarDistance.cluster_queue.empty(): + LidarDistance.cluster_queue.get() + discarded_tasks += 1 + + # Anzahl verworfener Einträge loggen + if discarded_tasks > 0: + rospy.logwarn(f"{discarded_tasks} Einträge wurden verworfen.") + + # Stop-Signal überprüfen + if data is None: # Stop-Signal + break + + # Punktwolken-Daten verarbeiten + coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + filtered_coordinates = coordinates[(coordinates["x"] >= 2)] + clustered_points = cluster_lidar_data_from_pointcloud( + coordinates=filtered_coordinates + ) + + # Kombinierte Cluster erstellen + cluster_structured = combine_clusters(clustered_points) + + # Konvertiere zu PointCloud2-Nachricht + pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2( + cluster_structured + ) + pointcloud_msg.header = data.header + pointcloud_msg.header.stamp = rospy.Time.now() + + # Cluster veröffentlichen + self.dist_array_lidar_publisher.publish(pointcloud_msg) + + except queue.Empty: + rospy.loginfo("Cluster-Queue ist leer. Warte auf neue Aufgaben.") + continue # Zurück zur Queue-Warte + + except Exception as e: + rospy.logerr(f"Fehler im Cluster-Worker: {e}") + + def image_worker(self): + """ + Worker für die Berechnung von Bildern. + """ + while True: + data = LidarDistance.image_queue.get() + if data is None: # Stop-Signal + break + + coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) + # Bildverarbeitung auf den Koordinaten durchführen + processed_images = { + "Center": None, + "Back": None, + "Left": None, + "Right": None, + } + processed_images["Center"] = self.calculate_image_center(coordinates) + processed_images["Back"] = self.calculate_image_back(coordinates) + processed_images["Left"] = self.calculate_image_left(coordinates) + processed_images["Right"] = self.calculate_image_right(coordinates) + + self.publish_images(processed_images, data.header) + + def start_cluster_worker(self): + self.cluster_thread = threading.Thread(target=self.cluster_worker, daemon=True) + self.cluster_thread.start() + + def start_image_worker(self): + self.image_thread = threading.Thread(target=self.image_worker, daemon=True) + self.image_thread.start() + + def calculate_image_center(self, coordinates): + reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( + coordinates, + max_x=np.inf, + min_x=0.0, + min_z=-1.6, + ) + reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] + reconstruct_coordinates_xyz_center = np.array( + lidar_filter_utility.remove_field_name( + reconstruct_coordinates_center, "intensity" + ).tolist() + ) + dist_array_center = self.reconstruct_img_from_lidar( + reconstruct_coordinates_xyz_center, focus="Center" + ) + return dist_array_center + + def calculate_image_back(self, coordinates): + # Back + reconstruct_bit_mask_back = lidar_filter_utility.bounding_box( + coordinates, + max_x=0.0, + min_x=-np.inf, + min_z=-1.6, + ) + reconstruct_coordinates_back = coordinates[reconstruct_bit_mask_back] + reconstruct_coordinates_xyz_back = np.array( + lidar_filter_utility.remove_field_name( + reconstruct_coordinates_back, "intensity" + ).tolist() + ) + dist_array_back = self.reconstruct_img_from_lidar( + reconstruct_coordinates_xyz_back, focus="Back" + ) + return dist_array_back + + def calculate_image_left(self, coordinates): + # Left + reconstruct_bit_mask_left = lidar_filter_utility.bounding_box( + coordinates, + max_y=np.inf, + min_y=0.0, + min_z=-1.6, + ) + reconstruct_coordinates_left = coordinates[reconstruct_bit_mask_left] + reconstruct_coordinates_xyz_left = np.array( + lidar_filter_utility.remove_field_name( + reconstruct_coordinates_left, "intensity" + ).tolist() + ) + dist_array_left = self.reconstruct_img_from_lidar( + reconstruct_coordinates_xyz_left, focus="Left" + ) + return dist_array_left + + def calculate_image_right(self, coordinates): + # Right + reconstruct_bit_mask_right = lidar_filter_utility.bounding_box( + coordinates, max_y=-0.0, min_y=-np.inf, min_z=-1.6 + ) + reconstruct_coordinates_right = coordinates[reconstruct_bit_mask_right] + reconstruct_coordinates_xyz_right = np.array( + lidar_filter_utility.remove_field_name( + reconstruct_coordinates_right, "intensity" + ).tolist() + ) + dist_array_right = self.reconstruct_img_from_lidar( + reconstruct_coordinates_xyz_right, focus="Right" + ) + return dist_array_right + + def publish_images(self, processed_images, data_header): + for direction, image_array in processed_images.items(): + if not isinstance(image_array, np.ndarray): + continue + dist_array_msg = self.bridge.cv2_to_imgmsg( + image_array, encoding="passthrough" + ) + dist_array_msg.header = data_header + + if direction == "Center": + self.dist_array_center_publisher.publish(dist_array_msg) + if direction == "Back": + self.dist_array_back_publisher.publish(dist_array_msg) + if direction == "Left": + self.dist_array_left_publisher.publish(dist_array_msg) + if direction == "Right": + self.dist_array_right_publisher.publish(dist_array_msg) + + def reconstruct_img_from_lidar(self, coordinates_xyz, focus): + """ + reconstruct 3d LIDAR-Data and calculate 2D Pixel + according to Camera-World + + Args: + coordinates_xyz (np.array): filtered lidar points + focus (String): Camera Angle + + Returns: + image: depth image for camera angle + """ + + # intrinsic matrix for camera: + # width -> 300, height -> 200, fov -> 100 (agent.py) + im = np.identity(3) + im[0, 2] = 1280 / 2.0 + im[1, 2] = 720 / 2.0 + im[0, 0] = im[1, 1] = 1280 / (2.0 * np.tan(100 * np.pi / 360.0)) + + # extrinsic matrix for camera + ex = np.zeros(shape=(3, 4)) + ex[0][0] = 1 + ex[1][1] = 1 + ex[2][2] = 1 + m = np.matmul(im, ex) + + # reconstruct camera image with LIDAR-Data + img = np.zeros(shape=(720, 1280), dtype=np.float32) + dist_array = np.zeros(shape=(720, 1280, 3), dtype=np.float32) + for c in coordinates_xyz: + # center depth image + if focus == "Center": + point = np.array([c[1], c[2], c[0], 1]) + pixel = np.matmul(m, point) + x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) + if x >= 0 and x <= 1280 and y >= 0 and y <= 720: + img[719 - y][1279 - x] = c[0] + dist_array[719 - y][1279 - x] = np.array( + [c[0], c[1], c[2]], dtype=np.float32 + ) + + # back depth image + if focus == "Back": + point = np.array([c[1], c[2], c[0], 1]) + pixel = np.matmul(m, point) + x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) + if x >= 0 and x <= 1280 and y >= 0 and y < 720: + img[y][1279 - x] = -c[0] + dist_array[y][1279 - x] = np.array( + [-c[0], c[1], c[2]], dtype=np.float32 + ) + + # left depth image + if focus == "Left": + point = np.array([c[0], c[2], c[1], 1]) + pixel = np.matmul(m, point) + x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) + if x >= 0 and x <= 1280 and y >= 0 and y <= 720: + img[719 - y][1279 - x] = c[1] + dist_array[y][1279 - x] = np.array( + [c[0], c[1], c[2]], dtype=np.float32 + ) + + # right depth image + if focus == "Right": + point = np.array([c[0], c[2], c[1], 1]) + pixel = np.matmul(m, point) + x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) + if x >= 0 and x < 1280 and y >= 0 and y < 720: + img[y][1279 - x] = -c[1] + dist_array[y][1279 - x] = np.array( + [c[0], c[1], c[2]], dtype=np.float32 + ) + + return dist_array + + +def array_to_pointcloud2(points, header="hero/Lidar"): + points_array = np.array(points) + + points_structured = np.array( + [(p[0], p[1], p[2]) for p in points_array], + dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")], + ) + + pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2(points_structured) + + pointcloud_msg.header.stamp = rospy.Time.now() + pointcloud_msg.header = header + + return pointcloud_msg + + +def get_largest_cluster(clustered_points, return_structured=True): + """ + Bestimmt das größte Cluster aus den gegebenen Punkten und gibt es zurück. + + :param clustered_points: Dictionary mit Cluster-IDs als Schlüssel und Punktwolken als Werte. + :param return_structured: Gibt ein strukturiertes Array zurück, falls True. + :return: Größtes Cluster als Array (entweder raw oder strukturiert). + """ + if not clustered_points: + rospy.logerr( + "Clustered points are empty. Cannot determine the largest cluster." + ) + return np.array([]) + + # Finde das größte Cluster direkt + largest_cluster_id, largest_cluster = max( + clustered_points.items(), key=lambda item: len(item[1]) + ) + + if largest_cluster.size == 0: + rospy.logerr(f"Largest cluster (ID {largest_cluster_id}) is empty.") + return np.array([]) + + rospy.loginfo( + f"Largest cluster: {largest_cluster_id} with {largest_cluster.shape[0]} points" + ) + + # Falls kein strukturiertes Array benötigt wird, direkt zurückgeben + if not return_structured: + return largest_cluster + + # Andernfalls Punkte in ein strukturiertes Array konvertieren + points_structured = np.empty( + largest_cluster.shape[0], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")] + ) + points_structured["x"] = largest_cluster[:, 0] + points_structured["y"] = largest_cluster[:, 1] + points_structured["z"] = largest_cluster[:, 2] + + return points_structured + + +def combine_clusters(clustered_points): + """ + Kombiniert Cluster-Daten in ein strukturiertes Array. + + :param clustered_points: Dictionary mit Cluster-IDs als Schlüssel und 3D-Punktwolken als Werten. + :return: Kombiniertes strukturiertes NumPy-Array mit Feldern "x", "y", "z", "cluster_id". + """ + + # Vorab die Gesamtanzahl der Punkte berechnen + total_points = sum(points.shape[0] for points in clustered_points.values()) + + # Erstelle ein leeres strukturiertes Array + combined_points = np.empty( + total_points, + dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"), ("cluster_id", "f4")], + ) + + # Fülle das Array direkt + index = 0 + for cluster_id, points in clustered_points.items(): + num_points = points.shape[0] + combined_points["x"][index : index + num_points] = points[:, 0] + combined_points["y"][index : index + num_points] = points[:, 1] + combined_points["z"][index : index + num_points] = points[:, 2] + combined_points["cluster_id"][index : index + num_points] = cluster_id + index += num_points + + return combined_points + + +def fuse_clusters(cluster_data_list): + """ + Fusioniert eine Liste von Cluster-Daten und entfernt redundante Punkte basierend auf (x, y, z). + + :param cluster_data_list: Liste von NumPy-Arrays mit Feldern (x, y, z, intensity) + :return: Fusioniertes NumPy-Array mit einzigartigen Punkten + """ + # Kombiniere alle Arrays in ein großes Array + concatenated_points = np.concatenate(cluster_data_list, axis=0) + + # Erstelle eine flache Ansicht für die Felder (x, y, z) + unique_xyz, indices = np.unique( + concatenated_points[["x", "y", "z"]].view(np.float32).reshape(-1, 3), + axis=0, + return_index=True, + ) + + # Behalte die entsprechenden `intensity`-Werte basierend auf den eindeutigen Indizes + unique_points = concatenated_points[indices] + + return unique_points + + +def cluster_lidar_data_from_pointcloud(coordinates, eps=0.1, min_samples=10): + """ + Cluster LiDAR-Daten effizient mit DBSCAN. + """ + # Erstelle Matrix direkt mit column_stack (schneller als vstack) + xyz = np.column_stack((coordinates["x"], coordinates["y"], coordinates["z"])) + + # DBSCAN-Cluster-Berechnung + clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(xyz) + labels = clustering.labels_ + + # Nur eindeutige Cluster (Rauschen entfernen) + unique_labels = np.unique(labels) + valid_labels = unique_labels[unique_labels != -1] + + # Parallelisiertes Extrahieren der Cluster + clusters = Parallel(n_jobs=-1)( + delayed(lambda l: (l, xyz[labels == l]))(label) for label in valid_labels + ) + clusters = dict(clusters) + + return clusters + + +if __name__ == "__main__": + lidar_distance = LidarDistance() + lidar_distance.listener() From 2aae9be231e3cde0e545ea4b1adf733c942598c9 Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 14:49:52 +0100 Subject: [PATCH 74/85] Deleted file duplicate. Refactored the existing node code by modularizing it into functions for better readability and maintainability. --- code/perception/src/lidar_distance_neu.py | 516 ---------------------- 1 file changed, 516 deletions(-) delete mode 100755 code/perception/src/lidar_distance_neu.py diff --git a/code/perception/src/lidar_distance_neu.py b/code/perception/src/lidar_distance_neu.py deleted file mode 100755 index 57892ed6..00000000 --- a/code/perception/src/lidar_distance_neu.py +++ /dev/null @@ -1,516 +0,0 @@ -#!/usr/bin/env python -import rospy -import ros_numpy -import numpy as np -import lidar_filter_utility -from sensor_msgs.msg import PointCloud2, Image as ImageMsg -from sklearn.cluster import DBSCAN -from cv_bridge import CvBridge -from joblib import Parallel, delayed -import queue -import threading - -# from mpl_toolkits.mplot3d import Axes3D -# from itertools import combinations -# from matplotlib.colors import LinearSegmentedColormap - - -class LidarDistance: - """See doc/perception/lidar_distance_utility.md on - how to configute this node - """ - - # Klassenattribute - cluster_queue = queue.Queue() - image_queue = queue.Queue() - workers_initialized = False - cluster_data_list = [] - - def callback(self, data): - """Callback function, filters a PontCloud2 message - by restrictions defined in the launchfile. - - Publishes a Depth image for the specified camera angle. - Each angle has do be delt with differently since the signs of the - coordinate system change with the view angle. - - :param data: a PointCloud2 - """ - - if not LidarDistance.workers_initialized: - LidarDistance.workers_initialized = True - self.start_image_worker() - self.start_cluster_worker() - - if not self.cluster_thread.is_alive: - rospy.logwarn("Cluster-Worker abgestürzt. Neustart...") - self.start_cluster_worker() - - if not self.image_thread.is_alive: - rospy.logwarn("Image-Worker abgestürzt. Neustart...") - self.start_image_worker() - - LidarDistance.cluster_queue.put(data) - if LidarDistance.cluster_queue.qsize() > 10: - rospy.logwarn( - "Cluster-Worker kommt nicht hinterher. Queue size:" - + str(LidarDistance.cluster_queue.qsize()), - ) - # Dasselbe Koordinatenset für die Bildberechnung in die Bild-Warteschlange legen - LidarDistance.image_queue.put(data) - if LidarDistance.image_queue.qsize() > 10: - rospy.logwarn( - f"Image-Worker ({self.image_thread.is_alive}) kommt nicht hinterher. Queue size: {str(LidarDistance.image_queue.qsize())}" - ) - - def listener(self): - """ - Initializes the node and it's publishers - """ - # run simultaneously. - rospy.init_node("lidar_distance") - self.bridge = CvBridge() - - self.pub_pointcloud = rospy.Publisher( - rospy.get_param( - "~point_cloud_topic", - "/carla/hero/" + rospy.get_namespace() + "_filtered", - ), - PointCloud2, - queue_size=10, - ) - - # publisher for dist_array - self.dist_array_center_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), - ImageMsg, - queue_size=10, - ) - - # publisher for dist_array - self.dist_array_back_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Back/dist_array"), - ImageMsg, - queue_size=10, - ) - - self.dist_array_lidar_publisher = rospy.Publisher( - rospy.get_param( - "~image_distance_topic_cluster", "/paf/hero/dist_clustered" - ), - PointCloud2, - queue_size=10, - ) - rospy.loginfo("dist_array_lidar_publisher erfolgreich erstellt.") - - # publisher for dist_array - self.dist_array_left_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Left/dist_array"), - ImageMsg, - queue_size=10, - ) - - # publisher for dist_array - self.dist_array_right_publisher = rospy.Publisher( - rospy.get_param("~image_distance_topic", "/paf/hero/Right/dist_array"), - ImageMsg, - queue_size=10, - ) - - rospy.Subscriber( - rospy.get_param("~source_topic", "/carla/hero/LIDAR"), - PointCloud2, - self.callback, - ) - - rospy.loginfo("Lidar Processor Node gestartet.") - rospy.spin() - - def cluster_worker(self): - """ - Worker für das Clustern von Punkten. - """ - while True: - try: - # Neueste Aufgabe holen - data = LidarDistance.cluster_queue.get(timeout=1) - - # Restliche Aufgaben aus der Queue entfernen - discarded_tasks = 0 - while not LidarDistance.cluster_queue.empty(): - LidarDistance.cluster_queue.get() - discarded_tasks += 1 - - # Anzahl verworfener Einträge loggen - if discarded_tasks > 0: - rospy.logwarn(f"{discarded_tasks} Einträge wurden verworfen.") - - # Stop-Signal überprüfen - if data is None: # Stop-Signal - break - - # Punktwolken-Daten verarbeiten - coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - filtered_coordinates = coordinates[(coordinates["x"] >= 2)] - clustered_points = cluster_lidar_data_from_pointcloud( - coordinates=filtered_coordinates - ) - - # Kombinierte Cluster erstellen - cluster_structured = combine_clusters(clustered_points) - - # Konvertiere zu PointCloud2-Nachricht - pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2( - cluster_structured - ) - pointcloud_msg.header = data.header - pointcloud_msg.header.stamp = rospy.Time.now() - - # Cluster veröffentlichen - self.dist_array_lidar_publisher.publish(pointcloud_msg) - - except queue.Empty: - rospy.loginfo("Cluster-Queue ist leer. Warte auf neue Aufgaben.") - continue # Zurück zur Queue-Warte - - except Exception as e: - rospy.logerr(f"Fehler im Cluster-Worker: {e}") - - def image_worker(self): - """ - Worker für die Berechnung von Bildern. - """ - while True: - data = LidarDistance.image_queue.get() - if data is None: # Stop-Signal - break - - coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - # Bildverarbeitung auf den Koordinaten durchführen - processed_images = { - "Center": None, - "Back": None, - "Left": None, - "Right": None, - } - processed_images["Center"] = self.calculate_image_center(coordinates) - processed_images["Back"] = self.calculate_image_back(coordinates) - processed_images["Left"] = self.calculate_image_left(coordinates) - processed_images["Right"] = self.calculate_image_right(coordinates) - - self.publish_images(processed_images, data.header) - - def start_cluster_worker(self): - self.cluster_thread = threading.Thread(target=self.cluster_worker, daemon=True) - self.cluster_thread.start() - - def start_image_worker(self): - self.image_thread = threading.Thread(target=self.image_worker, daemon=True) - self.image_thread.start() - - def calculate_image_center(self, coordinates): - reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( - coordinates, - max_x=np.inf, - min_x=0.0, - min_z=-1.6, - ) - reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] - reconstruct_coordinates_xyz_center = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_center, "intensity" - ).tolist() - ) - dist_array_center = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_center, focus="Center" - ) - return dist_array_center - - def calculate_image_back(self, coordinates): - # Back - reconstruct_bit_mask_back = lidar_filter_utility.bounding_box( - coordinates, - max_x=0.0, - min_x=-np.inf, - min_z=-1.6, - ) - reconstruct_coordinates_back = coordinates[reconstruct_bit_mask_back] - reconstruct_coordinates_xyz_back = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_back, "intensity" - ).tolist() - ) - dist_array_back = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_back, focus="Back" - ) - return dist_array_back - - def calculate_image_left(self, coordinates): - # Left - reconstruct_bit_mask_left = lidar_filter_utility.bounding_box( - coordinates, - max_y=np.inf, - min_y=0.0, - min_z=-1.6, - ) - reconstruct_coordinates_left = coordinates[reconstruct_bit_mask_left] - reconstruct_coordinates_xyz_left = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_left, "intensity" - ).tolist() - ) - dist_array_left = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_left, focus="Left" - ) - return dist_array_left - - def calculate_image_right(self, coordinates): - # Right - reconstruct_bit_mask_right = lidar_filter_utility.bounding_box( - coordinates, max_y=-0.0, min_y=-np.inf, min_z=-1.6 - ) - reconstruct_coordinates_right = coordinates[reconstruct_bit_mask_right] - reconstruct_coordinates_xyz_right = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_right, "intensity" - ).tolist() - ) - dist_array_right = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_right, focus="Right" - ) - return dist_array_right - - def publish_images(self, processed_images, data_header): - for direction, image_array in processed_images.items(): - if not isinstance(image_array, np.ndarray): - continue - dist_array_msg = self.bridge.cv2_to_imgmsg( - image_array, encoding="passthrough" - ) - dist_array_msg.header = data_header - - if direction == "Center": - self.dist_array_center_publisher.publish(dist_array_msg) - if direction == "Back": - self.dist_array_back_publisher.publish(dist_array_msg) - if direction == "Left": - self.dist_array_left_publisher.publish(dist_array_msg) - if direction == "Right": - self.dist_array_right_publisher.publish(dist_array_msg) - - def reconstruct_img_from_lidar(self, coordinates_xyz, focus): - """ - reconstruct 3d LIDAR-Data and calculate 2D Pixel - according to Camera-World - - Args: - coordinates_xyz (np.array): filtered lidar points - focus (String): Camera Angle - - Returns: - image: depth image for camera angle - """ - - # intrinsic matrix for camera: - # width -> 300, height -> 200, fov -> 100 (agent.py) - im = np.identity(3) - im[0, 2] = 1280 / 2.0 - im[1, 2] = 720 / 2.0 - im[0, 0] = im[1, 1] = 1280 / (2.0 * np.tan(100 * np.pi / 360.0)) - - # extrinsic matrix for camera - ex = np.zeros(shape=(3, 4)) - ex[0][0] = 1 - ex[1][1] = 1 - ex[2][2] = 1 - m = np.matmul(im, ex) - - # reconstruct camera image with LIDAR-Data - img = np.zeros(shape=(720, 1280), dtype=np.float32) - dist_array = np.zeros(shape=(720, 1280, 3), dtype=np.float32) - for c in coordinates_xyz: - # center depth image - if focus == "Center": - point = np.array([c[1], c[2], c[0], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x <= 1280 and y >= 0 and y <= 720: - img[719 - y][1279 - x] = c[0] - dist_array[719 - y][1279 - x] = np.array( - [c[0], c[1], c[2]], dtype=np.float32 - ) - - # back depth image - if focus == "Back": - point = np.array([c[1], c[2], c[0], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x <= 1280 and y >= 0 and y < 720: - img[y][1279 - x] = -c[0] - dist_array[y][1279 - x] = np.array( - [-c[0], c[1], c[2]], dtype=np.float32 - ) - - # left depth image - if focus == "Left": - point = np.array([c[0], c[2], c[1], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x <= 1280 and y >= 0 and y <= 720: - img[719 - y][1279 - x] = c[1] - dist_array[y][1279 - x] = np.array( - [c[0], c[1], c[2]], dtype=np.float32 - ) - - # right depth image - if focus == "Right": - point = np.array([c[0], c[2], c[1], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x < 1280 and y >= 0 and y < 720: - img[y][1279 - x] = -c[1] - dist_array[y][1279 - x] = np.array( - [c[0], c[1], c[2]], dtype=np.float32 - ) - - return dist_array - - -def array_to_pointcloud2(points, header="hero/Lidar"): - points_array = np.array(points) - - points_structured = np.array( - [(p[0], p[1], p[2]) for p in points_array], - dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")], - ) - - pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2(points_structured) - - pointcloud_msg.header.stamp = rospy.Time.now() - pointcloud_msg.header = header - - return pointcloud_msg - - -def get_largest_cluster(clustered_points, return_structured=True): - """ - Bestimmt das größte Cluster aus den gegebenen Punkten und gibt es zurück. - - :param clustered_points: Dictionary mit Cluster-IDs als Schlüssel und Punktwolken als Werte. - :param return_structured: Gibt ein strukturiertes Array zurück, falls True. - :return: Größtes Cluster als Array (entweder raw oder strukturiert). - """ - if not clustered_points: - rospy.logerr( - "Clustered points are empty. Cannot determine the largest cluster." - ) - return np.array([]) - - # Finde das größte Cluster direkt - largest_cluster_id, largest_cluster = max( - clustered_points.items(), key=lambda item: len(item[1]) - ) - - if largest_cluster.size == 0: - rospy.logerr(f"Largest cluster (ID {largest_cluster_id}) is empty.") - return np.array([]) - - rospy.loginfo( - f"Largest cluster: {largest_cluster_id} with {largest_cluster.shape[0]} points" - ) - - # Falls kein strukturiertes Array benötigt wird, direkt zurückgeben - if not return_structured: - return largest_cluster - - # Andernfalls Punkte in ein strukturiertes Array konvertieren - points_structured = np.empty( - largest_cluster.shape[0], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")] - ) - points_structured["x"] = largest_cluster[:, 0] - points_structured["y"] = largest_cluster[:, 1] - points_structured["z"] = largest_cluster[:, 2] - - return points_structured - - -def combine_clusters(clustered_points): - """ - Kombiniert Cluster-Daten in ein strukturiertes Array. - - :param clustered_points: Dictionary mit Cluster-IDs als Schlüssel und 3D-Punktwolken als Werten. - :return: Kombiniertes strukturiertes NumPy-Array mit Feldern "x", "y", "z", "cluster_id". - """ - - # Vorab die Gesamtanzahl der Punkte berechnen - total_points = sum(points.shape[0] for points in clustered_points.values()) - - # Erstelle ein leeres strukturiertes Array - combined_points = np.empty( - total_points, - dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"), ("cluster_id", "f4")], - ) - - # Fülle das Array direkt - index = 0 - for cluster_id, points in clustered_points.items(): - num_points = points.shape[0] - combined_points["x"][index : index + num_points] = points[:, 0] - combined_points["y"][index : index + num_points] = points[:, 1] - combined_points["z"][index : index + num_points] = points[:, 2] - combined_points["cluster_id"][index : index + num_points] = cluster_id - index += num_points - - return combined_points - - -def fuse_clusters(cluster_data_list): - """ - Fusioniert eine Liste von Cluster-Daten und entfernt redundante Punkte basierend auf (x, y, z). - - :param cluster_data_list: Liste von NumPy-Arrays mit Feldern (x, y, z, intensity) - :return: Fusioniertes NumPy-Array mit einzigartigen Punkten - """ - # Kombiniere alle Arrays in ein großes Array - concatenated_points = np.concatenate(cluster_data_list, axis=0) - - # Erstelle eine flache Ansicht für die Felder (x, y, z) - unique_xyz, indices = np.unique( - concatenated_points[["x", "y", "z"]].view(np.float32).reshape(-1, 3), - axis=0, - return_index=True, - ) - - # Behalte die entsprechenden `intensity`-Werte basierend auf den eindeutigen Indizes - unique_points = concatenated_points[indices] - - return unique_points - - -def cluster_lidar_data_from_pointcloud(coordinates, eps=0.1, min_samples=10): - """ - Cluster LiDAR-Daten effizient mit DBSCAN. - """ - # Erstelle Matrix direkt mit column_stack (schneller als vstack) - xyz = np.column_stack((coordinates["x"], coordinates["y"], coordinates["z"])) - - # DBSCAN-Cluster-Berechnung - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(xyz) - labels = clustering.labels_ - - # Nur eindeutige Cluster (Rauschen entfernen) - unique_labels = np.unique(labels) - valid_labels = unique_labels[unique_labels != -1] - - # Parallelisiertes Extrahieren der Cluster - clusters = Parallel(n_jobs=-1)( - delayed(lambda l: (l, xyz[labels == l]))(label) for label in valid_labels - ) - clusters = dict(clusters) - - return clusters - - -if __name__ == "__main__": - lidar_distance = LidarDistance() - lidar_distance.listener() From 279944884dd72fe2a21180768d402da77bdce794 Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 11 Dec 2024 15:12:52 +0100 Subject: [PATCH 75/85] added code documentation --- code/perception/src/radar_node.py | 315 +++++++++++++++++------------- 1 file changed, 174 insertions(+), 141 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index ddff6511..975af2b1 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -27,34 +27,29 @@ def callback(self, data): Args: data: Point2Cloud message containing radar data """ - # clustered_points = cluster_radar_data_from_pointcloud(data, 10) - # clustered_points_json = json.dumps(clustered_points) - # self.dist_array_radar_publisher.publish(clustered_points_json) - # output array [x, y, z, distance] dataarray = pointcloud2_to_array(data) - # input array [x, y, z, distance], max_distance, output: filtered data - # dataarray = filter_data(dataarray, 10) + # radar position z=0.7 + dataarray = filter_data(dataarray, min_z=-0.6) - # input array [x, y, z, distance], output: dict clustered clustered_data = cluster_data(dataarray) # transformed_data = transform_data_to_2d(dataarray) - # input array [x, y, z, distance], clustered labels cloud = create_pointcloud2(dataarray, clustered_data.labels_) self.visualization_radar_publisher.publish(cloud) - points_with_labels = np.hstack((dataarray, clustered_data.labels_.reshape(-1, 1))) + points_with_labels = np.hstack((dataarray, + clustered_data.labels_.reshape(-1, 1))) bounding_boxes = generate_bounding_boxes(points_with_labels) marker_array = MarkerArray() - # marker_array = clear_old_markers(marker_array) for label, bbox in bounding_boxes: if label != -1: marker = create_bounding_box_marker(label, bbox) marker_array.markers.append(marker) + # can be used for extra debugging # min_marker, max_marker = create_min_max_markers(label, bbox) # marker_array.markers.append(min_marker) # marker_array.markers.append(max_marker) @@ -63,7 +58,8 @@ def callback(self, data): self.marker_visualization_radar_publisher.publish(marker_array) - cluster_info = generate_cluster_labels_and_colors(clustered_data, dataarray, marker_array, bounding_boxes) + cluster_info = generate_cluster_info(clustered_data, dataarray, marker_array, + bounding_boxes) self.cluster_info_radar_publisher.publish(cluster_info) def listener(self): @@ -117,93 +113,73 @@ def pointcloud2_to_array(pointcloud_msg): Returns: - np.ndarray A 2D array where each row corresponds to a point in the point cloud: - [x, y, z, distance], where "distance" is the distance from the origin. + [x, y, z, Velocity] """ cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg) - # distances = np.sqrt( - # cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2 - # ) - # return np.column_stack( - # (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances) - # ) return np.column_stack( (cloud_array["x"], cloud_array["y"], cloud_array["z"], cloud_array["Velocity"]) ) -def cluster_radar_data_from_pointcloud( - pointcloud_msg, max_distance, eps=1.0, min_samples=2 -): +def filter_data(data, min_x=-100, max_x=100, min_y=-100, max_y=100, min_z=-1, max_z=100, + max_distance=100): """ - Filters and clusters points from a ROS PointCloud2 message based on DBSCAN - clustering. + Filters radar data based on specified spatial and distance constraints. - Parameters: - - pointcloud_msg: sensor_msgs/PointCloud2 - The ROS PointCloud2 message containing the 3D points. - - max_distance: float - Maximum distance to consider points. Points beyond this distance are - discarded. - - eps: float, optional (default: 1.0) - The maximum distance between two points for them to be considered in - the same cluster. - - min_samples: int, optional (default: 2) - The minimum number of points required to form a cluster. + This function applies multiple filtering criteria to the input radar data. + Points outside these bounds are excluded from the output. + + Args: + data (np.ndarray): A 2D numpy array containing radar data, where each row + represents a data point with the format [x, y, z, distance]. The array + shape is (N, 4), where N is the number of points. + min_x (float, optional): Minimum value for the x-coordinate. Default is -1. + max_x (float, optional): Maximum value for the x-coordinate. Default is 1. + min_y (float, optional): Minimum value for the y-coordinate. Default is 1. + max_y (float, optional): Maximum value for the y-coordinate. Default is 1. + min_z (float, optional): Minimum value for the z-coordinate. Default is -0.7. + max_z (float, optional): Maximum value for the z-coordinate. Default is 1.3. + max_distance (float, optional): Maximum allowable distance of the point from + the sensor. Default is 100. Returns: - - dict - A dictionary where the keys are cluster labels (int) and the values - are the number of points in each cluster. Returns an empty dictionary - if no points are available. + np.ndarray: A numpy array containing only the filtered data points that meet + the specified criteria. """ - data = pointcloud2_to_array(pointcloud_msg) + filtered_data = data[data[:, 3] < max_distance] filtered_data = filtered_data[ - (filtered_data[:, 1] >= -1) - & (filtered_data[:, 1] <= 1) - & (filtered_data[:, 2] <= 1.3) - & (filtered_data[:, 2] >= -0.7) + (filtered_data[:, 0] >= min_x) + & (filtered_data[:, 0] <= max_x) + & (filtered_data[:, 1] >= min_y) + & (filtered_data[:, 1] <= max_y) + & (filtered_data[:, 2] <= max_z) + & (filtered_data[:, 2] >= min_z) ] - if len(filtered_data) == 0: - return {} - coordinates = filtered_data[:, :2] - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) - labels = clustering.labels_ - clustered_points = {label: list(labels).count(label) for label in set(labels)} - clustered_points = {int(label): count for label, count in clustered_points.items()} - return clustered_points - + return filtered_data -# filters radar data in distance, y, z direction -def filter_data(data, max_distance): - # filtered_data = data[data[:, 3] < max_distance] - filtered_data = data - filtered_data = filtered_data[ - # (filtered_data[:, 1] >= -1) - # & (filtered_data[:, 1] <= 1) - # & (filtered_data[:, 2] <= 1.3) - (filtered_data[:, 2] <= 1.3) - & (filtered_data[:, 2] >= -0.6) # -0.7 - ] - return filtered_data +def cluster_data(data, eps=0.8, min_samples=3): + """_summary_ + Args: + data (np.ndarray): data array which should be clustered + eps (float, optional): maximum distance of points. Defaults to 0.8. + min_samples (int, optional): min samples for 1 cluster. Defaults to 3. -# clusters data with DBSCAN -def cluster_data(filtered_data, eps=0.8, min_samples=5): + Returns: + dict: A dictionary where the keys are cluster labels (int) and the values + are the number of points in each cluster. Returns an empty dictionary + if no points are available. + """ - if len(filtered_data) == 0: + if len(data) == 0: return {} - # coordinates = filtered_data[:, :2] - # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates) - - # worse than without scaling scaler = StandardScaler() - data_scaled = scaler.fit_transform(filtered_data) - clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(data_scaled) + data_scaled = scaler.fit_transform(data) + clustered_points = DBSCAN(eps=eps, min_samples=min_samples).fit(data_scaled) - # clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(filtered_data) - return clustering + return clustered_points # generates random color for cluster @@ -213,8 +189,16 @@ def generate_color_map(num_clusters): return colors -# creates pointcloud2 for publishing clustered radar data def create_pointcloud2(clustered_points, cluster_labels): + """_summary_ + + Args: + clustered_points (dict): clustered points after dbscan + cluster_labels (_type_): _description_ + + Returns: + PointCloud2: pointcloud which can be published + """ header = Header() header.stamp = rospy.Time.now() header.frame_id = "hero/RADAR" @@ -224,7 +208,6 @@ def create_pointcloud2(clustered_points, cluster_labels): colors = generate_color_map(len(unique_labels)) for i, point in enumerate(clustered_points): - # x, y, z, _ = point x, y, z, v = point label = cluster_labels[i] @@ -247,6 +230,14 @@ def create_pointcloud2(clustered_points, cluster_labels): def transform_data_to_2d(clustered_data): + """_summary_ + + Args: + clustered_data (np.ndarray): clustered 3d data points + + Returns: + _np.ndarray: clustered points, every z value is set to 0 + """ transformed_points = clustered_data transformed_points[:, 0] = clustered_data[:, 0] @@ -258,13 +249,23 @@ def transform_data_to_2d(clustered_data): def calculate_aabb(cluster_points): - """_summary_ + """ + Calculates the axis-aligned bounding box (AABB) for a set of 3D points. + + This function computes the minimum and maximum values along each axis (x, y, z) + for a given set of 3D points, which defines the bounding box that contains + all points in the cluster. Args: - cluster_points (_type_): _description_ + cluster_points (numpy.ndarray): + A 2D array where each row represents a 3D point (x, y, z). + The array should have shape (N, 3) where N is the number of points. Returns: - _type_: _description_ + tuple: A tuple of the form (x_min, x_max, y_min, y_max, z_min, z_max), + which represents the axis-aligned bounding box (AABB) for the given + set of points. The values are the minimum and maximum coordinates + along the x, y, and z axes. """ # for 2d (top-down) boxes @@ -272,7 +273,7 @@ def calculate_aabb(cluster_points): # x_max = np.max(cluster_points[:, 0]) # y_min = np.min(cluster_points[:, 1]) # y_max = np.max(cluster_points[:, 1]) - + # rospy.loginfo(f"Bounding box: X({x_min}, {x_max}), Y({y_min}, {y_max})") # return x_min, x_max, y_min, y_max # for 3d boxes @@ -282,18 +283,27 @@ def calculate_aabb(cluster_points): y_max = np.max(cluster_points[:, 1]) z_min = np.min(cluster_points[:, 2]) z_max = np.max(cluster_points[:, 2]) - rospy.loginfo(f"Bounding box for label: X({x_min}, {x_max}), Y({y_min}, {y_max}), Z({z_min}, {z_max})") return x_min, x_max, y_min, y_max, z_min, z_max def generate_bounding_boxes(points_with_labels): - """_summary_ + """ + Generates bounding boxes for clustered points. + + This function processes a set of points, each associated with a cluster label, + and generates an axis-aligned bounding box (AABB) for each unique cluster label. Args: - points_with_labels (_type_): _description_ + points_with_labels (numpy.ndarray): + A 2D array of shape (N, 4) where each row contains + the coordinates (x, y, z) of a point along with its + corresponding cluster label in the last column. + The array should have the structure [x, y, z, label]. Returns: - _type_: _description_ + list: A list of tuples, where each tuple contains a cluster label and the + corresponding bounding box (bbox). The bbox is represented by a tuple + of the form (x_min, x_max, y_min, y_max, z_min, z_max). """ bounding_boxes = [] unique_labels = np.unique(points_with_labels[:, -1]) @@ -307,10 +317,23 @@ def generate_bounding_boxes(points_with_labels): def create_bounding_box_marker(label, bbox): - """_summary_ + """ + Creates an RViz Marker for visualizing a 3D bounding box. + + This function generates a Marker object for RViz to visualize a 3D bounding box + based on the provided label and bounding box dimensions. The marker is + represented as a series of lines connecting the corners of the box. + + Args: + label (int): The unique identifier for the cluster or object to which the + bounding box belongs. This label is used as the Marker ID. + bbox (tuple): A tuple containing the min and max coordinates of the bounding box + in the format (x_min, x_max, y_min, y_max, z_min, z_max). Returns: - _type_: _description_ + Marker: A Marker object that can be published to RViz to display the + 3D bounding box. The marker is of type LINE_LIST, + representing the edges of the bounding box. """ # for 2d (top-down) boxes # x_min, x_max, y_min, y_max = bbox @@ -321,8 +344,8 @@ def create_bounding_box_marker(label, bbox): marker = Marker() marker.header.frame_id = "hero/RADAR" marker.id = int(label) - # marker.type = Marker.LINE_STRIP - marker.type = Marker.LINE_LIST + # marker.type = Marker.LINE_STRIP # 2d boxes + marker.type = Marker.LINE_LIST # 3d boxes marker.action = Marker.ADD marker.scale.x = 0.1 marker.color.r = 1.0 @@ -342,32 +365,20 @@ def create_bounding_box_marker(label, bbox): # for 3d boxes points = [ - Point(x_min, y_min, z_min), # Ecke 0 - Point(x_max, y_min, z_min), # Ecke 1 - Point(x_max, y_max, z_min), # Ecke 2 - Point(x_min, y_max, z_min), # Ecke 3 - Point(x_min, y_min, z_max), # Ecke 4 - Point(x_max, y_min, z_max), # Ecke 5 - Point(x_max, y_max, z_max), # Ecke 6 - Point(x_min, y_max, z_max), # Ecke 7 - - # Point(x_min, y_min, z_min), # Verbinde z_min zu z_max - # Point(x_min, y_min, z_max), - - # Point(x_max, y_min, z_min), - # Point(x_max, y_min, z_max), - - # Point(x_max, y_max, z_min), - # Point(x_max, y_max, z_max), - - # Point(x_min, y_max, z_min), - # Point(x_min, y_max, z_max), + Point(x_min, y_min, z_min), + Point(x_max, y_min, z_min), + Point(x_max, y_max, z_min), + Point(x_min, y_max, z_min), + Point(x_min, y_min, z_max), + Point(x_max, y_min, z_max), + Point(x_max, y_max, z_max), + Point(x_min, y_max, z_max), ] - # marker.points = points + lines = [ - (0, 1), (1, 2), (2, 3), (3, 0), # Boden - (4, 5), (5, 6), (6, 7), (7, 4), # Deckel - (0, 4), (1, 5), (2, 6), (3, 7), # Vertikale Kanten + (0, 1), (1, 2), (2, 3), (3, 0), # Bottom + (4, 5), (5, 6), (6, 7), (7, 4), # Top + (0, 4), (1, 5), (2, 6), (3, 7), # Vertical Edges ] for start, end in lines: marker.points.append(points[start]) @@ -376,41 +387,33 @@ def create_bounding_box_marker(label, bbox): return marker -def create_min_max_markers(label, bbox, frame_id="hero/RADAR", min_color=(0.0, 1.0, 0.0, 1.0), max_color=(1.0, 0.0, 0.0, 1.0)): +# can be used for extra debugging +def create_min_max_markers(label, bbox, frame_id="hero/RADAR", + min_color=(0.0, 1.0, 0.0, 1.0), + max_color=(1.0, 0.0, 0.0, 1.0)): """ - Erstellt RViz-Marker für die Min- und Max-Punkte einer Bounding Box. + creates RViz-Markers for min- and max-points of a bounding box. Args: - label (int): Die ID des Clusters (wird als Marker-ID genutzt). - bbox (tuple): Min- und Max-Werte der Bounding Box (x_min, x_max, y_min, y_max, z_min, z_max). - frame_id (str): Frame ID, in dem die Marker gezeichnet werden. - min_color (tuple): RGBA-Farbwerte für den Min-Punkt-Marker. - max_color (tuple): RGBA-Farbwerte für den Max-Punkt-Marker. + label (int): cluster-id (used as marker-ID in rviz). + bbox (tuple): min- and max-values of bounding box + (x_min, x_max, y_min, y_max, z_min, z_max). + frame_id (str): frame ID for markers + min_color (tuple): RGBA-value for min-point-marker + max_color (tuple): RGBA-value for max-point-marker Returns: - tuple: Ein Paar von Markern (min_marker, max_marker). + tuple: pair of markers (min_marker, max_marker). """ x_min, x_max, y_min, y_max, z_min, z_max = bbox - # marker = Marker() - # marker.header.frame_id = "hero/RADAR" - # marker.id = int(label) - # # marker.type = Marker.LINE_STRIP - # marker.type = Marker.LINE_LIST - # marker.action = Marker.ADD - # marker.scale.x = 0.1 - # marker.color.r = 1.0 - # marker.color.g = 1.0 - # marker.color.b = 0.0 - # marker.color.a = 1.0 - - # Min-Punkt-Marker + # min-point-marker min_marker = Marker() min_marker.header.frame_id = frame_id - min_marker.id = int(label * 10) # ID für Min-Punkt + min_marker.id = int(label * 10) min_marker.type = Marker.SPHERE min_marker.action = Marker.ADD - min_marker.scale.x = 0.2 # Größe des Punktes + min_marker.scale.x = 0.2 min_marker.scale.y = 0.2 min_marker.scale.z = 0.2 min_marker.color.r = min_color[0] @@ -421,10 +424,10 @@ def create_min_max_markers(label, bbox, frame_id="hero/RADAR", min_color=(0.0, 1 min_marker.pose.position.y = y_min min_marker.pose.position.z = z_min - # Max-Punkt-Marker + # max-point-marker max_marker = Marker() max_marker.header.frame_id = frame_id - max_marker.id = int(label * 10 + 1) # ID für Max-Punkt + max_marker.id = int(label * 10 + 1) max_marker.type = Marker.SPHERE max_marker.action = Marker.ADD max_marker.scale.x = 0.2 @@ -442,15 +445,45 @@ def create_min_max_markers(label, bbox, frame_id="hero/RADAR", min_color=(0.0, 1 def clear_old_markers(marker_array, max_id): - """Löscht alte Marker aus dem MarkerArray.""" + """ + Removes old markers from the given MarkerArray by setting the action + to DELETE for markers with an ID greater than or equal to max_id. + + Args: + marker_array (MarkerArray): The current MarkerArray containing all markers. + max_id (int): The highest ID of the new markers. Markers with an ID + greater than or equal to this value will be marked for deletion. + + Returns: + MarkerArray: The updated MarkerArray with old markers removed. + """ for marker in marker_array.markers: if marker.id >= max_id: marker.action = Marker.DELETE return marker_array -# generates string with label-id and cluster size -def generate_cluster_labels_and_colors(clusters, data, marker_array, bounding_boxes): +# generates string with label-id and cluster size, can be used for extra debugging +def generate_cluster_info(clusters, data, marker_array, bounding_boxes): + """ + Generates information about clusters, including the label, number of points, + markers, and bounding boxes. + + Args: + clusters (DBSCAN): The clustered data, containing the labels for each point. + data (numpy.ndarray): + The point cloud data, typically with columns [x, y, z, distance]. + marker_array (MarkerArray): + The array of RViz markers associated with the clusters. + bounding_boxes (list): The list of bounding boxes for each detected object. + + Returns: + str: A JSON string containing the information about each cluster, including: + - "label": The cluster label. + - "points_count": The number of points in the cluster. + - "Anzahl marker": The number of markers in the MarkerArray. + - "Anzahl Boundingboxen": The number of bounding boxes. + """ cluster_info = [] for label in set(clusters.labels_): From 57e720d6119685ac63d3e276dcbb11c9c4a59aaa Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 11 Dec 2024 15:23:41 +0100 Subject: [PATCH 76/85] removed trailing white spaces --- code/perception/src/radar_node.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 975af2b1..aecbeca2 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -130,8 +130,8 @@ def filter_data(data, min_x=-100, max_x=100, min_y=-100, max_y=100, min_z=-1, ma Points outside these bounds are excluded from the output. Args: - data (np.ndarray): A 2D numpy array containing radar data, where each row - represents a data point with the format [x, y, z, distance]. The array + data (np.ndarray): A 2D numpy array containing radar data, where each row + represents a data point with the format [x, y, z, distance]. The array shape is (N, 4), where N is the number of points. min_x (float, optional): Minimum value for the x-coordinate. Default is -1. max_x (float, optional): Maximum value for the x-coordinate. Default is 1. @@ -143,7 +143,7 @@ def filter_data(data, min_x=-100, max_x=100, min_y=-100, max_y=100, min_z=-1, ma the sensor. Default is 100. Returns: - np.ndarray: A numpy array containing only the filtered data points that meet + np.ndarray: A numpy array containing only the filtered data points that meet the specified criteria. """ @@ -257,7 +257,7 @@ def calculate_aabb(cluster_points): all points in the cluster. Args: - cluster_points (numpy.ndarray): + cluster_points (numpy.ndarray): A 2D array where each row represents a 3D point (x, y, z). The array should have shape (N, 3) where N is the number of points. @@ -396,7 +396,7 @@ def create_min_max_markers(label, bbox, frame_id="hero/RADAR", Args: label (int): cluster-id (used as marker-ID in rviz). - bbox (tuple): min- and max-values of bounding box + bbox (tuple): min- and max-values of bounding box (x_min, x_max, y_min, y_max, z_min, z_max). frame_id (str): frame ID for markers min_color (tuple): RGBA-value for min-point-marker @@ -410,10 +410,10 @@ def create_min_max_markers(label, bbox, frame_id="hero/RADAR", # min-point-marker min_marker = Marker() min_marker.header.frame_id = frame_id - min_marker.id = int(label * 10) + min_marker.id = int(label * 10) min_marker.type = Marker.SPHERE min_marker.action = Marker.ADD - min_marker.scale.x = 0.2 + min_marker.scale.x = 0.2 min_marker.scale.y = 0.2 min_marker.scale.z = 0.2 min_marker.color.r = min_color[0] @@ -446,12 +446,12 @@ def create_min_max_markers(label, bbox, frame_id="hero/RADAR", def clear_old_markers(marker_array, max_id): """ - Removes old markers from the given MarkerArray by setting the action + Removes old markers from the given MarkerArray by setting the action to DELETE for markers with an ID greater than or equal to max_id. Args: marker_array (MarkerArray): The current MarkerArray containing all markers. - max_id (int): The highest ID of the new markers. Markers with an ID + max_id (int): The highest ID of the new markers. Markers with an ID greater than or equal to this value will be marked for deletion. Returns: From 78afbb6b82b7298674f15ab50584d6951c679f17 Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 15:34:04 +0100 Subject: [PATCH 77/85] Applied some suggestions by CodeRabbit. Deleted function get_largest_cluster which was not used anywhere. --- code/perception/src/lidar_distance.py | 327 ++++++++++---------------- 1 file changed, 122 insertions(+), 205 deletions(-) diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index 260cbea8..fa8ce676 100644 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -18,28 +18,28 @@ class LidarDistance: how to configute this node """ - cluster_buffer = [] + def __init__(self): + self.cluster_buffer = [] def callback(self, data): """ - Callback-Funktion, die LiDAR-Punktwolkendaten verarbeitet. + Callback function that processes LiDAR point cloud data. - Führt Clustering und Bildberechnungen für die Punktwolken aus. + Executes clustering and image calculations for the provided point cloud. - :param data: LiDAR-Punktwolken als ROS PointCloud2-Nachricht. + :param data: LiDAR point cloud as a ROS PointCloud2 message. """ - self.start_clustering(data) self.start_image_calculation(data) def listener(self): """ - Initialisiert die ROS-Node, erstellt Publisher/Subscriber und hält sie aktiv. + Initializes the ROS node, creates publishers/subscribers, and keeps it active. """ rospy.init_node("lidar_distance") - self.bridge = CvBridge() # OpenCV-Bridge für Bildkonvertierungen + self.bridge = CvBridge() # OpenCV bridge for image conversions - # Publisher für gefilterte Punktwolken + # Publisher for filtered point clouds self.pub_pointcloud = rospy.Publisher( rospy.get_param( "~point_cloud_topic", @@ -49,7 +49,7 @@ def listener(self): queue_size=1, ) - # Publisher für Distanzbilder in verschiedene Richtungen + # Publishers for distance images in various directions self.dist_array_center_publisher = rospy.Publisher( rospy.get_param("~image_distance_topic", "/paf/hero/Center/dist_array"), ImageMsg, @@ -67,7 +67,7 @@ def listener(self): PointCloud2, queue_size=10, ) - rospy.loginfo("dist_array_lidar_publisher erfolgreich erstellt.") + rospy.loginfo("dist_array_lidar_publisher successfully created.") self.dist_array_left_publisher = rospy.Publisher( rospy.get_param("~image_distance_topic", "/paf/hero/Left/dist_array"), ImageMsg, @@ -79,168 +79,125 @@ def listener(self): queue_size=10, ) - # Subscriber für LiDAR-Daten (Punktwolken) + # Subscriber for LiDAR data (point clouds) rospy.Subscriber( rospy.get_param("~source_topic", "/carla/hero/LIDAR"), PointCloud2, self.callback, ) - rospy.loginfo("Lidar Processor Node gestartet.") + rospy.loginfo("Lidar Processor Node started.") rospy.spin() def start_clustering(self, data): """ - Filtert LiDAR-Punktwolken, führt Clustering durch und veröffentlicht die kombinierten Cluster. + Filters LiDAR point clouds, performs clustering, and publishes the combined clusters. - :param data: LiDAR-Punktwolken im ROS PointCloud2-Format. + :param data: LiDAR point clouds in ROS PointCloud2 format. """ - # Punktwolken filtern, um irrelevante Daten zu entfernen + # Filter point clouds to remove irrelevant data coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) filtered_coordinates = coordinates[ ~( - (-2 <= coordinates["x"]) + (coordinates["x"] >= -2) & (coordinates["x"] <= 2) - & (-1 <= coordinates["y"]) + & (coordinates["y"] >= -1) & (coordinates["y"] <= 1) - ) # Ausschluss von Punkten die das eigene Auto betreffen + ) # Exclude points related to the ego vehicle & ( coordinates["z"] > -1.7 + 0.05 - ) # Mindesthöhe in z, um die Straße nicht zu clustern + ) # Minimum height in z to exclude the road ] - # Cluster-Daten aus den gefilterten Koordinaten berechnen + # Compute cluster data from the filtered coordinates clustered_points = cluster_lidar_data_from_pointcloud( coordinates=filtered_coordinates ) - # Nur gültige Cluster-Daten speichern + # Only store valid cluster data if clustered_points: - LidarDistance.cluster_buffer.append(clustered_points) + self.cluster_buffer.append(clustered_points) else: - rospy.logwarn("Keine Cluster-Daten erzeugt.") + rospy.logwarn("No cluster data generated.") - # Cluster kombinieren - combined_clusters = combine_clusters(LidarDistance.cluster_buffer) + # Combine clusters + combined_clusters = combine_clusters(self.cluster_buffer) - LidarDistance.cluster_buffer = [] + self.cluster_buffer = [] - # Veröffentliche die kombinierten Cluster + # Publish the combined clusters self.publish_clusters(combined_clusters, data.header) def publish_clusters(self, combined_clusters, data_header): """ - Veröffentlicht kombinierte Cluster als ROS PointCloud2-Nachricht. + Publishes combined clusters as a ROS PointCloud2 message. - :param combined_clusters: Kombinierte Punktwolken der Cluster als strukturiertes NumPy-Array. - :param data_header: Header-Informationen der ROS-Nachricht. + :param combined_clusters: Combined point clouds of the clusters as a structured NumPy array. + :param data_header: Header information for the ROS message. """ - # Konvertiere zu PointCloud2-Nachricht + # Convert to a PointCloud2 message pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2(combined_clusters) pointcloud_msg.header = data_header pointcloud_msg.header.stamp = rospy.Time.now() - # Cluster veröffentlichen + # Publish the clusters self.dist_array_lidar_publisher.publish(pointcloud_msg) def start_image_calculation(self, data): """ - Berechnet Distanzbilder basierend auf LiDAR-Daten und veröffentlicht sie. + Computes distance images based on LiDAR data and publishes them. - :param data: LiDAR-Punktwolken im ROS PointCloud2-Format. + :param data: LiDAR point cloud in ROS PointCloud2 format. """ coordinates = ros_numpy.point_cloud2.pointcloud2_to_array(data) - # Bildverarbeitung auf den Koordinaten durchführen + + # Directions to process + directions = ["Center", "Back", "Left", "Right"] + + # Process images for all directions processed_images = { - "Center": None, - "Back": None, - "Left": None, - "Right": None, + direction: self.calculate_image(coordinates, focus=direction) + for direction in directions } - processed_images["Center"] = self.calculate_image_center(coordinates) - processed_images["Back"] = self.calculate_image_back(coordinates) - processed_images["Left"] = self.calculate_image_left(coordinates) - processed_images["Right"] = self.calculate_image_right(coordinates) + # Publish the processed images self.publish_images(processed_images, data.header) - def calculate_image_center(self, coordinates): + def calculate_image(self, coordinates, focus): """ - Berechnet ein Distanzbild für die zentrale Ansicht aus LiDAR-Koordinaten. + Calculates a distance image for a specific focus (view direction) from LiDAR coordinates. - :param coordinates: Gefilterte LiDAR-Koordinaten als NumPy-Array. - :return: Distanzbild als 2D-Array. + :param coordinates: Filtered LiDAR coordinates as a NumPy array. + :param focus: The focus direction ("Center", "Back", "Left", "Right"). + :return: Distance image as a 2D array. """ - reconstruct_bit_mask_center = lidar_filter_utility.bounding_box( - coordinates, - max_x=np.inf, - min_x=0.0, - min_z=-1.6, - ) - reconstruct_coordinates_center = coordinates[reconstruct_bit_mask_center] - reconstruct_coordinates_xyz_center = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_center, "intensity" - ).tolist() - ) - dist_array_center = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_center, focus="Center" - ) - return dist_array_center - - def calculate_image_back(self, coordinates): - # Back - reconstruct_bit_mask_back = lidar_filter_utility.bounding_box( - coordinates, - max_x=0.0, - min_x=-np.inf, - min_z=-1.6, - ) - reconstruct_coordinates_back = coordinates[reconstruct_bit_mask_back] - reconstruct_coordinates_xyz_back = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_back, "intensity" - ).tolist() - ) - dist_array_back = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_back, focus="Back" - ) - return dist_array_back - - def calculate_image_left(self, coordinates): - # Left - reconstruct_bit_mask_left = lidar_filter_utility.bounding_box( - coordinates, - max_y=np.inf, - min_y=0.0, - min_z=-1.6, - ) - reconstruct_coordinates_left = coordinates[reconstruct_bit_mask_left] - reconstruct_coordinates_xyz_left = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates_left, "intensity" - ).tolist() - ) - dist_array_left = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_left, focus="Left" - ) - return dist_array_left + # Define bounding box parameters based on focus direction + bounding_box_params = { + "Center": {"max_x": np.inf, "min_x": 0.0, "min_z": -1.6}, + "Back": {"max_x": 0.0, "min_x": -np.inf, "min_z": -1.6}, + "Left": {"max_y": np.inf, "min_y": 0.0, "min_z": -1.6}, + "Right": {"max_y": -0.0, "min_y": -np.inf, "min_z": -1.6}, + } - def calculate_image_right(self, coordinates): - # Right - reconstruct_bit_mask_right = lidar_filter_utility.bounding_box( - coordinates, max_y=-0.0, min_y=-np.inf, min_z=-1.6 - ) - reconstruct_coordinates_right = coordinates[reconstruct_bit_mask_right] - reconstruct_coordinates_xyz_right = np.array( + # Select parameters for the given focus + params = bounding_box_params.get(focus) + if not params: + rospy.logwarn(f"Unknown focus: {focus}. Skipping image calculation.") + return None + + # Apply bounding box filter + reconstruct_bit_mask = lidar_filter_utility.bounding_box(coordinates, **params) + reconstruct_coordinates = coordinates[reconstruct_bit_mask] + + # Remove the "intensity" field and convert to a NumPy array + reconstruct_coordinates_xyz = np.array( lidar_filter_utility.remove_field_name( - reconstruct_coordinates_right, "intensity" + reconstruct_coordinates, "intensity" ).tolist() ) - dist_array_right = self.reconstruct_img_from_lidar( - reconstruct_coordinates_xyz_right, focus="Right" - ) - return dist_array_right + + # Reconstruct the image based on the focus + return self.reconstruct_img_from_lidar(reconstruct_coordinates_xyz, focus=focus) def publish_images(self, processed_images, data_header): """ @@ -271,71 +228,71 @@ def publish_images(self, processed_images, data_header): def reconstruct_img_from_lidar(self, coordinates_xyz, focus): """ - Rekonstruiert ein 2D-Bild aus 3D-LiDAR-Daten für eine gegebene Kameraansicht. + Reconstructs a 2D image from 3D LiDAR data for a given camera perspective. - :param coordinates_xyz: 3D-Koordinaten der gefilterten LiDAR-Punkte. - :param focus: Kameraansicht (z. B. "Center", "Back"). - :return: Rekonstruiertes Bild als 2D-Array. + :param coordinates_xyz: 3D coordinates of the filtered LiDAR points. + :param focus: Camera view (e.g., "Center", "Back"). + :return: Reconstructed image as a 2D array. """ - # Erstelle die intrinsische Kamera-Matrix basierend auf den Bildparametern (FOV, Auflösung) + # Create the intrinsic camera matrix based on image parameters (FOV, resolution) im = np.identity(3) - im[0, 2] = 1280 / 2.0 # x-Verschiebung (Bildmitte) - im[1, 2] = 720 / 2.0 # y-Verschiebung (Bildmitte) + im[0, 2] = 1280 / 2.0 # x-offset (image center) + im[1, 2] = 720 / 2.0 # y-offset (image center) im[0, 0] = im[1, 1] = 1280 / ( 2.0 * np.tan(100 * np.pi / 360.0) - ) # Skalierungsfaktor basierend auf FOV + ) # Scale factor based on FOV - # Erstelle die extrinsische Kamera-Matrix (Identität für keine Transformation) + # Create the extrinsic camera matrix (identity matrix for no transformation) ex = np.zeros(shape=(3, 4)) ex[0][0] = ex[1][1] = ex[2][2] = 1 - m = np.matmul(im, ex) # Kombiniere intrinsische und extrinsische Matrix + m = np.matmul(im, ex) # Combine intrinsic and extrinsic matrices - # Initialisiere leere Bilder für die Rekonstruktion + # Initialize empty images for reconstruction img = np.zeros(shape=(720, 1280), dtype=np.float32) dist_array = np.zeros(shape=(720, 1280, 3), dtype=np.float32) - # Verarbeite jeden Punkt in der Punktwolke + # Process each point in the point cloud for c in coordinates_xyz: - if focus == "Center": + if focus == "Center": # Compute image for the center view point = np.array([c[1], c[2], c[0], 1]) - pixel = np.matmul( - m, point - ) # Projiziere 3D-Punkt auf 2D-Bildkoordinaten + pixel = np.matmul(m, point) # Project 3D point to 2D image coordinates x, y = int(pixel[0] / pixel[2]), int( pixel[1] / pixel[2] - ) # Normalisiere Koordinaten - if x >= 0 and x <= 1280 and y >= 0 and y <= 720: # Prüfe Bildgrenzen - img[719 - y][1279 - x] = c[0] # Setze Tiefenwert + ) # Normalize coordinates + if ( + 0 <= x <= 1280 and 0 <= y <= 720 + ): # Check if coordinates are within image bounds + img[719 - y][1279 - x] = c[0] # Set depth value dist_array[719 - y][1279 - x] = np.array( [c[0], c[1], c[2]], dtype=np.float32 ) - if focus == "Back": # Berechne Bild für die Rückansicht + if focus == "Back": # Compute image for the rear view point = np.array([c[1], c[2], c[0], 1]) pixel = np.matmul(m, point) x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x <= 1280 and y >= 0 and y < 720: + if 0 <= x <= 1280 and 0 <= y < 720: img[y][1279 - x] = -c[0] dist_array[y][1279 - x] = np.array( [-c[0], c[1], c[2]], dtype=np.float32 ) - if focus == "Left": # Berechne Bild für die linke Ansicht + if focus == "Left": # Compute image for the left view point = np.array([c[0], c[2], c[1], 1]) pixel = np.matmul(m, point) x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x <= 1280 and y >= 0 and y <= 720: + if 0 <= x <= 1280 and 0 <= y <= 720: img[719 - y][1279 - x] = c[1] dist_array[y][1279 - x] = np.array( [c[0], c[1], c[2]], dtype=np.float32 ) - if focus == "Right": # Berechne Bild für die rechte Ansicht + if focus == "Right": # Compute image for the right view point = np.array([c[0], c[2], c[1], 1]) pixel = np.matmul(m, point) x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if x >= 0 and x < 1280 and y >= 0 and y < 720: + if 0 <= x < 1280 and 0 <= y < 720: img[y][1279 - x] = -c[1] dist_array[y][1279 - x] = np.array( [c[0], c[1], c[2]], dtype=np.float32 @@ -346,100 +303,60 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): def array_to_pointcloud2(points, header="hero/Lidar"): """ - Konvertiert ein Array von Punkten in eine ROS PointCloud2-Nachricht. + Converts an array of points into a ROS PointCloud2 message. - :param points: Array von Punkten mit [x, y, z]-Koordinaten. - :param header: Header-Informationen der ROS PointCloud2-Nachricht. - :return: ROS PointCloud2-Nachricht. + :param points: Array of points with [x, y, z] coordinates. + :param header: Header information for the ROS PointCloud2 message. + :return: ROS PointCloud2 message. """ - # Sicherstellen, dass die Eingabe ein NumPy-Array ist + # Ensure the input is a NumPy array points_array = np.array(points) - # Konvertiere die Punkte in ein strukturiertes Array mit Feldern "x", "y", "z" + # Convert the points into a structured array with fields "x", "y", "z" points_structured = np.array( [(p[0], p[1], p[2]) for p in points_array], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")], ) - # Erstelle eine PointCloud2-Nachricht aus dem strukturierten Array + # Create a PointCloud2 message from the structured array pointcloud_msg = ros_numpy.point_cloud2.array_to_pointcloud2(points_structured) - # Setze den Zeitstempel und den Header der Nachricht + # Set the timestamp and header for the message pointcloud_msg.header.stamp = rospy.Time.now() pointcloud_msg.header = header return pointcloud_msg -def get_largest_cluster(clustered_points, return_structured=True): - """ - Ermittelt das größte Cluster aus gegebenen Punktwolken-Clustern. - - :param clustered_points: Dictionary mit Cluster-IDs und zugehörigen Punktwolken. - :param return_structured: Gibt ein strukturiertes NumPy-Array zurück, falls True. - :return: Größtes Cluster als NumPy-Array (roh oder strukturiert). - """ - # Prüfen, ob es Cluster gibt - if not clustered_points: - return np.array([]) - - # Identifiziere das größte Cluster basierend auf der Anzahl der Punkte - largest_cluster_id, largest_cluster = max( - clustered_points.items(), key=lambda item: len(item[1]) - ) - - # Sicherstellen, dass das größte Cluster nicht leer ist - if largest_cluster.size == 0: - return np.array([]) - - rospy.loginfo( - f"Largest cluster: {largest_cluster_id} with {largest_cluster.shape[0]} points" - ) - - # Rohdaten zurückgeben, wenn kein strukturiertes Array benötigt wird - if not return_structured: - return largest_cluster - - # Konvertiere das größte Cluster in ein strukturiertes Array - points_structured = np.empty( - largest_cluster.shape[0], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4")] - ) - points_structured["x"] = largest_cluster[:, 0] - points_structured["y"] = largest_cluster[:, 1] - points_structured["z"] = largest_cluster[:, 2] - - return points_structured - - def combine_clusters(cluster_buffer): """ - Kombiniert Cluster aus mehreren Punktwolken zu einem strukturierten NumPy-Array. + Combines clusters from multiple point clouds into a structured NumPy array. - :param cluster_buffer: Liste von Dictionaries mit Cluster-IDs und Punktwolken. - :return: Kombiniertes strukturiertes NumPy-Array mit Feldern "x", "y", "z", "cluster_id". + :param cluster_buffer: List of dictionaries containing cluster IDs and point clouds. + :return: Combined structured NumPy array with fields "x", "y", "z", "cluster_id". """ points_list = [] cluster_ids_list = [] for clustered_points in cluster_buffer: for cluster_id, points in clustered_points.items(): - if points.size > 0: # Ignoriere leere Cluster + if points.size > 0: # Ignore empty clusters points_list.append(points) - # Erstelle ein Array mit der Cluster-ID für alle Punkte des Clusters + # Create an array with the cluster ID for all points in the cluster cluster_ids_list.append( np.full(points.shape[0], cluster_id, dtype=np.float32) ) - if not points_list: # Falls keine Punkte vorhanden sind + if not points_list: # If no points are present return np.array( [], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"), ("cluster_id", "f4")] ) - # Kombiniere alle Punkte und Cluster-IDs in zwei separate Arrays + # Combine all points and cluster IDs into two separate arrays all_points = np.vstack(points_list) all_cluster_ids = np.concatenate(cluster_ids_list) - # Erstelle ein strukturiertes Array für die kombinierten Daten + # Create a structured array for the combined data combined_points = np.zeros( all_points.shape[0], dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"), ("cluster_id", "f4")], @@ -454,33 +371,33 @@ def combine_clusters(cluster_buffer): def cluster_lidar_data_from_pointcloud(coordinates, eps=0.3, min_samples=10): """ - Führt Clustering auf LiDAR-Daten mit DBSCAN durch und gibt Cluster zurück. + Performs clustering on LiDAR data using DBSCAN and returns the clusters. - :param coordinates: LiDAR-Punktwolken als NumPy-Array mit "x", "y", "z". - :param eps: Maximaler Abstand zwischen Punkten, um sie zu einem Cluster zuzuordnen. - :param min_samples: Minimale Anzahl von Punkten, um ein Cluster zu bilden. - :return: Dictionary mit Cluster-IDs und zugehörigen Punktwolken. + :param coordinates: LiDAR point cloud as a NumPy array with "x", "y", "z". + :param eps: Maximum distance between points to group them into a cluster. + :param min_samples: Minimum number of points required to form a cluster. + :return: Dictionary with cluster IDs and their corresponding point clouds. """ if coordinates.shape[0] == 0: - rospy.logerr("Das Eingabe-Array 'coordinates' ist leer.") + rospy.logerr("The input array 'coordinates' is empty.") return {} - # Extrahiere x, y und z aus den Koordinaten für die DBSCAN-Berechnung + # Extract x, y, and z from the coordinates for DBSCAN clustering xyz = np.column_stack((coordinates["x"], coordinates["y"], coordinates["z"])) if xyz.shape[0] == 0: - rospy.logwarn("Keine Datenpunkte für DBSCAN verfügbar. Überspringe Clustering.") + rospy.logwarn("No data points available for DBSCAN. Skipping clustering.") return {} - # Wende DBSCAN an, um Cluster-Labels für die Punktwolke zu berechnen + # Apply DBSCAN to compute cluster labels for the point cloud clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(xyz) labels = clustering.labels_ - # Entferne Rauschen (Cluster-ID: -1) und bestimme gültige Cluster-IDs + # Remove noise (cluster ID: -1) and identify valid cluster IDs unique_labels = np.unique(labels) valid_labels = unique_labels[unique_labels != -1] - # Erstelle ein Dictionary mit Cluster-IDs und den zugehörigen Punkten + # Create a dictionary with cluster IDs and their corresponding points clusters = Parallel(n_jobs=-1)( delayed(lambda l: (l, xyz[labels == l]))(label) for label in valid_labels ) From ca171467c4eca354a36115257f89e7baa40c7557 Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 15:38:28 +0100 Subject: [PATCH 78/85] Updated version to satisfy linter. --- code/perception/src/lidar_distance.py | 26 +++++++++++++++++--------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index fa8ce676..939224c5 100644 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -91,7 +91,8 @@ def listener(self): def start_clustering(self, data): """ - Filters LiDAR point clouds, performs clustering, and publishes the combined clusters. + Filters LiDAR point clouds, performs clustering, + and publishes the combined clusters. :param data: LiDAR point clouds in ROS PointCloud2 format. """ @@ -133,7 +134,8 @@ def publish_clusters(self, combined_clusters, data_header): """ Publishes combined clusters as a ROS PointCloud2 message. - :param combined_clusters: Combined point clouds of the clusters as a structured NumPy array. + :param combined_clusters: Combined point clouds of the clusters as a structured + NumPy array. :param data_header: Header information for the ROS message. """ # Convert to a PointCloud2 message @@ -165,7 +167,8 @@ def start_image_calculation(self, data): def calculate_image(self, coordinates, focus): """ - Calculates a distance image for a specific focus (view direction) from LiDAR coordinates. + Calculates a distance image for a specific focus (view direction) from + LiDAR coordinates. :param coordinates: Filtered LiDAR coordinates as a NumPy array. :param focus: The focus direction ("Center", "Back", "Left", "Right"). @@ -201,17 +204,18 @@ def calculate_image(self, coordinates, focus): def publish_images(self, processed_images, data_header): """ - Veröffentlicht Distanzbilder für verschiedene Richtungen als ROS-Bildnachrichten. + Publishes distance images for various directions as ROS image messages. - :param processed_images: Dictionary mit Richtungen ("Center", "Back", etc.) als Schlüssel und Bildarrays als Werte. - :param data_header: Header der ROS-Bildnachrichten. + :param processed_images: Dictionary with directions ("Center", "Back", etc.) + as keys and image arrays as values. + :param data_header: Header for the ROS image messages. """ - # Nur gültige NumPy-Arrays weiterverarbeiten + # Process only valid NumPy arrays for direction, image_array in processed_images.items(): if not isinstance(image_array, np.ndarray): continue - # Konvertiere das Bild in eine ROS-Image-Nachricht + # Convert the image into a ROS image message dist_array_msg = self.bridge.cv2_to_imgmsg( image_array, encoding="passthrough" ) @@ -399,8 +403,12 @@ def cluster_lidar_data_from_pointcloud(coordinates, eps=0.3, min_samples=10): # Create a dictionary with cluster IDs and their corresponding points clusters = Parallel(n_jobs=-1)( - delayed(lambda l: (l, xyz[labels == l]))(label) for label in valid_labels + delayed(lambda cluster_label: (cluster_label, xyz[labels == cluster_label]))( + label + ) + for label in valid_labels ) + clusters = dict(clusters) return clusters From 0f1a9f93b785d26cfa6945c2c7be8fb00a2b8358 Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 11 Dec 2024 15:47:18 +0100 Subject: [PATCH 79/85] bug fixes --- code/perception/src/radar_node.py | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index aecbeca2..246e86cf 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -74,21 +74,21 @@ def listener(self): ) self.visualization_radar_publisher = rospy.Publisher( rospy.get_param( - "~image_distance_topic", "/paf/hero/Radar/Visualization" + "~visualisation_topic", "/paf/hero/Radar/Visualization" ), PointCloud2, queue_size=10, ) self.marker_visualization_radar_publisher = rospy.Publisher( rospy.get_param( - "~image_distance_topic", "/paf/hero/Radar/Marker" + "~marker_topic", "/paf/hero/Radar/Marker" ), MarkerArray, queue_size=10, ) self.cluster_info_radar_publisher = rospy.Publisher( rospy.get_param( - "~image_distance_topic", "/paf/hero/Radar/ClusterInfo" + "~clusterInfo_topic_topic", "/paf/hero/Radar/ClusterInfo" ), String, queue_size=10, @@ -133,12 +133,12 @@ def filter_data(data, min_x=-100, max_x=100, min_y=-100, max_y=100, min_z=-1, ma data (np.ndarray): A 2D numpy array containing radar data, where each row represents a data point with the format [x, y, z, distance]. The array shape is (N, 4), where N is the number of points. - min_x (float, optional): Minimum value for the x-coordinate. Default is -1. - max_x (float, optional): Maximum value for the x-coordinate. Default is 1. - min_y (float, optional): Minimum value for the y-coordinate. Default is 1. - max_y (float, optional): Maximum value for the y-coordinate. Default is 1. - min_z (float, optional): Minimum value for the z-coordinate. Default is -0.7. - max_z (float, optional): Maximum value for the z-coordinate. Default is 1.3. + min_x (float, optional): Minimum value for the x-coordinate. Default is -100. + max_x (float, optional): Maximum value for the x-coordinate. Default is 100. + min_y (float, optional): Minimum value for the y-coordinate. Default is -100. + max_y (float, optional): Maximum value for the y-coordinate. Default is 100. + min_z (float, optional): Minimum value for the z-coordinate. Default is -1. + max_z (float, optional): Maximum value for the z-coordinate. Default is 100. max_distance (float, optional): Maximum allowable distance of the point from the sensor. Default is 100. @@ -160,7 +160,8 @@ def filter_data(data, min_x=-100, max_x=100, min_y=-100, max_y=100, min_z=-1, ma def cluster_data(data, eps=0.8, min_samples=3): - """_summary_ + """ + Clusters the radar data using the DBSCAN algorithm Args: data (np.ndarray): data array which should be clustered @@ -171,6 +172,7 @@ def cluster_data(data, eps=0.8, min_samples=3): dict: A dictionary where the keys are cluster labels (int) and the values are the number of points in each cluster. Returns an empty dictionary if no points are available. + DBSCAN: A DBSCAN clustering object containing labels and core sample indices """ if len(data) == 0: @@ -458,7 +460,7 @@ def clear_old_markers(marker_array, max_id): MarkerArray: The updated MarkerArray with old markers removed. """ for marker in marker_array.markers: - if marker.id >= max_id: + if marker.id > max_id: marker.action = Marker.DELETE return marker_array @@ -493,8 +495,8 @@ def generate_cluster_info(clusters, data, marker_array, bounding_boxes): cluster_info.append({ "label": int(label), "points_count": cluster_size, - "Anzahl marker": len(marker_array.markers), - "Anzahl Boundingboxen": len(bounding_boxes) + "num_marker": len(marker_array.markers), + "num_bounding_boxes": len(bounding_boxes) }) return json.dumps(cluster_info) From 40a4595c977687321b7b3d63d5b077b218b6cc86 Mon Sep 17 00:00:00 2001 From: Ralf Date: Wed, 11 Dec 2024 15:55:29 +0100 Subject: [PATCH 80/85] added black formatter extension --- code/perception/src/radar_node.py | 83 +++++++++++++++++++------------ 1 file changed, 51 insertions(+), 32 deletions(-) diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py index 246e86cf..fcb32ddd 100755 --- a/code/perception/src/radar_node.py +++ b/code/perception/src/radar_node.py @@ -40,8 +40,9 @@ def callback(self, data): cloud = create_pointcloud2(dataarray, clustered_data.labels_) self.visualization_radar_publisher.publish(cloud) - points_with_labels = np.hstack((dataarray, - clustered_data.labels_.reshape(-1, 1))) + points_with_labels = np.hstack( + (dataarray, clustered_data.labels_.reshape(-1, 1)) + ) bounding_boxes = generate_bounding_boxes(points_with_labels) marker_array = MarkerArray() @@ -58,8 +59,9 @@ def callback(self, data): self.marker_visualization_radar_publisher.publish(marker_array) - cluster_info = generate_cluster_info(clustered_data, dataarray, marker_array, - bounding_boxes) + cluster_info = generate_cluster_info( + clustered_data, dataarray, marker_array, bounding_boxes + ) self.cluster_info_radar_publisher.publish(cluster_info) def listener(self): @@ -73,23 +75,17 @@ def listener(self): queue_size=10, ) self.visualization_radar_publisher = rospy.Publisher( - rospy.get_param( - "~visualisation_topic", "/paf/hero/Radar/Visualization" - ), + rospy.get_param("~visualisation_topic", "/paf/hero/Radar/Visualization"), PointCloud2, queue_size=10, ) self.marker_visualization_radar_publisher = rospy.Publisher( - rospy.get_param( - "~marker_topic", "/paf/hero/Radar/Marker" - ), + rospy.get_param("~marker_topic", "/paf/hero/Radar/Marker"), MarkerArray, queue_size=10, ) self.cluster_info_radar_publisher = rospy.Publisher( - rospy.get_param( - "~clusterInfo_topic_topic", "/paf/hero/Radar/ClusterInfo" - ), + rospy.get_param("~clusterInfo_topic_topic", "/paf/hero/Radar/ClusterInfo"), String, queue_size=10, ) @@ -121,8 +117,16 @@ def pointcloud2_to_array(pointcloud_msg): ) -def filter_data(data, min_x=-100, max_x=100, min_y=-100, max_y=100, min_z=-1, max_z=100, - max_distance=100): +def filter_data( + data, + min_x=-100, + max_x=100, + min_y=-100, + max_y=100, + min_z=-1, + max_z=100, + max_distance=100, +): """ Filters radar data based on specified spatial and distance constraints. @@ -218,14 +222,14 @@ def create_pointcloud2(clustered_points, cluster_labels): else: r, g, b = colors[label] - rgb = struct.unpack('f', struct.pack('I', (r << 16) | (g << 8) | b))[0] + rgb = struct.unpack("f", struct.pack("I", (r << 16) | (g << 8) | b))[0] points.append([x, y, z, rgb]) fields = [ - PointField('x', 0, PointField.FLOAT32, 1), - PointField('y', 4, PointField.FLOAT32, 1), - PointField('z', 8, PointField.FLOAT32, 1), - PointField('rgb', 12, PointField.FLOAT32, 1), + PointField("x", 0, PointField.FLOAT32, 1), + PointField("y", 4, PointField.FLOAT32, 1), + PointField("z", 8, PointField.FLOAT32, 1), + PointField("rgb", 12, PointField.FLOAT32, 1), ] return point_cloud2.create_cloud(header, fields, points) @@ -378,9 +382,18 @@ def create_bounding_box_marker(label, bbox): ] lines = [ - (0, 1), (1, 2), (2, 3), (3, 0), # Bottom - (4, 5), (5, 6), (6, 7), (7, 4), # Top - (0, 4), (1, 5), (2, 6), (3, 7), # Vertical Edges + (0, 1), + (1, 2), + (2, 3), + (3, 0), # Bottom + (4, 5), + (5, 6), + (6, 7), + (7, 4), # Top + (0, 4), + (1, 5), + (2, 6), + (3, 7), # Vertical Edges ] for start, end in lines: marker.points.append(points[start]) @@ -390,9 +403,13 @@ def create_bounding_box_marker(label, bbox): # can be used for extra debugging -def create_min_max_markers(label, bbox, frame_id="hero/RADAR", - min_color=(0.0, 1.0, 0.0, 1.0), - max_color=(1.0, 0.0, 0.0, 1.0)): +def create_min_max_markers( + label, + bbox, + frame_id="hero/RADAR", + min_color=(0.0, 1.0, 0.0, 1.0), + max_color=(1.0, 0.0, 0.0, 1.0), +): """ creates RViz-Markers for min- and max-points of a bounding box. @@ -492,12 +509,14 @@ def generate_cluster_info(clusters, data, marker_array, bounding_boxes): cluster_points = data[clusters.labels_ == label] cluster_size = len(cluster_points) if label != -1: - cluster_info.append({ - "label": int(label), - "points_count": cluster_size, - "num_marker": len(marker_array.markers), - "num_bounding_boxes": len(bounding_boxes) - }) + cluster_info.append( + { + "label": int(label), + "points_count": cluster_size, + "num_marker": len(marker_array.markers), + "num_bounding_boxes": len(bounding_boxes), + } + ) return json.dumps(cluster_info) From fc396341a8315d1fa5eaf97fa210a19dc9ccdaaf Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 16:04:20 +0100 Subject: [PATCH 81/85] Restored standard settings in file '/code/agent/config/rviz_config.rviz' --- code/agent/config/rviz_config.rviz | 93 +++++++----------------------- 1 file changed, 20 insertions(+), 73 deletions(-) diff --git a/code/agent/config/rviz_config.rviz b/code/agent/config/rviz_config.rviz index 998284c8..2e419cc2 100644 --- a/code/agent/config/rviz_config.rviz +++ b/code/agent/config/rviz_config.rviz @@ -1,12 +1,14 @@ Panels: - Class: rviz/Displays - Help Height: 70 + Help Height: 78 Name: Displays Property Tree Widget: Expanded: - - /PointCloud2 dist_clustered1 + - /PointCloud23 + - /PointCloud24 + - /PointCloud25 Splitter Ratio: 0.5 - Tree Height: 325 + Tree Height: 308 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -64,23 +66,26 @@ Visualization Manager: Grid: false Imu: false Path: false - PointCloud2: true - PointCloud2 dist_clustered: true + PointCloud2: false Value: true - VisonNode Output: true Zoom Factor: 1 - Class: rviz/Image Enabled: true + Image Rendering: background and overlay Image Topic: /paf/hero/Center/segmented_image - Max Value: 1 - Median window: 5 - Min Value: 0 Name: VisonNode Output - Normalize Range: true + Overlay Alpha: 0.5 Queue Size: 2 Transport Hint: raw Unreliable: false Value: true + Visibility: + Grid: true + Imu: true + Path: true + PointCloud2: true + Value: true + Zoom Factor: 1 - Alpha: 1 Class: rviz_plugin_tutorials/Imu Color: 204; 51; 204 @@ -255,62 +260,6 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: PointCloud2 - Position Transformer: "" - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /paf/hero/dist_clustered - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Min Color: 0; 0; 0 - Name: PointCloud2 dist_clustered - Position Transformer: "" - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: /paf/hero/dist_clustered - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -339,7 +288,7 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 10.540092468261719 + Distance: 34.785499572753906 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -355,9 +304,9 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.3953982889652252 + Pitch: 0.19039836525917053 Target Frame: - Yaw: 3.255431652069092 + Yaw: 4.520427227020264 Saved: ~ Window Geometry: Camera: @@ -367,7 +316,7 @@ Window Geometry: Height: 1376 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000304000004c6fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000002070000021e0000001600fffffffb00000020005600690073006f006e004e006f006400650020004f00750074007000750074010000042b000000d60000001600ffffff000000010000010f000004c6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000004c6000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b80000003efc0100000002fb0000000800540069006d00650100000000000009b80000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000599000004c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd000000040000000000000304000004c6fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b0000022a000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061010000026b000002960000001600ffffff000000010000010f000004c6fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000004c6000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009b80000003efc0100000002fb0000000800540069006d00650100000000000009b80000030700fffffffb0000000800540069006d0065010000000000000450000000000000000000000599000004c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -376,8 +325,6 @@ Window Geometry: collapsed: false Views: collapsed: false - VisonNode Output: - collapsed: false Width: 2488 X: 1992 - Y: 27 + Y: 27 \ No newline at end of file From d6615f519d366fbe11ff0437878556c5f48581b8 Mon Sep 17 00:00:00 2001 From: michalal7 Date: Wed, 11 Dec 2024 16:09:23 +0100 Subject: [PATCH 82/85] Removed debugger arguments. --- code/perception/launch/perception.launch | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch index 127ae9a4..0133a9d4 100644 --- a/code/perception/launch/perception.launch +++ b/code/perception/launch/perception.launch @@ -1,6 +1,6 @@ - + @@ -75,7 +75,7 @@ - + From 486e5bf62e4f8112c1dd6f805e89e80c6d31b04a Mon Sep 17 00:00:00 2001 From: SirMDA Date: Thu, 12 Dec 2024 17:16:24 +0100 Subject: [PATCH 83/85] fixed lidar_distance node speed by removing for loop --- code/perception/src/lidar_distance.py | 129 ++++++++++++++++---------- 1 file changed, 79 insertions(+), 50 deletions(-) mode change 100644 => 100755 code/perception/src/lidar_distance.py diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py old mode 100644 new mode 100755 index 939224c5..bea1d550 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -3,7 +3,7 @@ import rospy import ros_numpy import numpy as np -import lidar_filter_utility +from lidar_filter_utility import bounding_box, remove_field_name from sensor_msgs.msg import PointCloud2, Image as ImageMsg from sklearn.cluster import DBSCAN from cv_bridge import CvBridge @@ -189,14 +189,12 @@ def calculate_image(self, coordinates, focus): return None # Apply bounding box filter - reconstruct_bit_mask = lidar_filter_utility.bounding_box(coordinates, **params) + reconstruct_bit_mask = bounding_box(coordinates, **params) reconstruct_coordinates = coordinates[reconstruct_bit_mask] # Remove the "intensity" field and convert to a NumPy array reconstruct_coordinates_xyz = np.array( - lidar_filter_utility.remove_field_name( - reconstruct_coordinates, "intensity" - ).tolist() + remove_field_name(reconstruct_coordinates, "intensity").tolist() ) # Reconstruct the image based on the focus @@ -256,51 +254,82 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): img = np.zeros(shape=(720, 1280), dtype=np.float32) dist_array = np.zeros(shape=(720, 1280, 3), dtype=np.float32) - # Process each point in the point cloud - for c in coordinates_xyz: - if focus == "Center": # Compute image for the center view - point = np.array([c[1], c[2], c[0], 1]) - pixel = np.matmul(m, point) # Project 3D point to 2D image coordinates - x, y = int(pixel[0] / pixel[2]), int( - pixel[1] / pixel[2] - ) # Normalize coordinates - if ( - 0 <= x <= 1280 and 0 <= y <= 720 - ): # Check if coordinates are within image bounds - img[719 - y][1279 - x] = c[0] # Set depth value - dist_array[719 - y][1279 - x] = np.array( - [c[0], c[1], c[2]], dtype=np.float32 - ) - - if focus == "Back": # Compute image for the rear view - point = np.array([c[1], c[2], c[0], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if 0 <= x <= 1280 and 0 <= y < 720: - img[y][1279 - x] = -c[0] - dist_array[y][1279 - x] = np.array( - [-c[0], c[1], c[2]], dtype=np.float32 - ) - - if focus == "Left": # Compute image for the left view - point = np.array([c[0], c[2], c[1], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if 0 <= x <= 1280 and 0 <= y <= 720: - img[719 - y][1279 - x] = c[1] - dist_array[y][1279 - x] = np.array( - [c[0], c[1], c[2]], dtype=np.float32 - ) - - if focus == "Right": # Compute image for the right view - point = np.array([c[0], c[2], c[1], 1]) - pixel = np.matmul(m, point) - x, y = int(pixel[0] / pixel[2]), int(pixel[1] / pixel[2]) - if 0 <= x < 1280 and 0 <= y < 720: - img[y][1279 - x] = -c[1] - dist_array[y][1279 - x] = np.array( - [c[0], c[1], c[2]], dtype=np.float32 - ) + # Prepare points based on focus + if focus == "Center": + points = np.column_stack( + ( + coordinates_xyz[:, 1], + coordinates_xyz[:, 2], + coordinates_xyz[:, 0], + np.ones(coordinates_xyz.shape[0]), + ) + ) + elif focus == "Back": + points = np.column_stack( + ( + coordinates_xyz[:, 1], + coordinates_xyz[:, 2], + coordinates_xyz[:, 0], + np.ones(coordinates_xyz.shape[0]), + ) + ) + elif focus == "Left": + points = np.column_stack( + ( + coordinates_xyz[:, 0], + coordinates_xyz[:, 2], + coordinates_xyz[:, 1], + np.ones(coordinates_xyz.shape[0]), + ) + ) + elif focus == "Right": + points = np.column_stack( + ( + coordinates_xyz[:, 0], + coordinates_xyz[:, 2], + coordinates_xyz[:, 1], + np.ones(coordinates_xyz.shape[0]), + ) + ) + else: + rospy.logwarn(f"Unknown focus: {focus}. Skipping image calculation.") + return None + + # Project 3D points to 2D image coordinates + pixels = np.dot(m, points.T).T + x = (pixels[:, 0] / pixels[:, 2]).astype(int) + y = (pixels[:, 1] / pixels[:, 2]).astype(int) + + # Filter valid coordinates + valid_indices = (x >= 0) & (x < 1280) & (y >= 0) & (y < 720) + x = x[valid_indices] + y = y[valid_indices] + valid_coordinates = coordinates_xyz[valid_indices] + + if focus == "Center": + img[719 - y, 1279 - x] = valid_coordinates[:, 0] + dist_array[719 - y, 1279 - x] = valid_coordinates + elif focus == "Back": + img[y, 1279 - x] = -valid_coordinates[:, 0] + dist_array[y, 1279 - x] = np.column_stack( + ( + -valid_coordinates[:, 0], + valid_coordinates[:, 1], + valid_coordinates[:, 2], + ) + ) + elif focus == "Left": + img[719 - y, 1279 - x] = valid_coordinates[:, 1] + dist_array[719 - y, 1279 - x] = valid_coordinates + elif focus == "Right": + img[y, 1279 - x] = -valid_coordinates[:, 1] + dist_array[y, 1279 - x] = np.column_stack( + ( + valid_coordinates[:, 0], + -valid_coordinates[:, 1], + valid_coordinates[:, 2], + ) + ) return dist_array From eefcd29f6690efbfa765c140a77261c161386f05 Mon Sep 17 00:00:00 2001 From: SirMDA Date: Thu, 12 Dec 2024 17:33:37 +0100 Subject: [PATCH 84/85] optimized focus if clause --- code/perception/src/lidar_distance.py | 22 ++-------------------- 1 file changed, 2 insertions(+), 20 deletions(-) diff --git a/code/perception/src/lidar_distance.py b/code/perception/src/lidar_distance.py index bea1d550..5c937be0 100755 --- a/code/perception/src/lidar_distance.py +++ b/code/perception/src/lidar_distance.py @@ -255,16 +255,7 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): dist_array = np.zeros(shape=(720, 1280, 3), dtype=np.float32) # Prepare points based on focus - if focus == "Center": - points = np.column_stack( - ( - coordinates_xyz[:, 1], - coordinates_xyz[:, 2], - coordinates_xyz[:, 0], - np.ones(coordinates_xyz.shape[0]), - ) - ) - elif focus == "Back": + if focus in ["Center", "Back"]: points = np.column_stack( ( coordinates_xyz[:, 1], @@ -273,16 +264,7 @@ def reconstruct_img_from_lidar(self, coordinates_xyz, focus): np.ones(coordinates_xyz.shape[0]), ) ) - elif focus == "Left": - points = np.column_stack( - ( - coordinates_xyz[:, 0], - coordinates_xyz[:, 2], - coordinates_xyz[:, 1], - np.ones(coordinates_xyz.shape[0]), - ) - ) - elif focus == "Right": + elif focus in ["Left", "Right"]: points = np.column_stack( ( coordinates_xyz[:, 0], From 727f1d5dad110ae194d40ca7f3549943be9e4840 Mon Sep 17 00:00:00 2001 From: seefelke <33551476+seefelke@users.noreply.github.com> Date: Thu, 12 Dec 2024 21:53:40 +0100 Subject: [PATCH 85/85] 529 - Implement service for planning - acting communication (#549) * implemented acting-planning service * Create RequestBehaviourChangeService.md * Update RequestBehaviourChangeService.md * Update RequestBehaviourChangeService.md * Update RequestBehaviourChangeService.py small comment fix --- code/planning/CMakeLists.txt | 7 +- code/planning/launch/planning.launch | 7 +- .../RequestBehaviourChangeService.py | 82 +++++++++++++++++++ code/planning/srv/RequestBehaviourChange.srv | 3 + doc/planning/RequestBehaviourChangeService.md | 26 ++++++ 5 files changed, 121 insertions(+), 4 deletions(-) create mode 100755 code/planning/src/behavior_agent/RequestBehaviourChangeService.py create mode 100644 code/planning/srv/RequestBehaviourChange.srv create mode 100644 doc/planning/RequestBehaviourChangeService.md diff --git a/code/planning/CMakeLists.txt b/code/planning/CMakeLists.txt index c6288e03..d8cf2bff 100755 --- a/code/planning/CMakeLists.txt +++ b/code/planning/CMakeLists.txt @@ -58,11 +58,12 @@ catkin_python_setup() ) ## Generate services in the 'srv' folder -# add_service_files( -# FILES +add_service_files( + FILES # Service1.srv # Service2.srv -# ) + RequestBehaviourChange.srv +) ## Generate actions in the 'action' folder # add_action_files( diff --git a/code/planning/launch/planning.launch b/code/planning/launch/planning.launch index 6662d9a3..d5803ddd 100644 --- a/code/planning/launch/planning.launch +++ b/code/planning/launch/planning.launch @@ -1,7 +1,7 @@ - + @@ -35,4 +35,9 @@ + + + + + diff --git a/code/planning/src/behavior_agent/RequestBehaviourChangeService.py b/code/planning/src/behavior_agent/RequestBehaviourChangeService.py new file mode 100755 index 00000000..aa058ab3 --- /dev/null +++ b/code/planning/src/behavior_agent/RequestBehaviourChangeService.py @@ -0,0 +1,82 @@ +#!/usr/bin/env python +# import BehaviourEnum +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from rospy import Subscriber, Publisher +import rospy +from planning.srv import RequestBehaviourChange, RequestBehaviourChangeResponse +from std_msgs.msg import String, Int8 + + +class RequestBehaviourChangeService(CompatibleNode): + def __init__(self): + super(RequestBehaviourChangeService, self).__init__( + "RequestBehaviourChangeService" + ) + self.role_name = self.get_param("role_name", "hero") + self.control_loop_rate = self.get_param("control_loop_rate", 1) + self.__curr_behavior = None + + self.service = rospy.Service( + "RequestBehaviourChange", + RequestBehaviourChange, + self.handle_request_behaviour_change, + ) + + self.behaviour_pub: Publisher = self.new_publisher( + Int8, + f"/paf/{self.role_name}/behaviour_request", + qos_profile=1, + ) + + self.curr_behavior_sub: Subscriber = self.new_subscription( + String, + f"/paf/{self.role_name}/curr_behavior", + self.__set_curr_behavior, + qos_profile=1, + ) + + self.behaviour_pub.publish(0) + rospy.spin() + + def __set_curr_behavior(self, data: String): + """ + Sets the received current behavior of the vehicle. + """ + self.__curr_behavior = data.data + + def handle_request_behaviour_change(self, req): + if ( + self.__curr_behavior == "us_unstuck" + or self.__curr_behavior == "us_stop" + or self.__curr_behavior == "us_overtake" + or self.__curr_behavior == "Cruise" + ): + self.behaviour_pub.publish(req.request) + return RequestBehaviourChangeResponse(True) + else: + return RequestBehaviourChangeResponse(False) + + def run(self): + """ + Control loop + + :return: + """ + + self.spin() + + +if __name__ == "__main__": + """ + main function starts the RequestBehaviourChangeService node + :param args: + """ + roscomp.init("RequestBehaviourChangeService") + try: + node = RequestBehaviourChangeService() + node.run() + except KeyboardInterrupt: + pass + finally: + roscomp.shutdown() diff --git a/code/planning/srv/RequestBehaviourChange.srv b/code/planning/srv/RequestBehaviourChange.srv new file mode 100644 index 00000000..d4da3b97 --- /dev/null +++ b/code/planning/srv/RequestBehaviourChange.srv @@ -0,0 +1,3 @@ +uint8 request +--- +bool answer \ No newline at end of file diff --git a/doc/planning/RequestBehaviourChangeService.md b/doc/planning/RequestBehaviourChangeService.md new file mode 100644 index 00000000..fe0a3751 --- /dev/null +++ b/doc/planning/RequestBehaviourChangeService.md @@ -0,0 +1,26 @@ +# Request Behaviour Change Service + +This service is hosted in the node RequestBehaviourChangeService. + +Calling it requires a behaviour ID integer (based on the corresponding enum) and returns a bool depending on whether the request is granted. + +To use it, import RequestBehaviourChange from planning.srv. + +To call it, create a callable instance with: + +```python +rospy.wait_for_service('RequestBehaviourChange') + +name = rospy.ServiceProxy('RequestBehaviourChange', RequestBehaviourChange) +``` + +Then, you can just use this instance in a try setup: + +```python +try: + response = name(input) +except rospy.ServiceException as e: + # handle exception +``` + +For communication with the behaviour tree this node publishes a granted request to a topic behaviour_request.