From 2893e67c3d8ad953a2d874d6ee129045d666aeef Mon Sep 17 00:00:00 2001 From: Hiroki Kato Date: Thu, 2 Jan 2025 13:45:42 +0900 Subject: [PATCH] added racs2_demos_on_spaceros jaxa's demo (Issue #26) --- racs2_demos_on_spaceros/CMakeLists.txt | 53 ++ racs2_demos_on_spaceros/Dockerfile | 142 ++++ racs2_demos_on_spaceros/README.md | 93 +++ racs2_demos_on_spaceros/build.sh | 23 + .../cFS/apps/run_app/CMakeLists.txt | 15 + .../run_app/fsw/mission_inc/run_app_perfids.h | 7 + .../run_app/fsw/platform_inc/run_app_msgids.h | 9 + .../fsw/src/RACS2Brdige_std_msgs.pb-c.c | 261 ++++++++ .../fsw/src/RACS2Brdige_std_msgs.pb-c.h | 139 ++++ .../fsw/src/RACS2Bridge_geometry_msgs.pb-c.c | 622 ++++++++++++++++++ .../fsw/src/RACS2Bridge_geometry_msgs.pb-c.h | 277 ++++++++ .../cFS/apps/run_app/fsw/src/racs2_user_msg.h | 22 + .../cFS/apps/run_app/fsw/src/run_app.c | 436 ++++++++++++ .../cFS/apps/run_app/fsw/src/run_app.h | 41 ++ .../cFS/apps/run_app/fsw/src/run_app_events.h | 13 + .../cFS/apps/run_app/fsw/src/run_app_msg.h | 36 + .../apps/run_app/fsw/src/run_app_version.h | 9 + .../cFS/sample_defs/cpu1_cfe_es_startup.scr | 34 + .../cFS/sample_defs/racs2_bridge_config.txt | 2 + .../cFS/sample_defs/targets.cmake | 100 +++ .../config/mars_rover_control.yaml | 116 ++++ racs2_demos_on_spaceros/entrypoint.sh | 6 + .../launch/mars_rover.launch.py | 194 ++++++ .../mars_rover/__init__.py | 0 .../nodes/RACS2Bridge_geometry_msgs_pb2.py | 374 +++++++++++ racs2_demos_on_spaceros/nodes/move_arm | 68 ++ racs2_demos_on_spaceros/nodes/move_mast | 84 +++ racs2_demos_on_spaceros/nodes/move_wheel | 147 +++++ .../nodes/odom_tf_publisher | 66 ++ racs2_demos_on_spaceros/nodes/run_demo | 86 +++ racs2_demos_on_spaceros/nodes/test_node | 41 ++ racs2_demos_on_spaceros/package.xml | 42 ++ .../racs2_demo_on_spaceros_nodes.png | Bin 0 -> 186909 bytes .../racs2_demos_on_spaceros/__init__.py | 0 racs2_demos_on_spaceros/run.sh | 16 + .../worlds/mars_curiosity.world | 64 ++ 36 files changed, 3638 insertions(+) create mode 100644 racs2_demos_on_spaceros/CMakeLists.txt create mode 100644 racs2_demos_on_spaceros/Dockerfile create mode 100644 racs2_demos_on_spaceros/README.md create mode 100755 racs2_demos_on_spaceros/build.sh create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/CMakeLists.txt create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/mission_inc/run_app_perfids.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/platform_inc/run_app_msgids.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.c create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.c create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/racs2_user_msg.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.c create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_events.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_msg.h create mode 100644 racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_version.h create mode 100644 racs2_demos_on_spaceros/cFS/sample_defs/cpu1_cfe_es_startup.scr create mode 100644 racs2_demos_on_spaceros/cFS/sample_defs/racs2_bridge_config.txt create mode 100644 racs2_demos_on_spaceros/cFS/sample_defs/targets.cmake create mode 100644 racs2_demos_on_spaceros/config/mars_rover_control.yaml create mode 100755 racs2_demos_on_spaceros/entrypoint.sh create mode 100644 racs2_demos_on_spaceros/launch/mars_rover.launch.py create mode 100644 racs2_demos_on_spaceros/mars_rover/__init__.py create mode 100644 racs2_demos_on_spaceros/nodes/RACS2Bridge_geometry_msgs_pb2.py create mode 100644 racs2_demos_on_spaceros/nodes/move_arm create mode 100644 racs2_demos_on_spaceros/nodes/move_mast create mode 100644 racs2_demos_on_spaceros/nodes/move_wheel create mode 100644 racs2_demos_on_spaceros/nodes/odom_tf_publisher create mode 100644 racs2_demos_on_spaceros/nodes/run_demo create mode 100644 racs2_demos_on_spaceros/nodes/test_node create mode 100644 racs2_demos_on_spaceros/package.xml create mode 100644 racs2_demos_on_spaceros/racs2_demo_on_spaceros_nodes.png create mode 100644 racs2_demos_on_spaceros/racs2_demos_on_spaceros/__init__.py create mode 100755 racs2_demos_on_spaceros/run.sh create mode 100644 racs2_demos_on_spaceros/worlds/mars_curiosity.world diff --git a/racs2_demos_on_spaceros/CMakeLists.txt b/racs2_demos_on_spaceros/CMakeLists.txt new file mode 100644 index 0000000..9f550fe --- /dev/null +++ b/racs2_demos_on_spaceros/CMakeLists.txt @@ -0,0 +1,53 @@ +cmake_minimum_required(VERSION 3.8) +project(mars_rover) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) +find_package(control_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(rclpy REQUIRED) +find_package(simulation REQUIRED) +find_package(std_msgs REQUIRED) +# uncomment the following section in order to fill in +# further dependencies manually. +# find_package( REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + # the following line skips the linter which checks for copyrights + # comment the line when a copyright and license is added to all source files + set(ament_cmake_copyright_FOUND TRUE) + # the following line skips cpplint (only works in a git repo) + # comment the line when this package is in a git repo and when + # a copyright and license is added to all source files + set(ament_cmake_cpplint_FOUND TRUE) + ament_lint_auto_find_test_dependencies() +endif() + +install(DIRECTORY + config + launch + worlds + DESTINATION share/${PROJECT_NAME} +) + +ament_python_install_package(${PROJECT_NAME}) + +install(PROGRAMS + nodes/move_arm + nodes/move_mast + nodes/move_wheel + nodes/run_demo + nodes/odom_tf_publisher + nodes/RACS2Bridge_geometry_msgs_pb2.py + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/racs2_demos_on_spaceros/Dockerfile b/racs2_demos_on_spaceros/Dockerfile new file mode 100644 index 0000000..eb79042 --- /dev/null +++ b/racs2_demos_on_spaceros/Dockerfile @@ -0,0 +1,142 @@ +# Copyright 2021 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# A Docker configuration script to build the Space ROS image. +# +# The script provides the following build arguments: +# +# VCS_REF - The git revision of the Space ROS source code (no default value). +# VERSION - The version of Space ROS (default: "preview") + +FROM openrobotics/space_robots_demo:latest + +# Define arguments used in the metadata definition +ARG VCS_REF +ARG VERSION="preview" + +# Specify the docker image metadata +LABEL org.label-schema.schema-version="1.0" +LABEL org.label-schema.name="RACS2 demo on Curiosity Rover" +LABEL org.label-schema.description="RACS2 demo on the Space ROS platform" +LABEL org.label-schema.vendor="JAXA" +LABEL org.label-schema.version=${VERSION} +LABEL org.label-schema.url="https://github.com/space-ros" +LABEL org.label-schema.vcs-url="https://github.com/space-ros/docker" +LABEL org.label-schema.vcs-ref=${VCS_REF} + +# Define a few key variables +ENV RACS2_DEMO_DIR=${HOME_DIR}/racs2_ws + +# Disable prompting during package installation +ARG DEBIAN_FRONTEND=noninteractive + +# Get rosinstall_generator +# Using Docker BuildKit cache mounts for /var/cache/apt and /var/lib/apt ensures that +# the cache won't make it into the built image but will be maintained between steps. +RUN --mount=type=cache,target=/var/cache/apt,sharing=locked \ + --mount=type=cache,target=/var/lib/apt,sharing=locked \ + sudo apt-get update -y && sudo apt-get install -y python3-rosinstall-generator + +RUN mkdir -p ${RACS2_DEMO_DIR} +WORKDIR ${RACS2_DEMO_DIR} + +# Install dependencies +RUN --mount=type=cache,target=/var/cache/apt,sharing=locked \ + --mount=type=cache,target=/var/lib/apt,sharing=locked \ + sudo apt-get install libwebsockets-dev libwebsockets-dev protobuf-c-compiler libprotobuf-c-dev python3-pip tmux gdb -y +RUN python3 -m pip install protobuf==3.20.0 websockets==12.0 + +# Get the cFS source code +RUN git clone --recursive -b v6.7.0a https://github.com/nasa/cFS/ cfs +WORKDIR ${RACS2_DEMO_DIR}/cfs +RUN git submodule init +RUN git submodule update + +# Get the RACS2 source code +WORKDIR ${RACS2_DEMO_DIR} +RUN git clone https://github.com/jaxa/racs2_bridge -b v1.1 + +# Get the demo source code +# rename old demo directory and exclude from build +WORKDIR ${DEMO_DIR}/src +# RUN mv demos demos_old +RUN cp -r demos demos_old +RUN touch demos_old/COLCON_IGNORE +# git clone new demo +# RUN git clone https://github.com/tt-saito/demos.git -b racs2_demo2 +# RUN git clone https://github.com/space-ros/demos + +# Customize cFS to run the bridge +WORKDIR ${RACS2_DEMO_DIR}/cfs +RUN cp cfe/cmake/Makefile.sample Makefile +RUN cp -r cfe/cmake/sample_defs sample_defs +RUN cp -pr ${RACS2_DEMO_DIR}/racs2_bridge/cFS/Bridge/Client_C/apps/racs2_bridge_client apps/ + +# Deploy the run_app application and adjust the startup scripts +# RUN cp -pr ${DEMO_DIR}/src/demos/racs2_demos_on_spaceros/cFS/sample_defs/* ${RACS2_DEMO_DIR}/cfs/sample_defs/ +# RUN cp -pr ${DEMO_DIR}/src/demos/racs2_demos_on_spaceros/cFS/apps/run_app ${RACS2_DEMO_DIR}/cfs/apps/ +COPY cFS/sample_defs/cpu1_cfe_es_startup.scr ${RACS2_DEMO_DIR}/cfs/sample_defs/cpu1_cfe_es_startup.scr +COPY cFS/sample_defs/racs2_bridge_config.txt ${RACS2_DEMO_DIR}/cfs/sample_defs/racs2_bridge_config.txt +COPY cFS/sample_defs/targets.cmake ${RACS2_DEMO_DIR}/cfs/sample_defs/targets.cmake +COPY cFS/apps/run_app ${RACS2_DEMO_DIR}/cfs/apps/run_app + +# This is necessary to run cFS inside docker +RUN sed -i -e 's/^#undef OSAL_DEBUG_PERMISSIVE_MODE/#define OSAL_DEBUG_PERMISSIVE_MODE 1/g' sample_defs/default_osconfig.h +RUN sed -i -e 's/^#undef OSAL_DEBUG_DISABLE_TASK_PRIORITIES/#define OSAL_DEBUG_DISABLE_TASK_PRIORITIES 1/g' sample_defs/default_osconfig.h + +# This is only needed because docker by default starts in IPv4. This setting +# is specific to the JAXA bridge. +RUN sed -i -e 's/^wss_uri=.*/wss_uri=127.0.0.1/g' sample_defs/racs2_bridge_config.txt + +# Compile cFS +RUN make SIMULATION=native prep +RUN make +RUN make install + +# Prepare ROS packages +WORKDIR ${DEMO_DIR} +# Copy bridge & racs2_msg node +RUN cp -pr ${RACS2_DEMO_DIR}/racs2_bridge/ROS2/Bridge/Server_Python/bridge_py_s src/ +RUN cp -pr ${RACS2_DEMO_DIR}/racs2_bridge/Example/Case.1/ROS2/racs2_msg src/ + + +COPY CMakeLists.txt ${DEMO_DIR}/src/demos/mars_rover/CMakeLists.txt +COPY package.xml ${DEMO_DIR}/src/demos/mars_rover/package.xml +# COPY racs2_demos_on_spaceros ${DEMO_DIR}/src/demos/mars_rover/racs2_demos_on_spaceros +COPY launch/mars_rover.launch.py ${DEMO_DIR}/src/demos/mars_rover/launch/mars_rover.launch.py +COPY nodes/RACS2Bridge_geometry_msgs_pb2.py ${DEMO_DIR}/src/demos/mars_rover/nodes/RACS2Bridge_geometry_msgs_pb2.py +COPY nodes/move_wheel ${DEMO_DIR}/src/demos/mars_rover/nodes/move_wheel + + + + +# Install dependencies +RUN --mount=type=cache,target=/var/cache/apt,sharing=locked \ + --mount=type=cache,target=/var/lib/apt,sharing=locked \ + sudo apt-get update -y \ +&& /bin/bash -c 'source "${SPACEROS_DIR}/install/setup.bash"' \ +&& /bin/bash -c 'source "${MOVEIT2_DIR}/install/setup.bash"' \ +&& rosdep install --from-paths src --ignore-src -r -y --rosdistro ${ROS_DISTRO} + +# Build the demo +RUN /bin/bash -c 'source ${SPACEROS_DIR}/install/setup.bash && source ${MOVEIT2_DIR}/install/setup.bash \ + && colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release' + +# Add the user to the render group so that the user can access /dev/dri/renderD128 +RUN sudo usermod -aG render $USERNAME + +# Setup the entrypoint +COPY ./entrypoint.sh / +ENTRYPOINT ["/entrypoint.sh"] +CMD ["bash"] diff --git a/racs2_demos_on_spaceros/README.md b/racs2_demos_on_spaceros/README.md new file mode 100644 index 0000000..3d08cc3 --- /dev/null +++ b/racs2_demos_on_spaceros/README.md @@ -0,0 +1,93 @@ +# RACS2 on Space ROS and Space Robots Demo Docker Image + +The RACS2 on Space ROS and Space Robots Demo docker image uses the space_robots demo docker image (*openrobotics/space_robots_demo:latest*) as its base image. +Build instructions for that image can be found in [this README](../space_robots/README.md). +The Dockerfile installs all of the prerequisite system dependencies along with the demos source code, then builds the Space ROS Space Robots and RACS2 demo. + +This is RACS2 Bridge demo for Curiosity Mars rover. + +## Building the Demo Docker + +The demo image builds on top of the `spaceros`, `moveit2`, `space_robots` images. +To build the docker image, first ensure the `spaceros` base image is available either by [building it locally](https://github.com/space-ros/space-ros) or pulling it. + +Then build the `moveit2`, `space_robots` and `racs2_demos_on_spaceros` demo images: + +```bash +git clone https://github.com/space-ros/docker.git +cd docker/moveit2 +./build.sh +cd ../space_robots +./build.sh +cd ../../ +./build.sh +``` + +## Running the Demo Docker + +(at /path/to/demos/racs2_demos_on_spaceros/docker/racs2_demos_on_spaceros) +run the following to allow GUI passthrough: +```bash +xhost +local:docker +``` + +Then run: +```bash +./run.sh +``` + +Depending on the host computer, you might need to remove the ```--gpus all``` flag in ```run.sh```, which uses your GPUs. + +## Running the Demos + +### Curiosity Mars rover demo +Launch the rover demo (calling Terminal 1): +```bash +source install/setup.bash +ros2 launch mars_rover mars_rover.launch.py +``` + +#### RACS2 Bridge demo + +##### Running racs2 bridge node +Open a new terminal (calling Terminal 2) and attach to the currently running container: + +```bash +docker exec -it bash +source install/setup.bash +ros2 run bridge_py_s bridge_py_s_node --ros-args --params-file ./src/bridge_py_s/config/params.yaml +``` + +##### Running cFS bridge app & run_app app +Open a new terminal (calling Terminal 3) and attach to the currently running container: + +```bash +docker exec -it bash +cd ~/racs2_ws +cd cfs/build/exe/cpu1/ +./core-cpu1 +``` + +**Executing commands to the rover must be done with this terminal active.** + + +##### Available Commands + +Drive commands to the rover are input via keyboard in Terimnal 3. The keymap is as follows. + +* "w": Drive the rover forward +* "s": Drive the rover backward +* "a": Turn left +* "d": Turn right +* "x": Stop the rover + +##### Nodes +![RACS2 demo on Space ROS Mars rover demo](racs2_demo_on_spaceros_nodes.png) + +## Reference + +* [RACS2 bridge project by Japan Aerospace Exploration Agency (JAXA)](https://github.com/jaxa/racs2_bridge) + +* [Hiroki Kato and Tatsuhiko Saito, "RACS2: the ROS2 and cFS System - launched" Flight Software Workshop 2023.](https://drive.google.com/drive/folders/1C9fokWGDl2e4NfgX_ZU3f98FfPe9udwQ) + +* [Hiroki Kato and Tatsuhiko Saito, "ROS and cFS System (RACS): Easing Space Robotic Development post-opensource activities and ROS2 integration" Flight Software Workshop 2021.](https://drive.google.com/file/d/11L48doT_pRNs7R0hdChPALqJO849TvV2/view?usp=drive_web) diff --git a/racs2_demos_on_spaceros/build.sh b/racs2_demos_on_spaceros/build.sh new file mode 100755 index 0000000..ded50cd --- /dev/null +++ b/racs2_demos_on_spaceros/build.sh @@ -0,0 +1,23 @@ +#!/usr/bin/env bash + +ORG=jaxa +IMAGE=racs2_demos_on_spaceros +TAG=latest + +VCS_REF="" +VERSION=preview + +# Exit script with failure if build fails +set -eo pipefail + +echo "" +echo "##### Building RACS2 Demo on Space ROS Docker Image #####" +echo "" + +docker build -t $ORG/$IMAGE:$TAG \ + --build-arg VCS_REF="$VCS_REF" \ + --build-arg VERSION="$VERSION" . + +echo "" +echo "##### Done! #####" + diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/CMakeLists.txt b/racs2_demos_on_spaceros/cFS/apps/run_app/CMakeLists.txt new file mode 100644 index 0000000..fe32de4 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.6.4) +project(CFE_RUN_APP C) + +include_directories(fsw/mission_inc) +include_directories(fsw/platform_inc) + +aux_source_directory(fsw/src APP_SRC_FILES) + +# Create the app module +add_cfe_app(run_app ${APP_SRC_FILES}) + +target_link_libraries(run_app + ${PROTOBUF_LIBRARY} + protobuf-c +) \ No newline at end of file diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/mission_inc/run_app_perfids.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/mission_inc/run_app_perfids.h new file mode 100644 index 0000000..643eeec --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/mission_inc/run_app_perfids.h @@ -0,0 +1,7 @@ +#ifndef _run_app_perfids_h_ +#define _run_app_perfids_h_ + + +#define SAMPLE_APP_PERF_ID 91 + +#endif /* _run_app_perfids_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/platform_inc/run_app_msgids.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/platform_inc/run_app_msgids.h new file mode 100644 index 0000000..0a44407 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/platform_inc/run_app_msgids.h @@ -0,0 +1,9 @@ +#ifndef _run_app_msgids_h_ +#define _run_app_msgids_h_ + +#define RUN_APP_CMD_MID 0x1892 +#define RUN_APP_SEND_HK_MID 0x1893 +#define RUN_APP_HK_TLM_MID 0x0893 +#define RACS2_BRIDGE_MID 0x1EFE + +#endif /* _run_app_msgids_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.c b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.c new file mode 100644 index 0000000..0512d65 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.c @@ -0,0 +1,261 @@ +/* Generated by the protocol buffer compiler. DO NOT EDIT! */ +/* Generated from: RACS2Brdige_std_msgs.proto */ + +/* Do not generate deprecated warnings for self */ +#ifndef PROTOBUF_C__NO_DEPRECATED +#define PROTOBUF_C__NO_DEPRECATED +#endif + +#include "RACS2Brdige_std_msgs.pb-c.h" +void racs2_bridge_std_msgs__init + (RACS2BridgeStdMsgs *message) +{ + static const RACS2BridgeStdMsgs init_value = RACS2_BRIDGE_STD_MSGS__INIT; + *message = init_value; +} +size_t racs2_bridge_std_msgs__get_packed_size + (const RACS2BridgeStdMsgs *message) +{ + assert(message->base.descriptor == &racs2_bridge_std_msgs__descriptor); + return protobuf_c_message_get_packed_size ((const ProtobufCMessage*)(message)); +} +size_t racs2_bridge_std_msgs__pack + (const RACS2BridgeStdMsgs *message, + uint8_t *out) +{ + assert(message->base.descriptor == &racs2_bridge_std_msgs__descriptor); + return protobuf_c_message_pack ((const ProtobufCMessage*)message, out); +} +size_t racs2_bridge_std_msgs__pack_to_buffer + (const RACS2BridgeStdMsgs *message, + ProtobufCBuffer *buffer) +{ + assert(message->base.descriptor == &racs2_bridge_std_msgs__descriptor); + return protobuf_c_message_pack_to_buffer ((const ProtobufCMessage*)message, buffer); +} +RACS2BridgeStdMsgs * + racs2_bridge_std_msgs__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data) +{ + return (RACS2BridgeStdMsgs *) + protobuf_c_message_unpack (&racs2_bridge_std_msgs__descriptor, + allocator, len, data); +} +void racs2_bridge_std_msgs__free_unpacked + (RACS2BridgeStdMsgs *message, + ProtobufCAllocator *allocator) +{ + if(!message) + return; + assert(message->base.descriptor == &racs2_bridge_std_msgs__descriptor); + protobuf_c_message_free_unpacked ((ProtobufCMessage*)message, allocator); +} +static const ProtobufCFieldDescriptor racs2_bridge_std_msgs__field_descriptors[14] = +{ + { + "bool_data", + 1, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_BOOL, + offsetof(RACS2BridgeStdMsgs, has_bool_data), + offsetof(RACS2BridgeStdMsgs, bool_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "float_data", + 2, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeStdMsgs, has_float_data), + offsetof(RACS2BridgeStdMsgs, float_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "double_data", + 3, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_DOUBLE, + offsetof(RACS2BridgeStdMsgs, has_double_data), + offsetof(RACS2BridgeStdMsgs, double_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "int32_data", + 4, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_INT32, + offsetof(RACS2BridgeStdMsgs, has_int32_data), + offsetof(RACS2BridgeStdMsgs, int32_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "int64_data", + 5, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_INT64, + offsetof(RACS2BridgeStdMsgs, has_int64_data), + offsetof(RACS2BridgeStdMsgs, int64_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "string_data", + 6, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_STRING, + 0, /* quantifier_offset */ + offsetof(RACS2BridgeStdMsgs, string_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "uint32_data", + 7, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_UINT32, + offsetof(RACS2BridgeStdMsgs, has_uint32_data), + offsetof(RACS2BridgeStdMsgs, uint32_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "uint64_data", + 8, + PROTOBUF_C_LABEL_OPTIONAL, + PROTOBUF_C_TYPE_UINT64, + offsetof(RACS2BridgeStdMsgs, has_uint64_data), + offsetof(RACS2BridgeStdMsgs, uint64_data), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "float32_array_data", + 9, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeStdMsgs, n_float32_array_data), + offsetof(RACS2BridgeStdMsgs, float32_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "float64_array_data", + 10, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_DOUBLE, + offsetof(RACS2BridgeStdMsgs, n_float64_array_data), + offsetof(RACS2BridgeStdMsgs, float64_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "int32_array_data", + 11, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_INT32, + offsetof(RACS2BridgeStdMsgs, n_int32_array_data), + offsetof(RACS2BridgeStdMsgs, int32_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "int64_array_data", + 12, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_INT64, + offsetof(RACS2BridgeStdMsgs, n_int64_array_data), + offsetof(RACS2BridgeStdMsgs, int64_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "uint32_array_data", + 13, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_UINT32, + offsetof(RACS2BridgeStdMsgs, n_uint32_array_data), + offsetof(RACS2BridgeStdMsgs, uint32_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "uint64_array_data", + 14, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_UINT64, + offsetof(RACS2BridgeStdMsgs, n_uint64_array_data), + offsetof(RACS2BridgeStdMsgs, uint64_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, +}; +static const unsigned racs2_bridge_std_msgs__field_indices_by_name[] = { + 0, /* field[0] = bool_data */ + 2, /* field[2] = double_data */ + 8, /* field[8] = float32_array_data */ + 9, /* field[9] = float64_array_data */ + 1, /* field[1] = float_data */ + 10, /* field[10] = int32_array_data */ + 3, /* field[3] = int32_data */ + 11, /* field[11] = int64_array_data */ + 4, /* field[4] = int64_data */ + 5, /* field[5] = string_data */ + 12, /* field[12] = uint32_array_data */ + 6, /* field[6] = uint32_data */ + 13, /* field[13] = uint64_array_data */ + 7, /* field[7] = uint64_data */ +}; +static const ProtobufCIntRange racs2_bridge_std_msgs__number_ranges[1 + 1] = +{ + { 1, 0 }, + { 0, 14 } +}; +const ProtobufCMessageDescriptor racs2_bridge_std_msgs__descriptor = +{ + PROTOBUF_C__MESSAGE_DESCRIPTOR_MAGIC, + "RACS2Bridge_std_msgs", + "RACS2BridgeStdMsgs", + "RACS2BridgeStdMsgs", + "", + sizeof(RACS2BridgeStdMsgs), + 14, + racs2_bridge_std_msgs__field_descriptors, + racs2_bridge_std_msgs__field_indices_by_name, + 1, racs2_bridge_std_msgs__number_ranges, + (ProtobufCMessageInit) racs2_bridge_std_msgs__init, + NULL,NULL,NULL /* reserved[123] */ +}; diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.h new file mode 100644 index 0000000..54a70aa --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Brdige_std_msgs.pb-c.h @@ -0,0 +1,139 @@ +/* Generated by the protocol buffer compiler. DO NOT EDIT! */ +/* Generated from: RACS2Brdige_std_msgs.proto */ + +#ifndef PROTOBUF_C_RACS2Brdige_5fstd_5fmsgs_2eproto__INCLUDED +#define PROTOBUF_C_RACS2Brdige_5fstd_5fmsgs_2eproto__INCLUDED + +#include + +PROTOBUF_C__BEGIN_DECLS + +#if PROTOBUF_C_VERSION_NUMBER < 1000000 +# error This file was generated by a newer version of protoc-c which is incompatible with your libprotobuf-c headers. Please update your headers. +#elif 1003003 < PROTOBUF_C_MIN_COMPILER_VERSION +# error This file was generated by an older version of protoc-c which is incompatible with your libprotobuf-c headers. Please regenerate this file with a newer version of protoc-c. +#endif + + +typedef struct _RACS2BridgeStdMsgs RACS2BridgeStdMsgs; + + +/* --- enums --- */ + + +/* --- messages --- */ + +struct _RACS2BridgeStdMsgs +{ + ProtobufCMessage base; + /* + * -- std_msgs/Bool --------------------------- + */ + protobuf_c_boolean has_bool_data; + protobuf_c_boolean bool_data; + /* + * -- std_msgs/Float32 --------------------------- + */ + protobuf_c_boolean has_float_data; + float float_data; + /* + * -- std_msgs/Float64 --------------------------- + */ + protobuf_c_boolean has_double_data; + double double_data; + /* + * -- std_msgs/Int32 --------------------------- + */ + protobuf_c_boolean has_int32_data; + int32_t int32_data; + /* + * -- std_msgs/Int64 --------------------------- + */ + protobuf_c_boolean has_int64_data; + int64_t int64_data; + /* + * -- std_msgs/String --------------------------- + */ + char *string_data; + /* + * -- std_msgs/Uint32 --------------------------- + */ + protobuf_c_boolean has_uint32_data; + uint32_t uint32_data; + /* + * -- std_msgs/Uint64 --------------------------- + */ + protobuf_c_boolean has_uint64_data; + uint64_t uint64_data; + /* + * -- std_msgs/Float32MultiArray --------------------------- + */ + size_t n_float32_array_data; + float *float32_array_data; + /* + * -- std_msgs/Float64MultiArray --------------------------- + */ + size_t n_float64_array_data; + double *float64_array_data; + /* + * -- std_msgs/Int32MultiArray --------------------------- + */ + size_t n_int32_array_data; + int32_t *int32_array_data; + /* + * -- std_msgs/Int64MultiArray --------------------------- + */ + size_t n_int64_array_data; + int64_t *int64_array_data; + /* + * -- std_msgs/Uint32MultiArray --------------------------- + */ + size_t n_uint32_array_data; + uint32_t *uint32_array_data; + /* + * -- std_msgs/Uint64MultiArray --------------------------- + */ + size_t n_uint64_array_data; + uint64_t *uint64_array_data; +}; +#define RACS2_BRIDGE_STD_MSGS__INIT \ + { PROTOBUF_C_MESSAGE_INIT (&racs2_bridge_std_msgs__descriptor) \ + , 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, NULL, 0, 0, 0, 0, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL } + + +/* RACS2BridgeStdMsgs methods */ +void racs2_bridge_std_msgs__init + (RACS2BridgeStdMsgs *message); +size_t racs2_bridge_std_msgs__get_packed_size + (const RACS2BridgeStdMsgs *message); +size_t racs2_bridge_std_msgs__pack + (const RACS2BridgeStdMsgs *message, + uint8_t *out); +size_t racs2_bridge_std_msgs__pack_to_buffer + (const RACS2BridgeStdMsgs *message, + ProtobufCBuffer *buffer); +RACS2BridgeStdMsgs * + racs2_bridge_std_msgs__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data); +void racs2_bridge_std_msgs__free_unpacked + (RACS2BridgeStdMsgs *message, + ProtobufCAllocator *allocator); +/* --- per-message closures --- */ + +typedef void (*RACS2BridgeStdMsgs_Closure) + (const RACS2BridgeStdMsgs *message, + void *closure_data); + +/* --- services --- */ + + +/* --- descriptors --- */ + +extern const ProtobufCMessageDescriptor racs2_bridge_std_msgs__descriptor; + +PROTOBUF_C__END_DECLS + + +#endif /* PROTOBUF_C_RACS2Brdige_5fstd_5fmsgs_2eproto__INCLUDED */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.c b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.c new file mode 100644 index 0000000..d26ed5e --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.c @@ -0,0 +1,622 @@ +/* Generated by the protocol buffer compiler. DO NOT EDIT! */ +/* Generated from: RACS2Bridge_geometry_msgs.proto */ + +/* Do not generate deprecated warnings for self */ +#ifndef PROTOBUF_C__NO_DEPRECATED +#define PROTOBUF_C__NO_DEPRECATED +#endif + +#include "RACS2Bridge_geometry_msgs.pb-c.h" +void racs2_bridge_geometry_msgs__vector3__init + (RACS2BridgeGeometryMsgsVector3 *message) +{ + static const RACS2BridgeGeometryMsgsVector3 init_value = RACS2_BRIDGE_GEOMETRY_MSGS__VECTOR3__INIT; + *message = init_value; +} +size_t racs2_bridge_geometry_msgs__vector3__get_packed_size + (const RACS2BridgeGeometryMsgsVector3 *message) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__vector3__descriptor); + return protobuf_c_message_get_packed_size ((const ProtobufCMessage*)(message)); +} +size_t racs2_bridge_geometry_msgs__vector3__pack + (const RACS2BridgeGeometryMsgsVector3 *message, + uint8_t *out) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__vector3__descriptor); + return protobuf_c_message_pack ((const ProtobufCMessage*)message, out); +} +size_t racs2_bridge_geometry_msgs__vector3__pack_to_buffer + (const RACS2BridgeGeometryMsgsVector3 *message, + ProtobufCBuffer *buffer) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__vector3__descriptor); + return protobuf_c_message_pack_to_buffer ((const ProtobufCMessage*)message, buffer); +} +RACS2BridgeGeometryMsgsVector3 * + racs2_bridge_geometry_msgs__vector3__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data) +{ + return (RACS2BridgeGeometryMsgsVector3 *) + protobuf_c_message_unpack (&racs2_bridge_geometry_msgs__vector3__descriptor, + allocator, len, data); +} +void racs2_bridge_geometry_msgs__vector3__free_unpacked + (RACS2BridgeGeometryMsgsVector3 *message, + ProtobufCAllocator *allocator) +{ + if(!message) + return; + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__vector3__descriptor); + protobuf_c_message_free_unpacked ((ProtobufCMessage*)message, allocator); +} +void racs2_bridge_geometry_msgs__twist__init + (RACS2BridgeGeometryMsgsTwist *message) +{ + static const RACS2BridgeGeometryMsgsTwist init_value = RACS2_BRIDGE_GEOMETRY_MSGS__TWIST__INIT; + *message = init_value; +} +size_t racs2_bridge_geometry_msgs__twist__get_packed_size + (const RACS2BridgeGeometryMsgsTwist *message) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__twist__descriptor); + return protobuf_c_message_get_packed_size ((const ProtobufCMessage*)(message)); +} +size_t racs2_bridge_geometry_msgs__twist__pack + (const RACS2BridgeGeometryMsgsTwist *message, + uint8_t *out) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__twist__descriptor); + return protobuf_c_message_pack ((const ProtobufCMessage*)message, out); +} +size_t racs2_bridge_geometry_msgs__twist__pack_to_buffer + (const RACS2BridgeGeometryMsgsTwist *message, + ProtobufCBuffer *buffer) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__twist__descriptor); + return protobuf_c_message_pack_to_buffer ((const ProtobufCMessage*)message, buffer); +} +RACS2BridgeGeometryMsgsTwist * + racs2_bridge_geometry_msgs__twist__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data) +{ + return (RACS2BridgeGeometryMsgsTwist *) + protobuf_c_message_unpack (&racs2_bridge_geometry_msgs__twist__descriptor, + allocator, len, data); +} +void racs2_bridge_geometry_msgs__twist__free_unpacked + (RACS2BridgeGeometryMsgsTwist *message, + ProtobufCAllocator *allocator) +{ + if(!message) + return; + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__twist__descriptor); + protobuf_c_message_free_unpacked ((ProtobufCMessage*)message, allocator); +} +void racs2_bridge_geometry_msgs__init + (RACS2BridgeGeometryMsgs *message) +{ + static const RACS2BridgeGeometryMsgs init_value = RACS2_BRIDGE_GEOMETRY_MSGS__INIT; + *message = init_value; +} +size_t racs2_bridge_geometry_msgs__get_packed_size + (const RACS2BridgeGeometryMsgs *message) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__descriptor); + return protobuf_c_message_get_packed_size ((const ProtobufCMessage*)(message)); +} +size_t racs2_bridge_geometry_msgs__pack + (const RACS2BridgeGeometryMsgs *message, + uint8_t *out) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__descriptor); + return protobuf_c_message_pack ((const ProtobufCMessage*)message, out); +} +size_t racs2_bridge_geometry_msgs__pack_to_buffer + (const RACS2BridgeGeometryMsgs *message, + ProtobufCBuffer *buffer) +{ + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__descriptor); + return protobuf_c_message_pack_to_buffer ((const ProtobufCMessage*)message, buffer); +} +RACS2BridgeGeometryMsgs * + racs2_bridge_geometry_msgs__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data) +{ + return (RACS2BridgeGeometryMsgs *) + protobuf_c_message_unpack (&racs2_bridge_geometry_msgs__descriptor, + allocator, len, data); +} +void racs2_bridge_geometry_msgs__free_unpacked + (RACS2BridgeGeometryMsgs *message, + ProtobufCAllocator *allocator) +{ + if(!message) + return; + assert(message->base.descriptor == &racs2_bridge_geometry_msgs__descriptor); + protobuf_c_message_free_unpacked ((ProtobufCMessage*)message, allocator); +} +static const ProtobufCFieldDescriptor racs2_bridge_geometry_msgs__vector3__field_descriptors[3] = +{ + { + "x", + 1, + PROTOBUF_C_LABEL_REQUIRED, + PROTOBUF_C_TYPE_DOUBLE, + 0, /* quantifier_offset */ + offsetof(RACS2BridgeGeometryMsgsVector3, x), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "y", + 2, + PROTOBUF_C_LABEL_REQUIRED, + PROTOBUF_C_TYPE_DOUBLE, + 0, /* quantifier_offset */ + offsetof(RACS2BridgeGeometryMsgsVector3, y), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "z", + 3, + PROTOBUF_C_LABEL_REQUIRED, + PROTOBUF_C_TYPE_DOUBLE, + 0, /* quantifier_offset */ + offsetof(RACS2BridgeGeometryMsgsVector3, z), + NULL, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, +}; +static const unsigned racs2_bridge_geometry_msgs__vector3__field_indices_by_name[] = { + 0, /* field[0] = x */ + 1, /* field[1] = y */ + 2, /* field[2] = z */ +}; +static const ProtobufCIntRange racs2_bridge_geometry_msgs__vector3__number_ranges[1 + 1] = +{ + { 1, 0 }, + { 0, 3 } +}; +const ProtobufCMessageDescriptor racs2_bridge_geometry_msgs__vector3__descriptor = +{ + PROTOBUF_C__MESSAGE_DESCRIPTOR_MAGIC, + "RACS2Bridge_geometry_msgs_Vector3", + "RACS2BridgeGeometryMsgsVector3", + "RACS2BridgeGeometryMsgsVector3", + "", + sizeof(RACS2BridgeGeometryMsgsVector3), + 3, + racs2_bridge_geometry_msgs__vector3__field_descriptors, + racs2_bridge_geometry_msgs__vector3__field_indices_by_name, + 1, racs2_bridge_geometry_msgs__vector3__number_ranges, + (ProtobufCMessageInit) racs2_bridge_geometry_msgs__vector3__init, + NULL,NULL,NULL /* reserved[123] */ +}; +static const ProtobufCFieldDescriptor racs2_bridge_geometry_msgs__twist__field_descriptors[2] = +{ + { + "linear", + 1, + PROTOBUF_C_LABEL_REQUIRED, + PROTOBUF_C_TYPE_MESSAGE, + 0, /* quantifier_offset */ + offsetof(RACS2BridgeGeometryMsgsTwist, linear), + &racs2_bridge_geometry_msgs__vector3__descriptor, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "angular", + 2, + PROTOBUF_C_LABEL_REQUIRED, + PROTOBUF_C_TYPE_MESSAGE, + 0, /* quantifier_offset */ + offsetof(RACS2BridgeGeometryMsgsTwist, angular), + &racs2_bridge_geometry_msgs__vector3__descriptor, + NULL, + 0, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, +}; +static const unsigned racs2_bridge_geometry_msgs__twist__field_indices_by_name[] = { + 1, /* field[1] = angular */ + 0, /* field[0] = linear */ +}; +static const ProtobufCIntRange racs2_bridge_geometry_msgs__twist__number_ranges[1 + 1] = +{ + { 1, 0 }, + { 0, 2 } +}; +const ProtobufCMessageDescriptor racs2_bridge_geometry_msgs__twist__descriptor = +{ + PROTOBUF_C__MESSAGE_DESCRIPTOR_MAGIC, + "RACS2Bridge_geometry_msgs_Twist", + "RACS2BridgeGeometryMsgsTwist", + "RACS2BridgeGeometryMsgsTwist", + "", + sizeof(RACS2BridgeGeometryMsgsTwist), + 2, + racs2_bridge_geometry_msgs__twist__field_descriptors, + racs2_bridge_geometry_msgs__twist__field_indices_by_name, + 1, racs2_bridge_geometry_msgs__twist__number_ranges, + (ProtobufCMessageInit) racs2_bridge_geometry_msgs__twist__init, + NULL,NULL,NULL /* reserved[123] */ +}; +static const ProtobufCFieldDescriptor racs2_bridge_geometry_msgs__field_descriptors[26] = +{ + { + "accel_with_covariance_data", + 1, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_accel_with_covariance_data), + offsetof(RACS2BridgeGeometryMsgs, accel_with_covariance_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "accel_with_covariance_stamped_data", + 2, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_accel_with_covariance_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, accel_with_covariance_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "point_stamped_data", + 3, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_point_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, point_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "inertia_stamped_data", + 4, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_inertia_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, inertia_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "quaternion_stamped_data", + 5, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_quaternion_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, quaternion_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "transform_stamped_data", + 6, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_transform_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, transform_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "inertia_data", + 7, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_inertia_data), + offsetof(RACS2BridgeGeometryMsgs, inertia_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "pose_with_covariance_data", + 8, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_pose_with_covariance_data), + offsetof(RACS2BridgeGeometryMsgs, pose_with_covariance_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "twist_covariance_stamped_data", + 9, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_twist_covariance_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, twist_covariance_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "wrench_data", + 10, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_wrench_data), + offsetof(RACS2BridgeGeometryMsgs, wrench_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "accel_data", + 11, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_accel_data), + offsetof(RACS2BridgeGeometryMsgs, accel_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "pose_with_covariance_stamped_data", + 12, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_pose_with_covariance_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, pose_with_covariance_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "accele_stamped_data", + 13, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_accele_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, accele_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "transform_data", + 14, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_transform_data), + offsetof(RACS2BridgeGeometryMsgs, transform_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "point_data", + 15, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_point_data), + offsetof(RACS2BridgeGeometryMsgs, point_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "polygon_stamped_dta", + 16, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_polygon_stamped_dta), + offsetof(RACS2BridgeGeometryMsgs, polygon_stamped_dta), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "pose_array_data", + 17, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_pose_array_data), + offsetof(RACS2BridgeGeometryMsgs, pose_array_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "vector3_stamped_data", + 18, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_vector3_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, vector3_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "pose_stamped_data", + 19, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_pose_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, pose_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "polygon_data", + 20, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_polygon_data), + offsetof(RACS2BridgeGeometryMsgs, polygon_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "queaternion_data", + 21, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_queaternion_data), + offsetof(RACS2BridgeGeometryMsgs, queaternion_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "point32_data", + 22, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_point32_data), + offsetof(RACS2BridgeGeometryMsgs, point32_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "twist_with_covariance_data", + 23, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_twist_with_covariance_data), + offsetof(RACS2BridgeGeometryMsgs, twist_with_covariance_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "pose_data", + 24, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_pose_data), + offsetof(RACS2BridgeGeometryMsgs, pose_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "twist_stamped_data", + 25, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_twist_stamped_data), + offsetof(RACS2BridgeGeometryMsgs, twist_stamped_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, + { + "pose_2d_data", + 26, + PROTOBUF_C_LABEL_REPEATED, + PROTOBUF_C_TYPE_FLOAT, + offsetof(RACS2BridgeGeometryMsgs, n_pose_2d_data), + offsetof(RACS2BridgeGeometryMsgs, pose_2d_data), + NULL, + NULL, + 0 | PROTOBUF_C_FIELD_FLAG_PACKED, /* flags */ + 0,NULL,NULL /* reserved1,reserved2, etc */ + }, +}; +static const unsigned racs2_bridge_geometry_msgs__field_indices_by_name[] = { + 10, /* field[10] = accel_data */ + 0, /* field[0] = accel_with_covariance_data */ + 1, /* field[1] = accel_with_covariance_stamped_data */ + 12, /* field[12] = accele_stamped_data */ + 6, /* field[6] = inertia_data */ + 3, /* field[3] = inertia_stamped_data */ + 21, /* field[21] = point32_data */ + 14, /* field[14] = point_data */ + 2, /* field[2] = point_stamped_data */ + 19, /* field[19] = polygon_data */ + 15, /* field[15] = polygon_stamped_dta */ + 25, /* field[25] = pose_2d_data */ + 16, /* field[16] = pose_array_data */ + 23, /* field[23] = pose_data */ + 18, /* field[18] = pose_stamped_data */ + 7, /* field[7] = pose_with_covariance_data */ + 11, /* field[11] = pose_with_covariance_stamped_data */ + 4, /* field[4] = quaternion_stamped_data */ + 20, /* field[20] = queaternion_data */ + 13, /* field[13] = transform_data */ + 5, /* field[5] = transform_stamped_data */ + 8, /* field[8] = twist_covariance_stamped_data */ + 24, /* field[24] = twist_stamped_data */ + 22, /* field[22] = twist_with_covariance_data */ + 17, /* field[17] = vector3_stamped_data */ + 9, /* field[9] = wrench_data */ +}; +static const ProtobufCIntRange racs2_bridge_geometry_msgs__number_ranges[1 + 1] = +{ + { 1, 0 }, + { 0, 26 } +}; +const ProtobufCMessageDescriptor racs2_bridge_geometry_msgs__descriptor = +{ + PROTOBUF_C__MESSAGE_DESCRIPTOR_MAGIC, + "RACS2Bridge_geometry_msgs", + "RACS2BridgeGeometryMsgs", + "RACS2BridgeGeometryMsgs", + "", + sizeof(RACS2BridgeGeometryMsgs), + 26, + racs2_bridge_geometry_msgs__field_descriptors, + racs2_bridge_geometry_msgs__field_indices_by_name, + 1, racs2_bridge_geometry_msgs__number_ranges, + (ProtobufCMessageInit) racs2_bridge_geometry_msgs__init, + NULL,NULL,NULL /* reserved[123] */ +}; diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.h new file mode 100644 index 0000000..f069dba --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/RACS2Bridge_geometry_msgs.pb-c.h @@ -0,0 +1,277 @@ +/* Generated by the protocol buffer compiler. DO NOT EDIT! */ +/* Generated from: RACS2Bridge_geometry_msgs.proto */ + +#ifndef PROTOBUF_C_RACS2Bridge_5fgeometry_5fmsgs_2eproto__INCLUDED +#define PROTOBUF_C_RACS2Bridge_5fgeometry_5fmsgs_2eproto__INCLUDED + +#include + +PROTOBUF_C__BEGIN_DECLS + +#if PROTOBUF_C_VERSION_NUMBER < 1000000 +# error This file was generated by a newer version of protoc-c which is incompatible with your libprotobuf-c headers. Please update your headers. +#elif 1003003 < PROTOBUF_C_MIN_COMPILER_VERSION +# error This file was generated by an older version of protoc-c which is incompatible with your libprotobuf-c headers. Please regenerate this file with a newer version of protoc-c. +#endif + + +typedef struct _RACS2BridgeGeometryMsgsVector3 RACS2BridgeGeometryMsgsVector3; +typedef struct _RACS2BridgeGeometryMsgsTwist RACS2BridgeGeometryMsgsTwist; +typedef struct _RACS2BridgeGeometryMsgs RACS2BridgeGeometryMsgs; + + +/* --- enums --- */ + + +/* --- messages --- */ + +struct _RACS2BridgeGeometryMsgsVector3 +{ + ProtobufCMessage base; + /* + * -- geometry_msgs/Vector3 ---------------------------- + */ + double x; + double y; + double z; +}; +#define RACS2_BRIDGE_GEOMETRY_MSGS__VECTOR3__INIT \ + { PROTOBUF_C_MESSAGE_INIT (&racs2_bridge_geometry_msgs__vector3__descriptor) \ + , 0, 0, 0 } + + +struct _RACS2BridgeGeometryMsgsTwist +{ + ProtobufCMessage base; + /* + * -- geometry_msgs/Twist ------------------------------ + */ + RACS2BridgeGeometryMsgsVector3 *linear; + RACS2BridgeGeometryMsgsVector3 *angular; +}; +#define RACS2_BRIDGE_GEOMETRY_MSGS__TWIST__INIT \ + { PROTOBUF_C_MESSAGE_INIT (&racs2_bridge_geometry_msgs__twist__descriptor) \ + , NULL, NULL } + + +struct _RACS2BridgeGeometryMsgs +{ + ProtobufCMessage base; + /* + * -- geometry_msgs/AccelWithCovariance ---------------- + */ + size_t n_accel_with_covariance_data; + float *accel_with_covariance_data; + /* + * -- geometry_msgs/AccelWithCovarianceStamped --------- + */ + size_t n_accel_with_covariance_stamped_data; + float *accel_with_covariance_stamped_data; + /* + * -- geometry_msgs/PointStamped ----------------------- + */ + size_t n_point_stamped_data; + float *point_stamped_data; + /* + * -- geometry_msgs/InertiaStamped --------------------- + */ + size_t n_inertia_stamped_data; + float *inertia_stamped_data; + /* + * -- geometry_msgs/QuaternionStamped ------------------ + */ + size_t n_quaternion_stamped_data; + float *quaternion_stamped_data; + /* + * -- geometry_msgs/TransformStamped ------------------- + */ + size_t n_transform_stamped_data; + float *transform_stamped_data; + /* + * -- geometry_msgs/Inertia ---------------------------- + */ + size_t n_inertia_data; + float *inertia_data; + /* + * -- geometry_msgs/PoseWithCovariance ----------------- + */ + size_t n_pose_with_covariance_data; + float *pose_with_covariance_data; + /* + * -- geometry_msgs/TwistWithCovarianceStamped --------- + */ + size_t n_twist_covariance_stamped_data; + float *twist_covariance_stamped_data; + /* + * -- geometry_msgs/Wrench ----------------------------- + */ + size_t n_wrench_data; + float *wrench_data; + /* + * -- geometry_msgs/Accel ------------------------------ + */ + size_t n_accel_data; + float *accel_data; + /* + * -- geometry_msgs/PoseWithCovarianceStamped ---------- + */ + size_t n_pose_with_covariance_stamped_data; + float *pose_with_covariance_stamped_data; + /* + * -- geometry_msgs/AccelStamped ----------------------- + */ + size_t n_accele_stamped_data; + float *accele_stamped_data; + /* + * -- geometry_msgs/Transform -------------------------- + */ + size_t n_transform_data; + float *transform_data; + /* + * -- geometry_msgs/Point ------------------------------ + */ + size_t n_point_data; + float *point_data; + /* + * -- geometry_msgs/PolygonStamped --------------------- + */ + size_t n_polygon_stamped_dta; + float *polygon_stamped_dta; + /* + * -- geometry_msgs/PoseArray -------------------------- + */ + size_t n_pose_array_data; + float *pose_array_data; + /* + * -- geometry_msgs/Vector3Stamped --------------------- + */ + size_t n_vector3_stamped_data; + float *vector3_stamped_data; + /* + * -- geometry_msgs/PoseStamped ------------------------ + */ + size_t n_pose_stamped_data; + float *pose_stamped_data; + /* + * -- geometry_msgs/Polygon ---------------------------- + */ + size_t n_polygon_data; + float *polygon_data; + /* + * -- geometry_msgs/Quaternion ------------------------- + */ + size_t n_queaternion_data; + float *queaternion_data; + /* + * -- geometry_msgs/Point32 ---------------------------- + */ + size_t n_point32_data; + float *point32_data; + /* + * -- geometry_msgs/TwistWithCovariance ---------------- + */ + size_t n_twist_with_covariance_data; + float *twist_with_covariance_data; + /* + * -- geometry_msgs/Pose ------------------------------- + */ + size_t n_pose_data; + float *pose_data; + /* + * -- geometry_msgs/TwistStamped ----------------------- + */ + size_t n_twist_stamped_data; + float *twist_stamped_data; + /* + * -- geometry_msgs/Pose2D ----------------------------- + */ + size_t n_pose_2d_data; + float *pose_2d_data; +}; +#define RACS2_BRIDGE_GEOMETRY_MSGS__INIT \ + { PROTOBUF_C_MESSAGE_INIT (&racs2_bridge_geometry_msgs__descriptor) \ + , 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL, 0,NULL } + + +/* RACS2BridgeGeometryMsgsVector3 methods */ +void racs2_bridge_geometry_msgs__vector3__init + (RACS2BridgeGeometryMsgsVector3 *message); +size_t racs2_bridge_geometry_msgs__vector3__get_packed_size + (const RACS2BridgeGeometryMsgsVector3 *message); +size_t racs2_bridge_geometry_msgs__vector3__pack + (const RACS2BridgeGeometryMsgsVector3 *message, + uint8_t *out); +size_t racs2_bridge_geometry_msgs__vector3__pack_to_buffer + (const RACS2BridgeGeometryMsgsVector3 *message, + ProtobufCBuffer *buffer); +RACS2BridgeGeometryMsgsVector3 * + racs2_bridge_geometry_msgs__vector3__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data); +void racs2_bridge_geometry_msgs__vector3__free_unpacked + (RACS2BridgeGeometryMsgsVector3 *message, + ProtobufCAllocator *allocator); +/* RACS2BridgeGeometryMsgsTwist methods */ +void racs2_bridge_geometry_msgs__twist__init + (RACS2BridgeGeometryMsgsTwist *message); +size_t racs2_bridge_geometry_msgs__twist__get_packed_size + (const RACS2BridgeGeometryMsgsTwist *message); +size_t racs2_bridge_geometry_msgs__twist__pack + (const RACS2BridgeGeometryMsgsTwist *message, + uint8_t *out); +size_t racs2_bridge_geometry_msgs__twist__pack_to_buffer + (const RACS2BridgeGeometryMsgsTwist *message, + ProtobufCBuffer *buffer); +RACS2BridgeGeometryMsgsTwist * + racs2_bridge_geometry_msgs__twist__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data); +void racs2_bridge_geometry_msgs__twist__free_unpacked + (RACS2BridgeGeometryMsgsTwist *message, + ProtobufCAllocator *allocator); +/* RACS2BridgeGeometryMsgs methods */ +void racs2_bridge_geometry_msgs__init + (RACS2BridgeGeometryMsgs *message); +size_t racs2_bridge_geometry_msgs__get_packed_size + (const RACS2BridgeGeometryMsgs *message); +size_t racs2_bridge_geometry_msgs__pack + (const RACS2BridgeGeometryMsgs *message, + uint8_t *out); +size_t racs2_bridge_geometry_msgs__pack_to_buffer + (const RACS2BridgeGeometryMsgs *message, + ProtobufCBuffer *buffer); +RACS2BridgeGeometryMsgs * + racs2_bridge_geometry_msgs__unpack + (ProtobufCAllocator *allocator, + size_t len, + const uint8_t *data); +void racs2_bridge_geometry_msgs__free_unpacked + (RACS2BridgeGeometryMsgs *message, + ProtobufCAllocator *allocator); +/* --- per-message closures --- */ + +typedef void (*RACS2BridgeGeometryMsgsVector3_Closure) + (const RACS2BridgeGeometryMsgsVector3 *message, + void *closure_data); +typedef void (*RACS2BridgeGeometryMsgsTwist_Closure) + (const RACS2BridgeGeometryMsgsTwist *message, + void *closure_data); +typedef void (*RACS2BridgeGeometryMsgs_Closure) + (const RACS2BridgeGeometryMsgs *message, + void *closure_data); + +/* --- services --- */ + + +/* --- descriptors --- */ + +extern const ProtobufCMessageDescriptor racs2_bridge_geometry_msgs__vector3__descriptor; +extern const ProtobufCMessageDescriptor racs2_bridge_geometry_msgs__twist__descriptor; +extern const ProtobufCMessageDescriptor racs2_bridge_geometry_msgs__descriptor; + +PROTOBUF_C__END_DECLS + + +#endif /* PROTOBUF_C_RACS2Bridge_5fgeometry_5fmsgs_2eproto__INCLUDED */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/racs2_user_msg.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/racs2_user_msg.h new file mode 100644 index 0000000..84dc66a --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/racs2_user_msg.h @@ -0,0 +1,22 @@ +#ifndef _racs2_user_msg_h_ +#define _racs2_user_msg_h_ + +/* +** Type definition (user data format for racs2 bridge) +*/ +#define ROS2_TOPIC_NAME_LNGTH 32 +#define BODY_DATA_MAX_LNGTH 128 + +typedef struct +{ + uint8 TlmHeader[CFE_SB_TLM_HDR_SIZE]; + char ros2_topic_name[ROS2_TOPIC_NAME_LNGTH]; + uint8 body_data_length; + uint8 body_data[BODY_DATA_MAX_LNGTH]; + +} OS_PACK racs2_user_msg_t ; + +#define RACS2_USER_MSG_LNGTH sizeof ( racs2_user_msg_t ) +#define RACS2_BRIDGE_USER_LISTENER_LNGTH sizeof ( racs2_user_msg_t ) + +#endif /* _racs2_user_msg_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.c b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.c new file mode 100644 index 0000000..3b87cd9 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.c @@ -0,0 +1,436 @@ +/* +** Include Files: +*/ + +#include "run_app.h" +#include "run_app_perfids.h" +#include "run_app_msgids.h" +#include "run_app_msg.h" +#include "racs2_user_msg.h" +#include "run_app_events.h" +#include "run_app_version.h" +#include "RACS2Bridge_geometry_msgs.pb-c.h" + +#include +#include +#include +#include +#include +#include + +/* +** global data +*/ + +sample_hk_tlm_t RUN_APP_HkTelemetryPkt; +racs2_user_msg_t RACS2_UserMsgPkt; +CFE_SB_PipeId_t RUN_APP_CommandPipe; +CFE_SB_MsgPtr_t RUN_APP_MsgPtr; + +typedef enum { + FORWARD, + BACKWARD, + TURN_RIGHT, + TURN_LEFT, + STOP +} Command; + +Command current_command = STOP; +struct termios original_termios; + +double twist_linear_x = 0.0; +double twist_linear_y = 0.0; +double twist_linear_z = 0.0; +double twist_angular_x = 0.0; +double twist_angular_y = 0.0; +double twist_angular_z = 0.0; + +static CFE_EVS_BinFilter_t SAMPLE_EventFilters[] = + { /* Event ID mask */ + {SAMPLE_STARTUP_INF_EID, 0x0000}, + {SAMPLE_COMMAND_ERR_EID, 0x0000}, + {SAMPLE_COMMANDNOP_INF_EID, 0x0000}, + {SAMPLE_COMMANDRST_INF_EID, 0x0000}, + }; + + +void send_command(Command cmd) { + switch (cmd) { + case FORWARD: + printf("Moving Forward\n"); + twist_linear_x = 2.0; + break; + case BACKWARD: + printf("Moving Backward\n"); + twist_linear_x = -2.0; + break; + case TURN_RIGHT: + printf("Turning Right\n"); + twist_linear_x = 1.0; + twist_angular_z = -0.4; + break; + case TURN_LEFT: + printf("Turning Left\n"); + twist_linear_x = 1.0; + twist_angular_z = 0.4; + break; + case STOP: + printf("Stopping\n"); + twist_linear_x = 0.0; + twist_linear_y = 0.0; + twist_linear_z = 0.0; + twist_angular_x = 0.0; + twist_angular_y = 0.0; + twist_angular_z = 0.0; + break; + } +} + +void process_input(char input) { + switch (input) { + case 'w': + current_command = FORWARD; + printf("###### Moving Forward ###### \n"); + twist_linear_x = 2.0; + break; + case 's': + current_command = BACKWARD; + printf("###### Moving Backward ###### \n"); + twist_linear_x = -2.0; + break; + case 'd': + current_command = TURN_RIGHT; + printf("###### Turning Right ###### \n"); + twist_linear_x = 1.0; + twist_angular_z = -0.4; + break; + case 'a': + current_command = TURN_LEFT; + printf("###### Turning Left ###### \n"); + twist_linear_x = 1.0; + twist_angular_z = 0.4; + break; + case 'x': + current_command = STOP; + printf("###### Stopping ###### \n"); + twist_linear_x = 0.0; + twist_linear_y = 0.0; + twist_linear_z = 0.0; + twist_angular_x = 0.0; + twist_angular_y = 0.0; + twist_angular_z = 0.0; + break; + default: + printf("!!!!! Invalid input !!!!! \n"); + return; + } +} + +void set_non_canonical_mode(int fd) { + struct termios termios; + + // 現在の端末設定を取得 + tcgetattr(fd, &original_termios); + + // 設定を変更 + termios = original_termios; + termios.c_lflag &= ~(ICANON | ECHO); // 非カノニカルモード、エコーを無効にする + + // 変更を適用 + tcsetattr(fd, TCSANOW, &termios); +} + +void restore_canonical_mode(int fd) { + tcsetattr(fd, TCSANOW, &original_termios); +} + +void signal_handler(int signum) { + // 端末設定を元に戻す + restore_canonical_mode(fileno(stdin)); + printf("\nTerminating program.\n"); + exit(0); +} + + +/** * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ +/* RUN_APP_Main() -- Application entry point and main process loop */ +/* */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +void RUN_APP_Main( void ) +{ + int32 status; + uint32 RunStatus = CFE_ES_RunStatus_APP_RUN; + + OS_printf("RUN_APP_Main starts.\n"); + + CFE_ES_PerfLogEntry(SAMPLE_APP_PERF_ID); + + SAMPLE_TAKLKER_Init(); + + struct termios original_termios; + char input; + signal(SIGINT, signal_handler); + + /* + ** RUN_APP Runloop + */ + + int fd = fileno(stdin); + set_non_canonical_mode(fd); + + int count = 0; + while (CFE_ES_RunLoop(&RunStatus) == true) + { + if (read(fd, &input, 1) == 1) { + process_input(input); + } + + CFE_ES_PerfLogExit(SAMPLE_APP_PERF_ID); + + // /* Pend on receipt of command packet -- timeout set to 500 millisecs */ + // status = CFE_SB_RcvMsg(&RUN_APP_MsgPtr, RUN_APP_CommandPipe, 500); + + CFE_ES_PerfLogEntry(SAMPLE_APP_PERF_ID); + + // if (status == CFE_SUCCESS) + // { + // RUN_APP_ProcessCommandPacket(); + // } + sleep(2); + + // send message + // set topic name + strcpy(RACS2_UserMsgPkt.ros2_topic_name, "/cmd_vel"); + // define serialized body data + uint8_t *buffer; + + RACS2BridgeGeometryMsgsVector3 linear = RACS2_BRIDGE_GEOMETRY_MSGS__VECTOR3__INIT; + RACS2BridgeGeometryMsgsVector3 angular = RACS2_BRIDGE_GEOMETRY_MSGS__VECTOR3__INIT; + RACS2BridgeGeometryMsgsTwist message = RACS2_BRIDGE_GEOMETRY_MSGS__TWIST__INIT; + + message.linear = &linear; + message.angular = &angular; + message.linear->x = twist_linear_x; + message.linear->y = twist_linear_y; + message.linear->z = twist_linear_z; + message.angular->x = twist_angular_x; + message.angular->y = twist_angular_y; + message.angular->z = twist_angular_z; + // message.linear->x = 2.0; + // message.linear->y = 0.0; + // message.linear->z = 0.0; + // message.angular->x = 0.0; + // message.angular->y = 0.0; + // message.angular->z = 0.0; + + OS_printf("RUN_APP: [Send][MsgID=0x%x][linear: x = %5.2f, y = %5.2f, z = %5.2f][angular: x = %5.2f, y = %5.2f, z = %5.2f]\n", + RACS2_BRIDGE_MID, + message.linear->x, + message.linear->y, + message.linear->z, + message.angular->x, + message.angular->y, + message.angular->z + ); + + size_t len = protobuf_c_message_get_packed_size((const ProtobufCMessage *) &message); + buffer=malloc(len); + size_t packed_len = protobuf_c_message_pack((const ProtobufCMessage *)&message, buffer); + + // set body data + memcpy(RACS2_UserMsgPkt.body_data, buffer, len); + // set body data length + RACS2_UserMsgPkt.body_data_length = len; + + // send data + CFE_SB_TimeStampMsg((CFE_SB_Msg_t *) &RACS2_UserMsgPkt); + status = CFE_SB_SendMsg((CFE_SB_Msg_t *) &RACS2_UserMsgPkt); + // OS_printf("RUN_APP: Sent message, MID = [0x%x], sample_command_count = %d\n", + // CFE_SB_GetMsgId((CFE_SB_MsgPtr_t) &RACS2_UserMsgPkt), + // RACS2_UserMsgPkt.sample_command_count + // ); + if (status != CFE_SUCCESS) { + OS_printf("RUN_APP: Error: sending is failed. status = 0x%x\n", status); + } + + free(buffer); + + count++; + } + + CFE_ES_ExitApp(RunStatus); + +} /* End of RUN_APP_Main() */ + +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ +/* */ +/* SAMPLE_TAKLKER_Init() -- initialization */ +/* */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +void SAMPLE_TAKLKER_Init(void) +{ + /* + ** Register the app with Executive services + */ + CFE_ES_RegisterApp() ; + + /* + ** Register the events + */ + CFE_EVS_Register(SAMPLE_EventFilters, + sizeof(SAMPLE_EventFilters)/sizeof(CFE_EVS_BinFilter_t), + CFE_EVS_EventFilter_BINARY); + + RUN_APP_ResetCounters(); + + CFE_SB_InitMsg(&RUN_APP_HkTelemetryPkt, + RUN_APP_HK_TLM_MID, + SAMPLE_APP_HK_TLM_LNGTH, true); + + CFE_SB_InitMsg(&RACS2_UserMsgPkt, RACS2_BRIDGE_MID, RACS2_USER_MSG_LNGTH, false); + + CFE_EVS_SendEvent (SAMPLE_STARTUP_INF_EID, CFE_EVS_EventType_INFORMATION, + "RUN_APP App Initialized. Version %d.%d.%d.%d", + SAMPLE_APP_MAJOR_VERSION, + SAMPLE_APP_MINOR_VERSION, + SAMPLE_APP_REVISION, + SAMPLE_APP_MISSION_REV); + +} /* End of SAMPLE_TAKLKER_Init() */ + +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +/* Name: RUN_APP_ProcessCommandPacket */ +/* */ +/* Purpose: */ +/* This routine will process any packet that is received on the RUN_APP */ +/* command pipe. */ +/* */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ +void RUN_APP_ProcessCommandPacket(void) +{ + CFE_SB_MsgId_t MsgId; + + MsgId = CFE_SB_GetMsgId(RUN_APP_MsgPtr); + + switch (MsgId) + { + case RUN_APP_CMD_MID: + RUN_APP_ProcessGroundCommand(); + break; + + case RUN_APP_SEND_HK_MID: + RUN_APP_ReportHousekeeping(); + break; + + default: + RUN_APP_HkTelemetryPkt.sample_command_error_count++; + CFE_EVS_SendEvent(SAMPLE_COMMAND_ERR_EID,CFE_EVS_EventType_ERROR, + "RUN_APP: invalid command packet,MID = 0x%x", MsgId); + break; + } + + return; + +} /* End RUN_APP_ProcessCommandPacket */ + +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +/* */ +/* RUN_APP_ProcessGroundCommand() -- RUN_APP ground commands */ +/* */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ + +void RUN_APP_ProcessGroundCommand(void) +{ + uint16 CommandCode; + + CommandCode = CFE_SB_GetCmdCode(RUN_APP_MsgPtr); + + /* Process "known" RUN_APP app ground commands */ + switch (CommandCode) + { + case SAMPLE_APP_NOOP_CC: + RUN_APP_HkTelemetryPkt.sample_command_count++; + CFE_EVS_SendEvent(SAMPLE_COMMANDNOP_INF_EID, + CFE_EVS_EventType_INFORMATION, + "RUN_APP: NOOP command"); + break; + + case SAMPLE_APP_RESET_COUNTERS_CC: + RUN_APP_ResetCounters(); + break; + + /* default case already found during FC vs length test */ + default: + break; + } + return; + +} /* End of RUN_APP_ProcessGroundCommand() */ + +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +/* Name: RUN_APP_ReportHousekeeping */ +/* */ +/* Purpose: */ +/* This function is triggered in response to a task telemetry request */ +/* from the housekeeping task. This function will gather the Apps */ +/* telemetry, packetize it and send it to the housekeeping task via */ +/* the software bus */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ +void RUN_APP_ReportHousekeeping(void) +{ + CFE_SB_TimeStampMsg((CFE_SB_Msg_t *) &RUN_APP_HkTelemetryPkt); + CFE_SB_SendMsg((CFE_SB_Msg_t *) &RUN_APP_HkTelemetryPkt); + return; + +} /* End of RUN_APP_ReportHousekeeping() */ + +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +/* Name: RUN_APP_ResetCounters */ +/* */ +/* Purpose: */ +/* This function resets all the global counter variables that are */ +/* part of the task telemetry. */ +/* */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */ +void RUN_APP_ResetCounters(void) +{ + /* Status of commands processed by the RUN_APP App */ + RUN_APP_HkTelemetryPkt.sample_command_count = 0; + RUN_APP_HkTelemetryPkt.sample_command_error_count = 0; + + CFE_EVS_SendEvent(SAMPLE_COMMANDRST_INF_EID, CFE_EVS_EventType_INFORMATION, + "RUN_APP: RESET command"); + return; + +} /* End of RUN_APP_ResetCounters() */ + +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +/* */ +/* RUN_APP_VerifyCmdLength() -- Verify command packet length */ +/* */ +/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * **/ +bool RUN_APP_VerifyCmdLength(CFE_SB_MsgPtr_t msg, uint16 ExpectedLength) +{ + bool result = true; + + uint16 ActualLength = CFE_SB_GetTotalMsgLength(msg); + + /* + ** Verify the command packet length. + */ + if (ExpectedLength != ActualLength) + { + CFE_SB_MsgId_t MessageID = CFE_SB_GetMsgId(msg); + uint16 CommandCode = CFE_SB_GetCmdCode(msg); + + CFE_EVS_SendEvent(SAMPLE_LEN_ERR_EID, CFE_EVS_EventType_ERROR, + "Invalid msg length: ID = 0x%X, CC = %d, Len = %d, Expected = %d", + MessageID, CommandCode, ActualLength, ExpectedLength); + result = false; + RUN_APP_HkTelemetryPkt.sample_command_error_count++; + } + + return(result); + +} /* End of RUN_APP_VerifyCmdLength() */ + diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.h new file mode 100644 index 0000000..481095d --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app.h @@ -0,0 +1,41 @@ +#ifndef _run_app_h_ +#define _run_app_h_ + +/* +** Required header files. +*/ +#include "cfe.h" +#include "cfe_error.h" +#include "cfe_evs.h" +#include "cfe_sb.h" +#include "cfe_es.h" + +#include +#include +#include + +/***********************************************************************/ + +#define SAMPLE_PIPE_DEPTH 32 + +/************************************************************************ +** Type Definitions +*************************************************************************/ + +/****************************************************************************/ +/* +** Local function prototypes. +** +** Note: Except for the entry point (RUN_APP_Main), these +** functions are not called from any other source module. +*/ +void RUN_APP_Main(void); +void SAMPLE_TAKLKER_Init(void); +void RUN_APP_ProcessCommandPacket(void); +void RUN_APP_ProcessGroundCommand(void); +void RUN_APP_ReportHousekeeping(void); +void RUN_APP_ResetCounters(void); + +bool RUN_APP_VerifyCmdLength(CFE_SB_MsgPtr_t msg, uint16 ExpectedLength); + +#endif /* _run_app_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_events.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_events.h new file mode 100644 index 0000000..5e324d1 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_events.h @@ -0,0 +1,13 @@ +#ifndef _run_app_events_h_ +#define _run_app_events_h_ + + +#define SAMPLE_RESERVED_EID 20 +#define SAMPLE_STARTUP_INF_EID 21 +#define SAMPLE_COMMAND_ERR_EID 22 +#define SAMPLE_COMMANDNOP_INF_EID 23 +#define SAMPLE_COMMANDRST_INF_EID 24 +#define SAMPLE_INVALID_MSGID_ERR_EID 25 +#define SAMPLE_LEN_ERR_EID 26 + +#endif /* _run_app_events_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_msg.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_msg.h new file mode 100644 index 0000000..7e82b18 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_msg.h @@ -0,0 +1,36 @@ +#ifndef _run_app_msg_h_ +#define _run_app_msg_h_ + +/* +** SAMPLE App command codes +*/ +#define SAMPLE_APP_NOOP_CC 0 +#define SAMPLE_APP_RESET_COUNTERS_CC 1 + +/*************************************************************************/ +/* +** Type definition (generic "no arguments" command) +*/ +typedef struct +{ + uint8 CmdHeader[CFE_SB_CMD_HDR_SIZE]; + +} SAMPLE_NoArgsCmd_t; + +/*************************************************************************/ +/* +** Type definition (SAMPLE App housekeeping) +*/ +typedef struct +{ + uint8 TlmHeader[CFE_SB_TLM_HDR_SIZE]; + uint8 sample_command_error_count; + uint8 sample_command_count; + uint8 spare[2]; + +} OS_PACK sample_hk_tlm_t ; + +#define SAMPLE_APP_HK_TLM_LNGTH sizeof ( sample_hk_tlm_t ) +#define RUN_APP_LISTENER_LNGTH sizeof ( sample_hk_tlm_t ) + +#endif /* _run_app_msg_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_version.h b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_version.h new file mode 100644 index 0000000..f6ea9ea --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/apps/run_app/fsw/src/run_app_version.h @@ -0,0 +1,9 @@ +#ifndef _run_app_version_h_ +#define _run_app_version_h_ + +#define SAMPLE_APP_MAJOR_VERSION 1 +#define SAMPLE_APP_MINOR_VERSION 1 +#define SAMPLE_APP_REVISION 0 +#define SAMPLE_APP_MISSION_REV 0 + +#endif /* _run_app_version_h_ */ diff --git a/racs2_demos_on_spaceros/cFS/sample_defs/cpu1_cfe_es_startup.scr b/racs2_demos_on_spaceros/cFS/sample_defs/cpu1_cfe_es_startup.scr new file mode 100644 index 0000000..d53441a --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/sample_defs/cpu1_cfe_es_startup.scr @@ -0,0 +1,34 @@ +CFE_APP, /cf/racs2_bridge_client.so, RACS2_BRIDGE_CLIENT_Main, RACS2_BRIDGE_CLIENT, 55, 16384, 0x0, 0; +CFE_APP, /cf/run_app.so, RUN_APP_Main, RUN_APP, 57, 16384, 0x0, 0; +! +! CFE_LIB, /cf/sample_lib.so, SAMPLE_LibInit, SAMPLE_LIB, 0, 0, 0x0, 0; +! CFE_APP, /cf/racs2_bridge_client.so, RACS2_BRIDGE_CLIENT_Main, RACS2_BRIDGE_CLIENT, 55, 16384, 0x0, 0; +! CFE_APP, /cf/sample_listener.so, SAMPLE_LISTENER_Main, SAMPLE_LISTENER, 56, 16384, 0x0, 0; +! CFE_APP, /cf/ci_lab.so, CI_Lab_AppMain, CI_LAB_APP, 60, 16384, 0x0, 0; +! CFE_APP, /cf/to_lab.so, TO_Lab_AppMain, TO_LAB_APP, 70, 16384, 0x0, 0; +! CFE_APP, /cf/sch_lab.so, SCH_Lab_AppMain, SCH_LAB_APP, 80, 16384, 0x0, 0; +! +! Startup script fields: +! 1. Object Type -- CFE_APP for an Application, or CFE_LIB for a library. +! 2. Path/Filename -- This is a cFE Virtual filename, not a vxWorks device/pathname +! 3. Entry Point -- This is the "main" function for Apps. +! 4. CFE Name -- The cFE name for the the APP or Library +! 5. Priority -- This is the Priority of the App, not used for Library +! 6. Stack Size -- This is the Stack size for the App, not used for the Library +! 7. Load Address -- This is the Optional Load Address for the App or Library. Currently not implemented +! so keep it at 0x0. +! 8. Exception Action -- This is the Action the cFE should take if the App has an exception. +! 0 = Just restart the Application +! Non-Zero = Do a cFE Processor Reset +! +! Other Notes: +! 1. The software will not try to parse anything after the first '!' character it sees. That +! is the End of File marker. +! 2. Common Application file extensions: +! Linux = .so ( ci.so ) +! OS X = .bundle ( ci.bundle ) +! Cygwin = .dll ( ci.dll ) +! vxWorks = .o ( ci.o ) +! RTEMS with S-record Loader = .s3r ( ci.s3r ) +! RTEMS with CEXP Loader = .o ( ci.o ) + diff --git a/racs2_demos_on_spaceros/cFS/sample_defs/racs2_bridge_config.txt b/racs2_demos_on_spaceros/cFS/sample_defs/racs2_bridge_config.txt new file mode 100644 index 0000000..9502c84 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/sample_defs/racs2_bridge_config.txt @@ -0,0 +1,2 @@ +wss_uri=localhost +wss_port=8765 \ No newline at end of file diff --git a/racs2_demos_on_spaceros/cFS/sample_defs/targets.cmake b/racs2_demos_on_spaceros/cFS/sample_defs/targets.cmake new file mode 100644 index 0000000..12e23c7 --- /dev/null +++ b/racs2_demos_on_spaceros/cFS/sample_defs/targets.cmake @@ -0,0 +1,100 @@ +###################################################################### +# +# Master config file for cFS target boards +# +# This file indicates the architecture and configuration of the +# target boards that will run core flight software. +# +# The following variables are defined per board, where is the +# CPU number starting with 1: +# +# TGT_NAME : the user-friendly name of the cpu. Should be simple +# word with no punctuation. This MUST be specified. +# TGT_APPLIST : list of applications to build and install on the CPU. +# These are built as dynamically-loaded applications and installed +# as files in the non-volatile storage of the target, and loaded +# at runtime via the startup script or commands. +# TGT_STATIC_APPLIST : list of applications to build and statically +# link with the CFE executable. This is similar to the "APPLIST" +# except the application is built with STATIC linkage, and it is +# included directly when linking the CFE core executable itself. +# No separate application file is generated for these apps. +# TGT_STATIC_SYMLIST : list of symbols to include in the OSAL static +# symbol lookup table. Each entry is a comma-separated pair containing +# the symbol name and virtual module/app name, such as +# My_C_Function_Name,MY_APP +# The first item must be a publicly-exposed C symbol name available to +# the linker at static link time, generally the entry point/main function +# of the a module or library (see STATIC_APPLIST). The second item is the +# module name that should match the name used in the CFE startup script +# (4th parameter). +# IMPORTANT: For this to work, the OS_STATIC_LOADER configuration option +# must be specified in the osconfig.h for that CPU. +# TGT_PSP_MODULELIST : additional PSP "modules" to link into the +# CFE executable for this target. These can be device drivers or +# other bits of modular PSP functionality that provide I/O or other +# low level functions. +# TGT_FILELIST : list of extra files to copy onto the target. No +# modifications of the file will be made. In order to differentiate +# between different versions of files with the same name, priority +# will be given to a file named _ to be installed +# as simply on that cpu (prefix will be removed). These +# files are intended to be copied to the non-volatile storage on the +# target for use during runtime. +# TGT_EMBED_FILELIST : list of extra files which are to be converted +# into data arrays and linked with/embedded into the CFE executable, +# so the content of the files can be available at runtime on systems +# that do not have run time non-volatile storage. The format of each +# list entry is a comma-separated pair of variable and file name: +# VARIABLE_NAME,FILE_NAME +# The binary contents of the file will subsequently be available as: +# extern const char VARIABLE_NAME_DATA[] and +# extern const unsigned long VARIABLE_NAME_SIZE +# The same prefix-based filename mapping as used on FILELIST is also +# employed here, allowing CPU-specific data files to be used. +# TGT_SYSTEM : the toolchain to use for building all code. This +# will map to a CMake toolchain file called "toolchain-" +# If not specified then it will default to "cpu" so that +# each CPU will have a dedicated toolchain file and no objects +# will be shared across CPUs. +# Otherwise any code built using the same toolchain may be +# copied to multiple CPUs for more efficient builds. +# TGT_PLATFORM : configuration for the CFE core to use for this +# cpu. This determines the cfe_platform_cfg.h to use during the +# build. Multiple files/components may be concatenated together +# allowing the config to be generated in a modular fashion. If +# not specified then it will be assumed as "default ". +# + +# The MISSION_NAME will be compiled into the target build data structure +# as well as being passed to "git describe" to filter the tags when building +# the version string. +SET(MISSION_NAME "SampleMission") + +# SPACECRAFT_ID gets compiled into the build data structure and the PSP may use it. +# should be an integer. +SET(SPACECRAFT_ID 42) + +# UI_INSTALL_SUBDIR indicates where the UI data files (included in some apps) should +# be copied during the install process. +SET(UI_INSTALL_SUBDIR "host/ui") + +# FT_INSTALL_SUBDIR indicates where the black box test data files (lua scripts) should +# be copied during the install process. +SET(FT_INSTALL_SUBDIR "host/functional-test") + +# Each target board can have its own HW arch selection and set of included apps +SET(TGT1_NAME cpu1) +SET(TGT1_APPLIST sample_app racs2_bridge_client run_app sample_lib ci_lab to_lab sch_lab) +SET(TGT1_FILELIST cfe_es_startup.scr racs2_bridge_config.txt) + +# CPU2/3 are duplicates of CPU1. These are not built by default anymore but are +# commented out to serve as an example of how one would configure multiple cpus. +#SET(TGT2_NAME cpu2) +#SET(TGT2_APPLIST sample_app ci_lab to_lab sch_lab) +#SET(TGT2_FILELIST cfe_es_startup.scr) + +#SET(TGT3_NAME cpu3) +#SET(TGT3_APPLIST sample_app ci_lab to_lab sch_lab) +#SET(TGT3_FILELIST cfe_es_startup.scr) + diff --git a/racs2_demos_on_spaceros/config/mars_rover_control.yaml b/racs2_demos_on_spaceros/config/mars_rover_control.yaml new file mode 100644 index 0000000..4390b1a --- /dev/null +++ b/racs2_demos_on_spaceros/config/mars_rover_control.yaml @@ -0,0 +1,116 @@ +controller_manager: + ros__parameters: + update_rate: 100 + + arm_joint_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController + + mast_joint_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController + + wheel_velocity_controller: + type: velocity_controllers/JointGroupVelocityController + + steer_position_controller: + type: joint_trajectory_controller/JointTrajectoryController + + wheel_tree_position_controller: + type: effort_controllers/JointGroupPositionController + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + +arm_joint_trajectory_controller: + ros__parameters: + joints: + - arm_01_joint + - arm_02_joint + - arm_03_joint + - arm_04_joint + - arm_tools_joint + interface_name: position + command_interfaces: + - position + state_interfaces: + - position + - velocity + +mast_joint_trajectory_controller: + ros__parameters: + joints: + - mast_p_joint + - mast_02_joint + - mast_cameras_joint + interface_name: position + command_interfaces: + - position + state_interfaces: + - position + - velocity + +wheel_velocity_controller: + ros__parameters: + joints: + - front_wheel_L_joint + - middle_wheel_L_joint + - back_wheel_L_joint + - front_wheel_R_joint + - middle_wheel_R_joint + - back_wheel_R_joint + interface_name: velocity + + +steer_position_controller: + ros__parameters: + joints: + - suspension_steer_F_L_joint + - suspension_steer_B_L_joint + - suspension_steer_F_R_joint + - suspension_steer_B_R_joint + interface_name: position + command_interfaces: + - position + state_interfaces: + - position + - velocity + +wheel_tree_position_controller: + ros__parameters: + joints: + - suspension_arm_F_L_joint + - suspension_arm_B_L_joint + - suspension_arm_F_R_joint + - suspension_arm_B_R_joint + command_interfaces: + - effort + state_interfaces: + - position + - velocity + - effort + gains: + suspension_arm_F_L_joint: + p: 2200.0 + i: 10.0 + d: 10.0 + suspension_arm_B_L_joint: + p: 4200.0 + i: 10.0 + d: 10.0 + suspension_arm_F_R_joint: + p: 2200.0 + i: 10.0 + d: 10.0 + suspension_arm_B_R_joint: + p: 4200.0 + i: 10.0 + d: 10.0 + enable: + suspension_arm_F_L_joint: + status: 1 + suspension_arm_B_L_joint: + status: 1 + suspension_arm_F_R_joint: + status: 1 + suspension_arm_B_R_joint: + status: 1 diff --git a/racs2_demos_on_spaceros/entrypoint.sh b/racs2_demos_on_spaceros/entrypoint.sh new file mode 100755 index 0000000..d1b51f2 --- /dev/null +++ b/racs2_demos_on_spaceros/entrypoint.sh @@ -0,0 +1,6 @@ +#!/bin/bash +set -e + +# Setup the Demo environment +source "${DEMO_DIR}/install/setup.bash" +exec "$@" diff --git a/racs2_demos_on_spaceros/launch/mars_rover.launch.py b/racs2_demos_on_spaceros/launch/mars_rover.launch.py new file mode 100644 index 0000000..82e9ebf --- /dev/null +++ b/racs2_demos_on_spaceros/launch/mars_rover.launch.py @@ -0,0 +1,194 @@ +from http.server import executable +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, ExecuteProcess, RegisterEventHandler, IncludeLaunchDescription +from launch.substitutions import TextSubstitution, PathJoinSubstitution, LaunchConfiguration, Command +from launch_ros.actions import Node, SetParameter +from launch_ros.substitutions import FindPackageShare +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.event_handlers import OnProcessExit, OnExecutionComplete +import os +from os import environ + +from ament_index_python.packages import get_package_share_directory + +import xacro + + + +# . ../spaceros_ws/install/setup.bash && . ../depends_ws/install/setup.bash +# rm -rf build install log && colcon build && . install/setup.bash + +def generate_launch_description(): + + mars_rover_demos_path = get_package_share_directory('mars_rover') + mars_rover_models_path = get_package_share_directory('simulation') + + env = {'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': + ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')]), + 'IGN_GAZEBO_RESOURCE_PATH': + ':'.join([environ.get('IGN_GAZEBO_RESOURCE_PATH', default=''), mars_rover_demos_path])} + + urdf_model_path = os.path.join(mars_rover_models_path, 'models', 'curiosity_path', + 'urdf', 'curiosity_mars_rover.xacro') + mars_world_model = os.path.join(mars_rover_demos_path, 'worlds', 'mars_curiosity.world') + + doc = xacro.process_file(urdf_model_path) + robot_description = {'robot_description': doc.toxml()} + + arm_node = Node( + package="mars_rover", + executable="move_arm", + output='screen' + ) + + mast_node = Node( + package="mars_rover", + executable="move_mast", + output='screen' + ) + + wheel_node = Node( + package="mars_rover", + executable="move_wheel", + output='screen' + ) + + run_node = Node( + package="mars_rover", + executable="run_demo", + output='screen' + ) + + odom_node = Node( + package="mars_rover", + executable="odom_tf_publisher", + output='screen' + ) + + start_world = ExecuteProcess( + cmd=['ign gazebo', mars_world_model, '-r'], + output='screen', + additional_env=env, + shell=True + ) + + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[robot_description]) + + ros_gz_bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock', + '/model/curiosity_mars_rover/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry', + '/scan@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan', + ], + output='screen') + + image_bridge = Node( + package='ros_gz_image', + executable='image_bridge', + arguments=['/image_raw', '/image_raw'], + output='screen') + + spawn = Node( + package='ros_ign_gazebo', executable='create', + arguments=[ + '-name', 'curiosity_mars_rover', + '-topic', robot_description, + '-z', '-7.5' + ], + output='screen' + + ) + + + ## Control Components + + component_state_msg = '{name: "IgnitionSystem", target_state: {id: 3, label: ""}}' + + ## a hack to resolve current bug + set_hardware_interface_active = ExecuteProcess( + cmd=['ros2', 'service', 'call', + 'controller_manager/set_hardware_component_state', + 'controller_manager_msgs/srv/SetHardwareComponentState', + component_state_msg] + ) + + load_joint_state_broadcaster = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'joint_state_broadcaster'], + output='screen' + ) + + load_arm_joint_traj_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'arm_joint_trajectory_controller'], + output='screen' + ) + + load_mast_joint_traj_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'mast_joint_trajectory_controller'], + output='screen' + ) + + load_wheel_joint_traj_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'wheel_velocity_controller'], + output='screen' + ) + + load_steer_joint_traj_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'steer_position_controller'], + output='screen' + ) + + load_suspension_joint_traj_controller = ExecuteProcess( + cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', + 'wheel_tree_position_controller'], + output='screen' + ) + + return LaunchDescription([ + SetParameter(name='use_sim_time', value=True), + start_world, + robot_state_publisher, + spawn, + arm_node, + mast_node, + wheel_node, + # run_node, + odom_node, + ros_gz_bridge, + image_bridge, + + RegisterEventHandler( + OnProcessExit( + target_action=spawn, + on_exit=[set_hardware_interface_active], + ) + ), + RegisterEventHandler( + OnProcessExit( + target_action=set_hardware_interface_active, + on_exit=[load_joint_state_broadcaster], + ) + ), + RegisterEventHandler( + OnProcessExit( + target_action=load_joint_state_broadcaster, + on_exit=[load_arm_joint_traj_controller, + load_mast_joint_traj_controller, + load_wheel_joint_traj_controller, + load_steer_joint_traj_controller, + load_suspension_joint_traj_controller], + ) + ), + ]) diff --git a/racs2_demos_on_spaceros/mars_rover/__init__.py b/racs2_demos_on_spaceros/mars_rover/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/racs2_demos_on_spaceros/nodes/RACS2Bridge_geometry_msgs_pb2.py b/racs2_demos_on_spaceros/nodes/RACS2Bridge_geometry_msgs_pb2.py new file mode 100644 index 0000000..2ffdfea --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/RACS2Bridge_geometry_msgs_pb2.py @@ -0,0 +1,374 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: RACS2Bridge_geometry_msgs.proto + +from google.protobuf import descriptor as _descriptor +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + + + +DESCRIPTOR = _descriptor.FileDescriptor( + name='RACS2Bridge_geometry_msgs.proto', + package='', + syntax='proto2', + serialized_options=None, + create_key=_descriptor._internal_create_key, + serialized_pb=b'\n\x1fRACS2Bridge_geometry_msgs.proto\"D\n!RACS2Bridge_geometry_msgs_Vector3\x12\t\n\x01x\x18\x01 \x02(\x01\x12\t\n\x01y\x18\x02 \x02(\x01\x12\t\n\x01z\x18\x03 \x02(\x01\"\x8a\x01\n\x1fRACS2Bridge_geometry_msgs_Twist\x12\x32\n\x06linear\x18\x01 \x02(\x0b\x32\".RACS2Bridge_geometry_msgs_Vector3\x12\x33\n\x07\x61ngular\x18\x02 \x02(\x0b\x32\".RACS2Bridge_geometry_msgs_Vector3\"\xe9\x06\n\x19RACS2Bridge_geometry_msgs\x12&\n\x1a\x61\x63\x63\x65l_with_covariance_data\x18\x01 \x03(\x02\x42\x02\x10\x01\x12.\n\"accel_with_covariance_stamped_data\x18\x02 \x03(\x02\x42\x02\x10\x01\x12\x1e\n\x12point_stamped_data\x18\x03 \x03(\x02\x42\x02\x10\x01\x12 \n\x14inertia_stamped_data\x18\x04 \x03(\x02\x42\x02\x10\x01\x12#\n\x17quaternion_stamped_data\x18\x05 \x03(\x02\x42\x02\x10\x01\x12\"\n\x16transform_stamped_data\x18\x06 \x03(\x02\x42\x02\x10\x01\x12\x18\n\x0cinertia_data\x18\x07 \x03(\x02\x42\x02\x10\x01\x12%\n\x19pose_with_covariance_data\x18\x08 \x03(\x02\x42\x02\x10\x01\x12)\n\x1dtwist_covariance_stamped_data\x18\t \x03(\x02\x42\x02\x10\x01\x12\x17\n\x0bwrench_data\x18\n \x03(\x02\x42\x02\x10\x01\x12\x16\n\naccel_data\x18\x0b \x03(\x02\x42\x02\x10\x01\x12-\n!pose_with_covariance_stamped_data\x18\x0c \x03(\x02\x42\x02\x10\x01\x12\x1f\n\x13\x61\x63\x63\x65le_stamped_data\x18\r \x03(\x02\x42\x02\x10\x01\x12\x1a\n\x0etransform_data\x18\x0e \x03(\x02\x42\x02\x10\x01\x12\x16\n\npoint_data\x18\x0f \x03(\x02\x42\x02\x10\x01\x12\x1f\n\x13polygon_stamped_dta\x18\x10 \x03(\x02\x42\x02\x10\x01\x12\x1b\n\x0fpose_array_data\x18\x11 \x03(\x02\x42\x02\x10\x01\x12 \n\x14vector3_stamped_data\x18\x12 \x03(\x02\x42\x02\x10\x01\x12\x1d\n\x11pose_stamped_data\x18\x13 \x03(\x02\x42\x02\x10\x01\x12\x18\n\x0cpolygon_data\x18\x14 \x03(\x02\x42\x02\x10\x01\x12\x1c\n\x10queaternion_data\x18\x15 \x03(\x02\x42\x02\x10\x01\x12\x18\n\x0cpoint32_data\x18\x16 \x03(\x02\x42\x02\x10\x01\x12&\n\x1atwist_with_covariance_data\x18\x17 \x03(\x02\x42\x02\x10\x01\x12\x15\n\tpose_data\x18\x18 \x03(\x02\x42\x02\x10\x01\x12\x1e\n\x12twist_stamped_data\x18\x19 \x03(\x02\x42\x02\x10\x01\x12\x18\n\x0cpose_2d_data\x18\x1a \x03(\x02\x42\x02\x10\x01' +) + + + + +_RACS2BRIDGE_GEOMETRY_MSGS_VECTOR3 = _descriptor.Descriptor( + name='RACS2Bridge_geometry_msgs_Vector3', + full_name='RACS2Bridge_geometry_msgs_Vector3', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='x', full_name='RACS2Bridge_geometry_msgs_Vector3.x', index=0, + number=1, type=1, cpp_type=5, label=2, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='y', full_name='RACS2Bridge_geometry_msgs_Vector3.y', index=1, + number=2, type=1, cpp_type=5, label=2, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='z', full_name='RACS2Bridge_geometry_msgs_Vector3.z', index=2, + number=3, type=1, cpp_type=5, label=2, + has_default_value=False, default_value=float(0), + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto2', + extension_ranges=[], + oneofs=[ + ], + serialized_start=35, + serialized_end=103, +) + + +_RACS2BRIDGE_GEOMETRY_MSGS_TWIST = _descriptor.Descriptor( + name='RACS2Bridge_geometry_msgs_Twist', + full_name='RACS2Bridge_geometry_msgs_Twist', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='linear', full_name='RACS2Bridge_geometry_msgs_Twist.linear', index=0, + number=1, type=11, cpp_type=10, label=2, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='angular', full_name='RACS2Bridge_geometry_msgs_Twist.angular', index=1, + number=2, type=11, cpp_type=10, label=2, + has_default_value=False, default_value=None, + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=None, file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto2', + extension_ranges=[], + oneofs=[ + ], + serialized_start=106, + serialized_end=244, +) + + +_RACS2BRIDGE_GEOMETRY_MSGS = _descriptor.Descriptor( + name='RACS2Bridge_geometry_msgs', + full_name='RACS2Bridge_geometry_msgs', + filename=None, + file=DESCRIPTOR, + containing_type=None, + create_key=_descriptor._internal_create_key, + fields=[ + _descriptor.FieldDescriptor( + name='accel_with_covariance_data', full_name='RACS2Bridge_geometry_msgs.accel_with_covariance_data', index=0, + number=1, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='accel_with_covariance_stamped_data', full_name='RACS2Bridge_geometry_msgs.accel_with_covariance_stamped_data', index=1, + number=2, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='point_stamped_data', full_name='RACS2Bridge_geometry_msgs.point_stamped_data', index=2, + number=3, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='inertia_stamped_data', full_name='RACS2Bridge_geometry_msgs.inertia_stamped_data', index=3, + number=4, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='quaternion_stamped_data', full_name='RACS2Bridge_geometry_msgs.quaternion_stamped_data', index=4, + number=5, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='transform_stamped_data', full_name='RACS2Bridge_geometry_msgs.transform_stamped_data', index=5, + number=6, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='inertia_data', full_name='RACS2Bridge_geometry_msgs.inertia_data', index=6, + number=7, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='pose_with_covariance_data', full_name='RACS2Bridge_geometry_msgs.pose_with_covariance_data', index=7, + number=8, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='twist_covariance_stamped_data', full_name='RACS2Bridge_geometry_msgs.twist_covariance_stamped_data', index=8, + number=9, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='wrench_data', full_name='RACS2Bridge_geometry_msgs.wrench_data', index=9, + number=10, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='accel_data', full_name='RACS2Bridge_geometry_msgs.accel_data', index=10, + number=11, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='pose_with_covariance_stamped_data', full_name='RACS2Bridge_geometry_msgs.pose_with_covariance_stamped_data', index=11, + number=12, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='accele_stamped_data', full_name='RACS2Bridge_geometry_msgs.accele_stamped_data', index=12, + number=13, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='transform_data', full_name='RACS2Bridge_geometry_msgs.transform_data', index=13, + number=14, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='point_data', full_name='RACS2Bridge_geometry_msgs.point_data', index=14, + number=15, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='polygon_stamped_dta', full_name='RACS2Bridge_geometry_msgs.polygon_stamped_dta', index=15, + number=16, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='pose_array_data', full_name='RACS2Bridge_geometry_msgs.pose_array_data', index=16, + number=17, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='vector3_stamped_data', full_name='RACS2Bridge_geometry_msgs.vector3_stamped_data', index=17, + number=18, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='pose_stamped_data', full_name='RACS2Bridge_geometry_msgs.pose_stamped_data', index=18, + number=19, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='polygon_data', full_name='RACS2Bridge_geometry_msgs.polygon_data', index=19, + number=20, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='queaternion_data', full_name='RACS2Bridge_geometry_msgs.queaternion_data', index=20, + number=21, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='point32_data', full_name='RACS2Bridge_geometry_msgs.point32_data', index=21, + number=22, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='twist_with_covariance_data', full_name='RACS2Bridge_geometry_msgs.twist_with_covariance_data', index=22, + number=23, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='pose_data', full_name='RACS2Bridge_geometry_msgs.pose_data', index=23, + number=24, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='twist_stamped_data', full_name='RACS2Bridge_geometry_msgs.twist_stamped_data', index=24, + number=25, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + _descriptor.FieldDescriptor( + name='pose_2d_data', full_name='RACS2Bridge_geometry_msgs.pose_2d_data', index=25, + number=26, type=2, cpp_type=6, label=3, + has_default_value=False, default_value=[], + message_type=None, enum_type=None, containing_type=None, + is_extension=False, extension_scope=None, + serialized_options=b'\020\001', file=DESCRIPTOR, create_key=_descriptor._internal_create_key), + ], + extensions=[ + ], + nested_types=[], + enum_types=[ + ], + serialized_options=None, + is_extendable=False, + syntax='proto2', + extension_ranges=[], + oneofs=[ + ], + serialized_start=247, + serialized_end=1120, +) + +_RACS2BRIDGE_GEOMETRY_MSGS_TWIST.fields_by_name['linear'].message_type = _RACS2BRIDGE_GEOMETRY_MSGS_VECTOR3 +_RACS2BRIDGE_GEOMETRY_MSGS_TWIST.fields_by_name['angular'].message_type = _RACS2BRIDGE_GEOMETRY_MSGS_VECTOR3 +DESCRIPTOR.message_types_by_name['RACS2Bridge_geometry_msgs_Vector3'] = _RACS2BRIDGE_GEOMETRY_MSGS_VECTOR3 +DESCRIPTOR.message_types_by_name['RACS2Bridge_geometry_msgs_Twist'] = _RACS2BRIDGE_GEOMETRY_MSGS_TWIST +DESCRIPTOR.message_types_by_name['RACS2Bridge_geometry_msgs'] = _RACS2BRIDGE_GEOMETRY_MSGS +_sym_db.RegisterFileDescriptor(DESCRIPTOR) + +RACS2Bridge_geometry_msgs_Vector3 = _reflection.GeneratedProtocolMessageType('RACS2Bridge_geometry_msgs_Vector3', (_message.Message,), { + 'DESCRIPTOR' : _RACS2BRIDGE_GEOMETRY_MSGS_VECTOR3, + '__module__' : 'RACS2Bridge_geometry_msgs_pb2' + # @@protoc_insertion_point(class_scope:RACS2Bridge_geometry_msgs_Vector3) + }) +_sym_db.RegisterMessage(RACS2Bridge_geometry_msgs_Vector3) + +RACS2Bridge_geometry_msgs_Twist = _reflection.GeneratedProtocolMessageType('RACS2Bridge_geometry_msgs_Twist', (_message.Message,), { + 'DESCRIPTOR' : _RACS2BRIDGE_GEOMETRY_MSGS_TWIST, + '__module__' : 'RACS2Bridge_geometry_msgs_pb2' + # @@protoc_insertion_point(class_scope:RACS2Bridge_geometry_msgs_Twist) + }) +_sym_db.RegisterMessage(RACS2Bridge_geometry_msgs_Twist) + +RACS2Bridge_geometry_msgs = _reflection.GeneratedProtocolMessageType('RACS2Bridge_geometry_msgs', (_message.Message,), { + 'DESCRIPTOR' : _RACS2BRIDGE_GEOMETRY_MSGS, + '__module__' : 'RACS2Bridge_geometry_msgs_pb2' + # @@protoc_insertion_point(class_scope:RACS2Bridge_geometry_msgs) + }) +_sym_db.RegisterMessage(RACS2Bridge_geometry_msgs) + + +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['accel_with_covariance_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['accel_with_covariance_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['point_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['inertia_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['quaternion_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['transform_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['inertia_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['pose_with_covariance_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['twist_covariance_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['wrench_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['accel_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['pose_with_covariance_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['accele_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['transform_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['point_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['polygon_stamped_dta']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['pose_array_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['vector3_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['pose_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['polygon_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['queaternion_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['point32_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['twist_with_covariance_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['pose_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['twist_stamped_data']._options = None +_RACS2BRIDGE_GEOMETRY_MSGS.fields_by_name['pose_2d_data']._options = None +# @@protoc_insertion_point(module_scope) diff --git a/racs2_demos_on_spaceros/nodes/move_arm b/racs2_demos_on_spaceros/nodes/move_arm new file mode 100644 index 0000000..3cd7b7d --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/move_arm @@ -0,0 +1,68 @@ +#!/usr/bin/env python3 + +import rclpy +from rclpy.node import Node +from builtin_interfaces.msg import Duration + +from std_msgs.msg import String, Float64 +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from std_srvs.srv import Empty + +class MoveArm(Node): + + def __init__(self): + super().__init__('arm_node') + self.arm_publisher_ = self.create_publisher(JointTrajectory, '/arm_joint_trajectory_controller/joint_trajectory', 10) + self.open_srv = self.create_service(Empty, 'open_arm', self.open_arm_callback) + self.close_srv = self.create_service(Empty, 'close_arm', self.close_arm_callback) + + + self.open = True + + + def open_arm_callback(self, request, response): + self.open = True + traj = JointTrajectory() + traj.joint_names = ["arm_01_joint", "arm_02_joint", "arm_03_joint", "arm_04_joint", "arm_tools_joint"] + + point1 = JointTrajectoryPoint() + point1.positions = [0.0,-0.5,3.0,1.0,0.0] + point1.time_from_start = Duration(sec=4) + + traj.points.append(point1) + self.arm_publisher_.publish(traj) + + + return response + + def close_arm_callback(self, request, response): + self.open = False + traj = JointTrajectory() + traj.joint_names = ["arm_01_joint", "arm_02_joint", "arm_03_joint", "arm_04_joint", "arm_tools_joint"] + + point1 = JointTrajectoryPoint() + point1.positions = [-1.57,-0.4,-1.1,-1.57,-1.57] + point1.time_from_start = Duration(sec=4) + + traj.points.append(point1) + self.arm_publisher_.publish(traj) + + return response + + + +def main(args=None): + rclpy.init(args=args) + + arm_node = MoveArm() + + rclpy.spin(arm_node) + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + arm_node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/racs2_demos_on_spaceros/nodes/move_mast b/racs2_demos_on_spaceros/nodes/move_mast new file mode 100644 index 0000000..c29ab45 --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/move_mast @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 + +import rclpy +from rclpy.node import Node +from builtin_interfaces.msg import Duration + +from std_msgs.msg import String, Float64 +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from std_srvs.srv import Empty + +class MastArm(Node): + + def __init__(self): + super().__init__('mast_node') + self.mast_publisher_ = self.create_publisher(JointTrajectory, '/mast_joint_trajectory_controller/joint_trajectory', 10) + self.mast_open_srv = self.create_service(Empty, 'mast_open', self.mast_open_callback) + self.mast_close_srv = self.create_service(Empty, 'mast_close', self.mast_close_callback) + self.mast_rotate_srv = self.create_service(Empty, 'mast_rotate', self.mast_rotate_callback) + + + def mast_open_callback(self, request, response): + traj = JointTrajectory() + traj.joint_names = ["mast_p_joint", "mast_02_joint", "mast_cameras_joint"] + + point = JointTrajectoryPoint() + point.positions = [0.0,-0.5,0.0] + point.time_from_start = Duration(sec=1) + + traj.points.append(point) + self.mast_publisher_.publish(traj) + return response + + def mast_close_callback(self, request, response): + traj = JointTrajectory() + traj.joint_names = ["mast_p_joint", "mast_02_joint", "mast_cameras_joint"] + + point = JointTrajectoryPoint() + point.positions = [1.57,-1.57,0.0] + point.time_from_start = Duration(sec=1) + + traj.points.append(point) + self.mast_publisher_.publish(traj) + return response + + def mast_rotate_callback(self, request, response): + traj = JointTrajectory() + traj.joint_names = ["mast_p_joint", "mast_02_joint", "mast_cameras_joint"] + + point1 = JointTrajectoryPoint() + point1.positions = [0.0,-1.57,0.0] + point1.time_from_start = Duration(sec=2) + traj.points.append(point1) + + point2 = JointTrajectoryPoint() + point2.positions = [0.0,-3.14,0.0] + point2.time_from_start = Duration(sec=4) + traj.points.append(point2) + + point3 = JointTrajectoryPoint() + point3.positions = [0.0,-6.28,0.0] + point3.time_from_start = Duration(sec=6) + traj.points.append(point3) + + self.mast_publisher_.publish(traj) + return response + + + +def main(args=None): + rclpy.init(args=args) + + mast_node = MastArm() + + rclpy.spin(mast_node) + + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + mast_node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/racs2_demos_on_spaceros/nodes/move_wheel b/racs2_demos_on_spaceros/nodes/move_wheel new file mode 100644 index 0000000..8bf4b11 --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/move_wheel @@ -0,0 +1,147 @@ +#!/usr/bin/env python3 + +from pickle import FALSE +import rclpy +from rclpy.node import Node +from builtin_interfaces.msg import Duration + +from std_msgs.msg import String, Float64MultiArray +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from geometry_msgs.msg import Twist +import math +from racs2_msg.msg import RACS2UserMsg +from RACS2Bridge_geometry_msgs_pb2 import RACS2Bridge_geometry_msgs_Twist + + +class MoveWheel(Node): + + def __init__(self): + super().__init__('wheel_node') + self.wheel_publisher_ = self.create_publisher(Float64MultiArray, '/wheel_velocity_controller/commands', 10) + self.steer_publisher_ = self.create_publisher(JointTrajectory, '/steer_position_controller/joint_trajectory', 10) + self.suspension_publisher_ = self.create_publisher(Float64MultiArray, '/wheel_tree_position_controller/commands',10) + timer_period = 0.1 # seconds + self.timer = self.create_timer(timer_period, self.timer_callback) + + + # self.vel_sub = self.create_subscription(Twist, '/cmd_vel', self.vel_callback, 10) + self.vel_sub = self.create_subscription(RACS2UserMsg, '/cmd_vel', self.vel_callback, 10) + self.curr_vel = Twist() + self.last_vel = Twist() + self.should_steer = False + + def vel_callback(self, msg): + self.get_logger().info('Subscribing: [/cmd_vel]') + message = RACS2Bridge_geometry_msgs_Twist() + message.ParseFromString(b''.join(msg.body_data)) + self.get_logger().info(f"message: {message}") + twist_msg = Twist() + twist_msg.linear.x = message.linear.x + twist_msg.linear.y = message.linear.y + twist_msg.linear.z = message.linear.z + twist_msg.angular.x = message.angular.x + twist_msg.angular.y = message.angular.y + twist_msg.angular.z = message.angular.z + if abs(self.last_vel.angular.z - self.curr_vel.angular.z) > 0.01 and self.should_steer is False: + self.last_vel = Twist() + self.last_vel.linear.x = self.curr_vel.linear.x + self.last_vel.angular.z = self.curr_vel.angular.z + self.should_steer = True + + # self.curr_vel = msg + self.curr_vel = twist_msg + self.get_logger().info(f"self.curr_vel: {self.curr_vel}") + + def set_wheel_common_speed(self, vel): + + target_vel = Float64MultiArray() + target_vel.data = [vel, vel*1.5, vel, -vel, -vel*1.5, -vel] + + # self.get_logger().info(f'Publishing: "{target_vel.data}"') + self.wheel_publisher_.publish(target_vel) + + + def map_angular_to_steering(self, angular_speed) -> float: + if abs(angular_speed) < 1e-3: + return 0.0 + + #max 0.6 min -0.6 + angular_speed = min(0.6, max(angular_speed, -0.6)) + return (angular_speed/abs(angular_speed))*(-25 * abs(angular_speed) + 17.5) + + + def set_steering(self, turn_rad): + #Ideal Ackerman Steering + target_steer = JointTrajectory() + # target_steer.header.stamp = self.get_clock().now().to_msg() + target_steer.joint_names = ["suspension_steer_F_L_joint", "suspension_steer_B_L_joint", + "suspension_steer_F_R_joint", "suspension_steer_B_R_joint"] + steer_point = JointTrajectoryPoint() + + if abs(turn_rad) < 1e-3: + steer_point.positions = [0.0, 0.0, 0.0, 0.0] + else: + R = abs(turn_rad) #Turning radius + + L = 2.08157 #Chassis Length + T = 1.53774 #Chassis Width + + alpha_i = math.atan(L/(R - (T/2))) + alpha_o = math.atan(L/(R + (T/2))) + + if alpha_i > 0.6: + alpha_i = 0.6 + + if alpha_o > 0.6: + alpha_o = 0.6 + + alpha_i = round(alpha_i, 2) + alpha_o = round(alpha_o, 2) + + if turn_rad > 0.0: + steer_point.positions = [alpha_i, -alpha_i, alpha_o, -alpha_o] + else: + steer_point.positions = [-alpha_o, alpha_o, -alpha_i, alpha_i] + + + steer_point.time_from_start = Duration(sec=1) + + target_steer.points.append(steer_point) + + self.steer_publisher_.publish(target_steer) + + + def set_suspension(self, sus_val=None): + + target_val = Float64MultiArray() + if sus_val is None: + target_val.data = [0.3,-0.1,0.3,-0.1] + self.suspension_publisher_.publish(target_val) + + + def timer_callback(self): + self.set_wheel_common_speed(self.curr_vel.linear.x) + self.set_suspension() + + if self.should_steer: + steering_val = self.map_angular_to_steering(self.curr_vel.angular.z) + self.set_steering(steering_val) + self.should_steer = False + + +def main(args=None): + rclpy.init(args=args) + + wheel_node = MoveWheel() + + rclpy.spin(wheel_node) + + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + wheel_node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/racs2_demos_on_spaceros/nodes/odom_tf_publisher b/racs2_demos_on_spaceros/nodes/odom_tf_publisher new file mode 100644 index 0000000..ca5c95f --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/odom_tf_publisher @@ -0,0 +1,66 @@ +#!/usr/bin/env python3 + +# adapted from ROS 2 tutorial +# https://docs.ros.org/en/rolling/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Broadcaster-Py.html + +import rclpy + +from nav_msgs.msg import Odometry +from geometry_msgs.msg import TransformStamped +from rclpy.node import Node +from tf2_ros import TransformBroadcaster + +class OdomTFBroadcaster(Node): + + def __init__(self): + super().__init__('odom_tf_publisher') + + # Initialize the transform broadcaster + self.tf_broadcaster = TransformBroadcaster(self) + + # Subscribe to Odometry topic + # TODO: make the topic name a parameter instead of hard-coded + self.subscription = self.create_subscription( + Odometry, + f'/model/curiosity_mars_rover/odometry', + self.handle_odometry, + 1) + self.subscription # prevent unused variable warning + + def handle_odometry(self, msg): + tf = TransformStamped() + + # Read message content and assign it to + # corresponding tf variables + tf.header.stamp = msg.header.stamp + tf.header.frame_id = msg.header.frame_id + tf.child_frame_id = msg.child_frame_id + + # get translation coordinates from the message pose + tf.transform.translation.x = msg.pose.pose.position.x + tf.transform.translation.y = msg.pose.pose.position.y + tf.transform.translation.z = msg.pose.pose.position.z + + # get rotation from the message pose + tf.transform.rotation.x = msg.pose.pose.orientation.x + tf.transform.rotation.y = msg.pose.pose.orientation.y + tf.transform.rotation.z = msg.pose.pose.orientation.z + tf.transform.rotation.w = msg.pose.pose.orientation.w + + # Send the transformation + self.tf_broadcaster.sendTransform(tf) + + +def main(): + rclpy.init() + node = OdomTFBroadcaster() + node.get_logger().info('Starting odometry_tf_publisher node') + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + + rclpy.shutdown() + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/racs2_demos_on_spaceros/nodes/run_demo b/racs2_demos_on_spaceros/nodes/run_demo new file mode 100644 index 0000000..6df8d17 --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/run_demo @@ -0,0 +1,86 @@ +#!/usr/bin/env python3 + + +import rclpy +from rclpy.node import Node + +from std_msgs.msg import String, Float64MultiArray +from geometry_msgs.msg import Twist +import math +from random import randint +from std_srvs.srv import Empty + + +# A node for performing combination of motions from different moving parts of the Curiosity rover. +class RunDemo(Node): + def __init__(self) -> None: + super().__init__('run_node') + self.motion_publisher_ = self.create_publisher(Twist, '/cmd_vel', 10) + self.forward_srv = self.create_service(Empty, 'move_forward', self.move_forward_callback) + self.stop_srv = self.create_service(Empty, 'move_stop', self.move_stop_callback) + self.left_srv = self.create_service(Empty, 'turn_left', self.turn_left_callback) + self.right_srv = self.create_service(Empty, 'turn_right', self.turn_right_callback) + self.stopped = True + + timer_period = 0.1 + self.timer = self.create_timer(timer_period, self.timer_callback) + + self.curr_action = Twist() + + def timer_callback(self): + if (not self.stopped): + self.motion_publisher_.publish(self.curr_action) + + def move_forward_callback(self, request, response): + self.get_logger().info("Moving forward") + action = Twist() + action.linear.x = 2.0 + self.curr_action = action + self.stopped = False + return response + + def move_stop_callback(self, request, response): + # stop timer from publishing + self.stopped = True + self.get_logger().info("Stopping") + self.curr_action = Twist() + # publish once to ensure we stop + self.motion_publisher_.publish(self.curr_action) + return response + + def turn_left_callback(self, request, response): + self.get_logger().info("Turning left") + action = Twist() + action.linear.x = 1.0 + action.angular.z = 0.4 + self.curr_action = action + self.stopped = False + return response + + def turn_right_callback(self, request, response): + self.get_logger().info("Turning right") + self.stopped = False + action = Twist() + action.linear.x = 1.0 + action.angular.z = -0.4 + self.curr_action = action + self.stopped = False + return response + + +def main(args=None): + rclpy.init(args=args) + + run_demo = RunDemo() + + rclpy.spin(run_demo) + + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + run_demo.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/racs2_demos_on_spaceros/nodes/test_node b/racs2_demos_on_spaceros/nodes/test_node new file mode 100644 index 0000000..8318215 --- /dev/null +++ b/racs2_demos_on_spaceros/nodes/test_node @@ -0,0 +1,41 @@ +#!/usr/bin/env python3 + +import rclpy +from rclpy.node import Node + +from std_msgs.msg import String + + +class MinimalPublisher(Node): + + def __init__(self): + super().__init__('minimal_publisher') + self.publisher_ = self.create_publisher(String, 'topic', 10) + timer_period = 0.5 # seconds + self.timer = self.create_timer(timer_period, self.timer_callback) + self.i = 0 + + def timer_callback(self): + msg = String() + msg.data = 'Hello World: %d' % self.i + self.publisher_.publish(msg) + self.get_logger().info('Publishing: "%s"' % msg.data) + self.i += 1 + + +def main(args=None): + rclpy.init(args=args) + + minimal_publisher = MinimalPublisher() + + rclpy.spin(minimal_publisher) + + # Destroy the node explicitly + # (optional - otherwise it will be done automatically + # when the garbage collector destroys the node object) + minimal_publisher.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/racs2_demos_on_spaceros/package.xml b/racs2_demos_on_spaceros/package.xml new file mode 100644 index 0000000..f526fb0 --- /dev/null +++ b/racs2_demos_on_spaceros/package.xml @@ -0,0 +1,42 @@ + + + + mars_rover + 0.0.1 + A RACS2 Bridge demo for Mars rover + jaxa + Apache-2.0 + + ament_cmake + ament_cmake_python + + rclcpp + rclpy + simulation + + ament_index_python + control_msgs + diff_drive_controller + effort_controllers + geometry_msgs + hardware_interface + ign_ros2_control + imu_sensor_broadcaster + joint_state_broadcaster + joint_trajectory_controller + launch + launch_ros + robot_state_publisher + ros_ign_gazebo + ros2controlcli + std_msgs + velocity_controllers + xacro + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/racs2_demos_on_spaceros/racs2_demo_on_spaceros_nodes.png b/racs2_demos_on_spaceros/racs2_demo_on_spaceros_nodes.png new file mode 100644 index 0000000000000000000000000000000000000000..f0bf063b07535bc31cc1065b53845d6a5ee07c63 GIT binary patch literal 186909 zcmeFZc{rQx7C!3xx;qc5+NzqWt!gN$HIJ=o6-68K5Q?IPm}5?KG!|7;jj0l;F;!C~ zL|auggc1Z1GeJlY5fYM%QTwTj%Zv z`nh}hxbgAbjnB^vwJ;w!9oyTi+I;`b@r3kW-j9KQ-#yxVH&tFn@!)ZzFR%H|tLR(! z>pw^>IdJXr0D5BL9dWR-7^58tGJO^x2^tvi2b{~a~_$|qZJ zOQ;!r?A$h62Cw_-D<2o0-e`MXk?;Q7SLF4r5eH$R4mEA-JgEk=j<@wnCOub;dd}NE zyJnRZw0^}tYBSr7U!8vKg_dwvP|vj6>g<^GOp^Ku?5os=!b0Q&TaDMSmt3C*8^+xD z;Wt|?9A&D)clphj{Ctr4BOf`}HlB#oyM`Z6|-?A~H_+ zl7o3nQkr1mRBx{dIkBz#>M_-%3)70j*}}G>Q-OT$y*sui!@}yRo>33VaElu#jWW z0C9AbBk=q56%X0+u`vhZzu?{gg#{W5ek}TyQ&cYyOQOv=htbp2-UKV&a#Zzok0{aq z{s_6>+F9D#_i44i@C7{&)MQ{&eW#-61cA`5#2zx=EIi@;|-{>eRm-@F|6uYiY&lh01R z{!9Oy(8(ut@6Mz@t9&T^VISn3fYNgn|1-f)T_=^)_RBx*dibxgzkpYd6+8i~9_qev z{Kd!cgU{XiDf;Q9&1;d_J$r8n+!swhAazUc?%$_wP~HJQh?d1H6}m6jFI)~j zi{?9etKr>)$0t~)BKBXnda&fH-A4hRy)_Tb)D9%S5c=A&dQDA2{#nD94F5e*$Eh#O zTC*kvY!2x@MG8DQE}-!~@v6Y-Z+G-k!!8~akSu?FqWEvm8>6qqizONp?xrGt+MnEa z`?li!d+CQeB~HDZexF%rRj5)__F(`0{0}+(svIg|4p@lg~uo6TNh*=I0GW7X{>0tkQH75rx(>U4hmXmh=(*D-|f}e$(PK+O?z2a}9 zuXe4uZQY6DhaJ#OhD%-+e08wu#a%raXSu>RzwW3Re>M)gdGQ1z&h)$g`zN1cYz(#Z zwai4Nuu>21x?fZQJiRChmRym}KTkT}d@ily&LjRnE!%tJdcK$7k`vM`58lbx$o%W_ z>Paivfy==%4iCag;;fY{HY^+}-lA*@!}J60u9co}?6@0W`Tc<%!lEeHVlk$__L}9$ z9d!%!Tj4cAW^U$<1CW6`OSVgDM{iv(+4~FV ziKz8^{Ja)$Dj^}?sMe^!D5*2x6hN#{q;Jo{;>IrF1C^hemdMtTt z=!G&)>4K8=V=7+sSKd(n&^o@ezpP)Qh+&aiwNjX0)_jZoVzc;|WxI*NyP8|%;vUzS zL#=74Js%!zD3$~(Lv|rjXa@Q@`g+8VhzAibBUU1q8wXieb}#OVv6@-t`!x1R?%TVs za$m#IwU{fdCtE==yD_MwS4l3fRL($zwXa!SKX$c8)mItot)~*8YU|$rFc5drweyRA?$>G4(|U>f5=HKvz^7%m`nVE)H#a)kOHo1+fv4ik;#g`^!#Tb&bhzui(+5((AvJlABSAQ?)jm5n&Ik|AsX`=LnB{p zm!pQag@j6sbBq(aio$=;x9DfdNsUX5fesW9!uLpnenYb_FccJ;9QmBRhabvcV35}S z0$J)&M!wnW;W*@Y9(4>w@bTC*+64H0C-!2#NB)YP7MwF*37W9(RUK&<4DIY4_j@@3 zh^~!(%~j!w{AKso*pvAur8nBYWITo5EPl85=HN~KXSip#ziLbR-+lOV^EHNklzf;R z`tsSYC%;w-ncrTuX1;_8Ij5-*7##!*e@xGQP=!YH8GWVj+H=pl1Pt(uVH+&ya zbgD@3eQuFcdsusV`(4*c7waF63HUg{?~r!anWCB8X`~SA%2=bn)>oZEwJFy5ncLxs z@>hmz@~~T5C)%X)qzq2<#Vf|k#naRa^Y-;@^glt=86!XYQ01wD1^fN>`@NxcDv-@C zHeSk*);0<;886Vvo-P2Uu3LOLZE?5&$wCexu%?Gii11B-_N8X+Jz1%511#l?fhXVfKRI5@naMOyqhC_hVBReV zEV%0TuyJJFq)U1oN^fy|YWEe?XaCOrWBtQm1i6!C`Kt_39$`&E$=hjTfB4~^*1f3n z^p3teN*f9vAfWx*Q(oUYKTG{YY@9^E#IpkK@|Vg9JJrnpd&d; zGi$l&zO(g%hQyD?pN#E<9Y#QI_v`AGpb#U*-6U(1$V&H>l2HOC9D`b38^&89Ev@aC zzNm*ZTto}2XJ1iF0`x6Zoh`0%M|CqA$3iz67M0d6w!)@hi%;YBKyk@9oLr8aTcv+_ zF=YMWx366jVbOTf51(>BWJ8wt-?0~C#iMh#Rv4`}V zMPtzlnjorhfojxr0y_h5-Ha;0oc3So|GASoMR`E*8^8Nmvbh7Zy4_Kw*G z2|*iX3;LTA*f~rQn9^=FXz84`&XTsq>cg+kHC@N5rFGr78?dGY$!+Jh7d`s)3q*tV zOHgSAUB|7k9mAotY-F3REZ2eEJv$QG61H>g>M2cSj>E$$KvgJvcSg&xyr}4^pKBF<1HVbkbfTfffnz;LI1n9L416YJQ6C2 z`YV!g_zv%SK12PR7GZhIBwEVFaM-WyUe)t8Wswo?9?gyt2P9#`cUHe>-H=XZj7;t| zzI*rF4QW@D(1oHjs=|$H9v`9gzR)qjg7qWzXCet2l45@!e9DJX>|))BleklXQ^0-U zJdD1_yl2M!(EVx)M!WgQ-O`%e@ZR-OP}wIIW8DX%A#?rwwQJYPB$_CKrRgVlLjE59 zh`xbpAuFmLJPpTGH@1eBTocZ2Uosp((;-8zH(-$nlh<9|T>wu%1% z@joE`7bE@z$o~b)-$?uqi2nicKOXVh2L1=c|4)HX#Zblg)UHYOupS30slQKBl1*jl z%oz=G#h6*OAy=so22Tb~&-F&>Kc`TQtABG-pKT zUtT#Rh^N%)d@O0$tU2O}RpM<=*YP_WZG!YolPrhBCTI%^;76fzakMPtHCCtrBTluwiYFbL@tAmd-!v_nL8tpSfHW4*Q=?RXe&W>iwu47{j z^ws8{6v@%OA$-U)egWe^eapgy|Ufkz@kY0cbK&&O|$f%5KIQp~*~ZQ+rjHI9Tr zv95rhsj-r8vqF|_4mDcLtG_R{$*|1LQR#PwO$Kz^HZ3p=_&GBZyKL?hKAI9b(R|&w z{5JJ`yJ0t6DbbKpnqjZHGL|coMPj1;WEkTXbuyuT1}ix_z*zVon*B1vwbWFW;+fm2 z{K(1eksLwWKRg^XxJcPqnMZAr01TKd47R?1CoOBh7^HwksYEZY7>Q7z(*G$7nEO0Ward{yI8G zXJgiv-bup8rijC#yI+e?Q8SC0iEmr1j0^#w9eTtj|9{lr`|R7$sF9>%GyzD zj9M_;^lI}_znA<=S>j|Vn3?7v8X-z#JM@MykAd37N5PeTDehc$oCDAv4O8?pGfKDX zg3z@e&rFfhLTTON-Rq08D+Vx1!&vxSoz3iJL8k{RIHI{+D9E%-dal6HdZlNPt>H^x z6l!d_%Zd!QqFfw!zqscrr9ngX)R`aJyB6#&uw9!^ULd|z1xG$Yog-IKSXi^J;Po&F@=D9brnPlw?uczp zG+uW5f(d>CAjR)&g|9U+LZpwb%rh^OYM)lGP?>e8fyhB`!azd9dwt!-HE_0-b7nj_ z0DQ??XM?D==7Gb)N@}~j%T#396UrGQ9|WzPG&MaUBQCJFoz3EOfB=Mv2~kOk>^rC| zP&1;XTs|^_M?u%RoOnJ_xt~^C1rJRO+u3x1HGqjDJ|RslymHEa#&R3D%9Pxv;(<7^%9V zM%WMlYi<3&Ol;&j$~`cey$lAZqNtU!BI-r}DP@y{omrB>#MXK=yaDIkvfa9}NQw&) zJC%7t3YefG#xV-O_dMGG^q!|4r9&1n zWZRXfx2(W&UGq)zk^22uwfa8&*|?KZKrd5wdR$!k`pC416Z?lXc0D6hLOUUDpcvS> zJ%>6eX!bkMPD+L5mg7~ZO?1W}61I$L?vE;7q+Kbfa)j;<>M#-aawDxfL*9S@)kjT? z2xj)Zr$p2iyu5<8a*UMU)VtX?v@hJrZolMS1JWy02UT7CUnu8UYX| z0l?V{jUtf=gP6pIOx$y`-9ZTqlVzB2i5$4cpmV4q5}y~;1MTU8Wd!-on}pVfvCExw zlLpeM;}is#I8guK{jBH%pi!R^oAt`6Iw%&zwW#T=dmmUeggO|TKjEOvxByY|SYs?y zEvhPc(Twcbea*@sd(aOfa&0NqH6gph0W2M z4T`Gky*9r4Lv?)D%!$)aN{d7|-L?k?-6D5TgA4LDcfIQD*AFkqbFUhiN zko00OGx!}pblAuaj?OK_dzis>U^@$4PP?5%{s}6kD!VQZw{n67ZXqxGgwqR6*7AS16x-v~fkOeQMV^^TgDW0FN#Z>};}%G&4i>z~@WMJ|LYI@v?e z$SJt_;QWn-3~x4eX%?mnXO4-gXqrHcz`T0^13S6~m-1t2P4v~NqWykZ{kYK)8G~d8 zV7h}<;#`N}1aHB+5ljS!{j=i#&uDt#YY2%5m>dcbclN>$=?AAH4d$}u4I=0Z2Rtaq=JHH*(G#&!Y zGEy%+ve4`aG-@S#?+#U=Rg`f)^$Af!p`kh9N+wE+eMJ8CKmn4>M5LQaZX1gPpaF;l z^^yB|z6Y*hgI6#lvOko|3>v#6!HNI6J-}?R%NGx;cPq#Xqj|(qHwcW}eV9raf#vTK zje|_@aWi`}+$ZhjgMA?YWfP^otWOJ8DR3Pqc}kO}15=U(8{%X_L2&lv6`vs`lNP(9 zBfG0(xgoeeC0?Do?Ws{F%1Sr7=B{O>;RuPU6H)X!g3da4f)$Bfw0E?Xzd(KquQkEX zH(@b8*=oe~64HQ%+8c5NJC_hJ|3RW;}5R(EA_G?<37x8OS^r=rDBV%br zN^_S>@_fO5a`{2N7Z7))Zktvcg$slijMkgb->`iHHkEEKnwgpMHgEaB782WzYQ6!r zj5RjdSrDw!H?Lp+lpasmbYJp2cP}z*g&`hRJ2$%&>{PdrRw^{7U5YEGVn{UFz&dsl zHm8m2pz=qJjgD=AIsoXr-poX4GYOPcV!a92m(`!;5SadENYNL4b$$C?B2%WS<{D>#M&=lbuVv+W zg|e{u;WAG)-eSGGBkAXNjIL@%#U~mw%_YMq+#FL5Sy8i4)m+=MD95{>xz~_%L^V1$ z@1?1o76`GE8JLsqa)13lHd zpzEQ=8Qb5L)k}_+=dn0Lhd9rzk%EF-(0uFNfeo0M7dsl*Va!yf1UDj81MA`V78!DV z7c`4)*QQ5xo6{iCv`cGQeOYA>-6)c14yBC;R@*>Giyek|rLIA*z)H37 z`UU55yxq8(^3l?jXsB|AG%o;-PL)PLob28UczNMWmTDI(mtByLo_S|p<`(oZ)+^g&=x zxn+ahoQg77=0T@PF1``}+P)4<X_Q(sa+F5eYQ

qUD>_$vt?l4-X0k0T6~J9p=Uht|(KKLFJn!PY=RC zPSCWJ*Lru)Qi$JhfNL+XM?Dk@XFC{;B+olK4XH%?j`jRY__r;E@%wr}G~VLe`Lhx) zE9UZSsd3geEvFv3v9*?k-I$X$E5L3R5=`f%J-XU{ZJW@%Woo36L)n4^-NB7;NS)>= z4F&?wQ9Gbcr4P%Aq}_a53}&=qu)1z#C|zk~4VR(pA3^1=P zaq`wr2P0}w4~THPSZQ1IgP7nH!Lq7ZV>dZ^%UEISrxSZTrDe-&A_&5YLj%c;IM!jcIv}w6~es>KC+~q(%NI-t4=DSB=}im`4cd zA%yGNx4^^eix7t zXJKTU)r3$ocN&HLJ(Fd+alkJoC$c0PMLX5-w;2fZ?hfq~M%oL=|V?y5Eyo^-oy zf!j;vC>1~@+IRe3lVC*Up-P7K{wmY*!qM;3m7A+}(H4miW7`!6$4XQ0Sn#xSftME~ zM}~p(&oj>BDlR|tLJoD;?WtymnHIR&s~42QZKRR-{4NRY@L=BUN1C$XV^H=Kapg*W zUV%;+`)iHrJF{F=in(pCs+@qjk-R$c1Y$!9nVvKJD$T@`{u2rgHKT-gEU#>(Y+Flk zZ)IifV0$@f6oMj|8lvtr0dr8CQ5gMWiQ!|-C zR9-mWSzXh_HO=;imPe6;hZv;wMLdR{*1jE3ELy4`?_ks;Af@c7l5T3Cw4ii8FyUG^ zS7cv)$;#`w6Fdw?Ghcc>He*6e)JlprzLuM8GzoYRUP9k$ga?~BZ$DC<{v4o|JCT0o z8vc{Gx1CWjBcsv>2^Zhh{j)axL>mnrTzu>7NZ8yr+(#CLT4(k(G|pCSR>a#s$iJgs zTmmebHxgE1tPw2q2bYH3rz^(Zs<|q6QkRshY0sbwOG=flpHBkLll#d!%vRFd*rz4A zh2fOq#dUEp#%hyE*(voH#iwqXe9E^?Q~Nd4lHxw(eX~Zvq)$y+mbpID9VQJgPOD$7 zJD-16&P=Qv1nPxZwH~z`iq3TC%z2an|I-U_wPw31KLxjdKa(lCR(JOIBn@Ni9rLS- z5(@Xr5+gyVR=jh)bx$LWHK0^i=I7;?dZ}K+fDp7Z+{;-c3vuAOJ6uOQV7Z=mjUG~m z)Bh3QvU5E;uvt2q<41$-6bzK%L%ew0JEzeqU!2wC1q|X06zOEIe8T-nN8 z1n!d>CkJfreY@DC3kw5#Zutsh$B#TG*+U{85fb=^XT5*!Uzpa>YJqcSJfgSz-$ZY( z(bS`<^HVL{ESUOvPMZX$V1*!bv}@)Y*&8#O=q*AT>w(U10w^6Nlx!SDRkLlLGG$cX zJoblAR*=@0Hnh@*FCr28JqS;u1YW|Nbwb^sSVtL0EmGX3{t!$<&m4+`O_MoU`CZ)g zUQQ{T6%2>K(g$YW026qLal&1<++x!nQ*ZLl1Mw>UU$xFi ziCO&-PIl1b4n=o$#A#%EOY+DrSBJA74h_@Smk%e`z_<##>#JL2%?;|ePx-x2_aOWB zg4pZt<%q^1XJZQH^MX1|JY6hvEcJbJuuijX>T-0-_g{qq)Ws&7jdMr98D}N$yfc%oh{@2RB46f z{+pH)sE%y%K(Y7qTHfc)Ql1+epK`|1A`(_L{UEYdhBR zO_c_!ZCi8Z+ufO^EgGxmbI(S8K{;O5(XBstD^$ljH^~?N3A!V(wT#+XLIiG%Frt2B6DUm^F4RT+p_5U@Eqar>w_NoRBqGQ z$hl~;2X}F`jjYQd31vm|%B8$K*%iK2xwK zug8^j2J0{ICoZb^hC$lyG7~vEmZ-}b{)Qn3{_td$RuNv~ z#iQ}b#0^q5>s4pK2RYr+NpU83>{R>+^R4yUMLsc0w~wSfnE7DbJ>@&lT8_)* z4#i%)Et6W1WSXK;1wAM>U6V$U-5p~_5qe%uFuLI7+H2b{)5KeX5}SPbL-sM+%5Bp{ z5$QjBj|J}g56*nU5r8uM%Eu}ks5pd-!SCwhsj z8{oNZwlmV}V7HzYP2Ychx?OjB(Kv;>W(JGcqR`ER>#s&J`vqfL95;4!w773eQ=%NJ zEV|e=k-H{%3-Rb-dYR{WGQ%DY^kskC(+lC4di6{t(dw+6MFqvXYN$T z;x}k%l7>{sAbn!jjAOfE&!fysNQbp8p|SG{@l)uG3;bLSJ85LAn;bZ%;K#fSj1+nJ zw>o2@yn-wak$5+i6{kaX>q*U3K@5;Do1_^TQEt9Uz0fb7_?1}Tu`|#cJ*}`i`SNtl zdW0_HaMt0TuVx&aMA-bI2()o09ab~#OE8&j;HScO=MgQ`v7|!z=FcK^&CNS5sB4vS zJ~Hic*48y_k#NG-__#Rir>17F21lEgr3)%Y*F%Op^Z`))BXdArEQHEKdm7CemF7C8 z4e=!oEQ>%HgnIvRrov#D9)o25=$Uq|r`Byx}6ph|=HcDVR;pQ?J1-gY+yYy)kAaa)T$vd(&L zUJtK@w2D=WT@=k#3@5IP*9RcoK8r9^K9fY_lx9Cm0ZjdBm+GRqw9!*Y&LBJ?eCCSG}L>4AWd)go8OV(?yL(nN-_|YP2^_n z7rWrH`uE!4cj=HC)%48VU$yB?+mYkfN7N@d$4C*GZ=});LmPnxEjUCOZnrE z0fSXC?1`aMl%|Lv%@$1vIP0`H*Wh*Yna+Nk!em9X`9u3({DfslHb_R|^lzDYyzZa! z*sYzqs&6q0Lrx`mF`VEJen3O&IkpRIV?Rv(JdAZ+w-&VikMJM;W8aj^jxs8jA_^jR zwvTDG6p%9=>PD+UXSqX>kX3x8#*YA9l-uQu{?(Sl)&2FhGKeEgc*>hDf95<+=@(rn zIxi@O>{cJA)`gJ6Re1L1Tmpt8ln~%f|GAMJCw={d1yp#ff}tlf07V!y@6C2sV4K&V z4ry8TwA`|o-)?Ly<8EQF^pq$nU9$zk5Db+UwSq8aoct4;E(WH>WOoyTvBl{*?$t6- zbMy%ifmu$i^>oa~nW1;N$NwzzB@gf>>cVY+6xjiY{Z%kuq7T5mw(((|KiH$hW%KVO z#cj3d(8)0^$Br(1T%BHLhKnpD{s#swg7l$s_IAk3?(z!T!hUAFr)`f%Wv)vkRAT#6 zzLeI4Wv{FL?S@-+Zeh&xLw54`13!oZ!|7tXad>Vq;q}$uW<8pZAcpxs#*c zTDEp|HGQVHY1m1l5S`_4bLJ+r%v5B|{y^yP(e%rJe%8=>ZsE6FjFR8J{5$fg#vQ#E zP3E+IXjuvEt3Rfo+0MFMa>7$Ay9As_)Q?QkWH;IAS|wdYV$B83s!JKWe z62CROp+ClZEXG}wzo$-$Ii;Ra;^QuG2XMn1s&8nM9)xX2;M9bRom3 z3<-nn4w23goDu=zpQGC0nJ|2sO4$QBS@m|4R}#jH>oT^MS58*>ggQ}LK1@LFamGVo z%PCNf^^Beh>wNFoJ% z|IVoCg{G^0-dpdB=>ae2v@ny<2o*b4sxF-{(ThjHZb0UGQL}BpvW`eLM^xibWx=n= zLtQbp$OoOrlQV~VG{jUuo!jKfbTBMjR>!?{u1H__P^D<3hJYuw zjWmOmlONpO(t5MwQK4SH>QOVcVk|V5Szca2r$sGCvjkgMy`l0gE?`YKq|IF37rGSG zSUJ?9^m@n%#m!E4VH5w}*3xbMLHgq_zInU=oXL5l;&dgGHilsrzA>lf#<@j)>fAOJ z1o$DZWS#&Z(v6fNM|>;KR*XN`JuOTf-4VjlP+aaZ$th9ExIkz%uDgP&LsqZ3uE|b; z9B(6Ow#nYs-;g@+emt!4IDhj_G}{$q zll@Mq&nF=VK=}2&+JTWSAHGcqb}^&X{lmy=JNaLn?GxLtefVwOeES>nG@uu>+hq#i z;v(ioirBI#X{&(B=v_1JOfGz<56&59OB7@@?u`w5Or31dl~8-NRwP#3P>eo{T7f z=`<3Q&02)?KDbm+G=6M}_TK|o;`v0Z~WdsBqazy++_rF_dm_ICi=l03kVxL{<@YL{a;Hi>S7BrWC)i9!Dc{ zAplE2$ri9rUOZVizv8TVLQ?w+&Q>o>_r)rT(-Ezw2^ z>{~_X3_o|RC7KS8UU%YbXU|}Qrw!Moqqj=FE~lcRA+R&;7ZgNR?rU#UW>38yR z;jF_F`lOzQzA3)&ks|>DHj@1D**nBiYqptxE=ILcCa2^epcYJsIkO}aqk*V09_)2J zQh2QT7(+o!7xErj@wxs)&C8hUAsR_0n3C0C^n{-DFI5gRp5DI1{&)_`tX3_ZD56Dd zN^{zw&+JGcOqiPDi{l||Bzgn_fSR(QxuZ6rmNhA^htK?>-l~)z=Ey1aw5OCcmj?ea9@y3Z{XKbL~c;1HDqFnAVyc%s@z~F-SPoa)| z1_*lj7MMF)PqMc3y0wIJs|2s1A+tCkA^1o+pb$XMh%+|YM56PD&oeB`+5K_=vg&#o1 z0d}BNgTTnv^XM(W>+*_cxV_GJi&I8CGFE9Wf1Oo|DmRp>+8fVaYN zrKC_2rxeQSe~I>W0a=<@zT6C28o6aC7Zmr_^@up z;2_$Ee=QD&xMcSp@vb2%n}H&X2C+v|R`6s6r_B^67lOR@A2=V%`Km)$CB6=aVq?RR zv}i6={RjDsS1PQ$z#R?Q+xymVP*9k1=gxc9=wju!hWi)gtN^@lLOF)wWPR&0G6sBK zx)1lyt!`w;#?Di91{vmeK{bb&p`cUZ#Hu9i2cvZeQ@^^Q#f5DpdDa+XtQ|QYS- zXZWItXn1~PZ#lBZVM2{P0QKzABh)BVE3up>FSO$coa)cC3}7$RjHICVO7X{Qy)3kR ztz<}{k)%%BFNFNdf$#T`7P0pczrc!rHJSxTlp*g&XN^{^Y^Hz{Kw&!$s>tWI-kPoB z(r^66hEHj3%AB;*Xl7B3CwjAtGEuldg7esm;Z8IKXgLT70n{xTe?X%bU3LdzNd0^M zc&XKNra4mb$8lF)H$m0PXnna$oFdhAuvzOGbM?lI>qEr-;t%&f&Xz*YLZY0E>MVK? zWszPX$x*A+g-15DgLzmd=*)6j#QR4GuZb$TpkeFepb9J{P484nOQhrTYU9}3OekV1 zEB^IR2sCD^%@xBB`5gJ!m94G>#|+0DM}PK?lxWi?uYQ{TDc$AQwjf=W(j*7SAD2x) z9Q32tUvUoxMhBxqvs;d2+vNhq^z!utbHkz=%Bkj1W@4|IQ?y;gqu*x#MPn>*X=Co- zI4>+@jmo#ZbvXhSb9(QrV0qf<%_X-Jl8ALTjQcDe9(i~z3D&*(8J?0Hkz`!DY0%2@ zdY9~tMdgPT348<|Y#a`naIH8tRYrb>1k_d=FTNhuOh0X^aBv{r*uZoi&kx%wZ{g&& zFtRx71TdR!0mWb_E@kNU;VN0ssE4ewP`gaVwPkJW*~ZYM0o@&Nady_H;b7Alott$R zxO%Pt(AXfP41;8!%wb_ikP};#6P%4!3Az8Ld*ry>Q!G9XyeC;=gDf+J2Z$eas!t&@i=;` z$ggF0ld@@hKr*Sqtb6E6S{fCN?PNbRc zc8A%LUyCBi$#FZRm(7>nJfkNE{D#0MIw*u zjrlOFVr<>f_3YgaH~}Zu^4!mQ!s%795*7EZtQ~gX@`aZ&h=Ju0W@xAhevCB1T}pv% zF!*)ato056q(=S}qqpArYSp~ayDJGPrS!ulO3t9=U)1kXk6%wx2*U zl%j#97^61^Iw<&DsVkWZ!dcyv76qiBx@-FgqgGd=d9+A3zws52Y{@9F&Hx^g6#Hh# ztJm|Ib4q?8241EE?*f8zjq}A#k!8FA<7`MN4_Z$|jcSiYZ?7ZD%e^KnEC+Q;ArZt( z!&9{B)(&`9MDP2GGIDd|^2%BEILN35xsHLFI6Cb?`53+dMCZGW7aTk%5kH;lSXrI(5cEs1_aR+ZzTEJhMUP9 zr#ihlYxa7z>vctNuWS}I{xm3?iM_aUeS*t=S$|9KlEgM&}2dr^b%oa*1_%~aO8Z)PhG>(EKEx^ z*!5Lmsh)W|NRXEEi^syOEg2eNWn+ID>7wrOSgW?xRWMNnu~|xL00~XI9>5P>SU!EI zpE1~+cme+b>iKPa(;&tasFD9}2|p3#q}>=m(6!X|9M!AF*S!oZ)0>HhD!br0CRL2r zz_M0?q*!9E@0Gv^|G2y%$SwnEW(h(bcL5PF^PH(d3i`}UnjNx1PX4-U%hE_Id&$10 zqHM`9F*#4im^4x1sdvEAQrW~@6-V-AuKqLbH`_e=lO2DF7_(baYCa%2hLDJ6lDI4) zcQTYStpKyLWP(B)h$L-o?KbLuX(vte9d|SB8jFfda%aUAZS~P4og|GPc;Rp_GzvxzI(_b%0Si}%+f(^!z+v@u(&iQQ47N_-WG03i*SSXwK7 zx8YHM_LEC!UY{YP^1nvont(W@QKe6S@O*3W-$O{34QyMA=4`{;ZM1cCc9%VLX`@wO z%&!$QY)EiY_lZ5@uPfW{>5T0z9o&aVWzg^Je|1bDE;ijSLDC9hY02P+ZOr&#w>L;+ zzi4JC*N*f8!$aIz$aPqmzZYc#eY1F9t&xJ>oiQh9OPlc89r~vvN_QWpEw|dvD;#2# z8J9uOrckCVl7(bMdQl9!b>c+ycXYL`&7X$dJB@V% zo?)l7c3HWxTsj^;gc&YD+8|?5p|RIKDCWbwR)${~IOR8Dr3?H>KnTG|7+x?IlWyAE zip5wa<-uK_n}LZx&ZH=m^D;AZSs8}SKF<67=La3nWHQ0I5ng{+S-e_XeYJ>OP1ie6 z>b1nyAc^g(Mw!)|}&N2ib0M~*f?YP>NYG2Xx|7c|A&*&+p6cfG+;u$C}nM!Dm9 z-IYAG5U!)*mtNo$v`~^zT}CM@b75@#+gCplm176o@k$~`y|9KZVhWy4yRJ`wWd&#Z z5SwsU_P3Hhbi+{fjfQp!b~>@FOb<#}redf8q0B*RCn$ZJPA>DpMr{L`TFzP!xBf6< zci$XX8#av<4KBhD&U`-u??+TtRPBnM z0NKYmA|nr;;uejIk`X@Fe}A(7IM}`TnB>P@EK!+Xa=-*nrBcnyLPA3^7`BF1LHMA* zgj{wt%}nK${+o(TDf5!W!}Tk>&^jUs0xqMtH{iq`Q@sBg zuEH`u0oiYM|1|2TDUAD{q;+K}NWP%nHd}KrAMahm0jj*$>V~?8_ zKZC_Nb6fDu(+?@5_1ZgK0eILhZxQuB};s9_OyU~&5qFbeTy z^3O?pZ~Nqsru>fZNgVu2xBIer!Kv;)+?H<`?Y{WeJu2k;$|~&>@~VT%ZH-^KGby-3 zg@62t&!2No@V%$rR3uQ~6!)SCU*-d`NotJ~nKm-!LqHml?yX190Vx%B@yn1k5= zQQM8~5j$i7d;xi*`lsQMPwkC{n8*7Ac54P<{KCi&l(O_3yS;vtZAlZw=phxq-V`LQ z!8&>MQH?}YU6nuNV>-k%hFO&3`^gRU<&Lgt-s0o_jL6+rIpMD1*C!4A8nlDX5q`&+ zt;fZt25)PZoJ%JcS8vMHM5I-4um>nkC%=ZQ{{Y4ni%qUoaz@kIcY z_s;~Eb4ujdx1J?pM0lJR3U(Rsb$R_;4F990_@?YV|1y81-=Fwt_Y=$&{xb^5ahDpspJ(f9AsNld2GmUq{F|Yj>2qxkV_BNr27!p zbCY}W`igxN{>W8eha_Kld-2RTgMFa}!mD?t<_*_k*{~6Cv(KTUG+!Kjlck5u>>o`B zi8%nU*P?0m*+-l`psL+utWe1Ru9394|(s+RhDwRf;=1p zzh1GMYRXr~xh{U4cevk2pU!Nj-X+kwgM7PGUl%kz{SzvmJS{fW)liQo1{qsY-KlG5 z($H8apda#SCcq-K-E2v#6x;zvp3iSzJJKdVhBzVwzt6u+V(6DBE{p_*b%pjM$&` z?TTzWB=J)DO#uF-n#Y2-)Oa4jO>xY=S#9;EL*t9AGIjKPzJZw4AL~3-iWjuX@H?aV z*79hS&nwWMQ_0Q*LVwG2f2C#fot|6KURnkF&aH7)m@WH0G7Za&{H@*zY+MOw}MYVS~E{gt0!w?#q1p+=Jyc zQPV|Y{qt@(c^8g=yt1E}jLpIZF1+oGL7n;o);7-BoOx|$(&Wl(KuC)BKL3)Uk*e+e zsLjx?iz%c-M#30wg@-*1&-RubQ#3jn_&!7Vk)SNQdP&Wrk zz%z76>*2d^7Uy@oXpCV}5zV^jo3>CcIj6T#MH(XF@nFoTehv&cp`K4&m)|ON?`M{j zdd%pP)i$N@b+*|*n97=rt)rKG>$Vej)l=t5kXK;P!tf5UL6Ef z1VpKU5R@hz=`Dadib@la-UNg|=!DRljow4(5ITg=L+A-N?7exCGiDP1V#McR#kA!g^iQ9$9Qyv@9N-J-S}mb+%C;k<5*Lbp5>&X7E@a zd8>77Oke1Ge~!oU(e8)7#SedMmMNL@rQTklH4 zHJwXW-SxA}3yM|{^m~7*iaxntSpai=jVBr#n6L zlm-GxF)y6s%_QXv#G&<<78PF~HIcQC0g0%w`K)fQ@A+&hYGdq0ZSL9r^~yFPDK6sN z()+k}D>W(m>1SU=tSsCGDB+LBUPM|TKlt>eDzeF9$eD2o;+I5H8(uVEM|DS)Imm_ih3TvJNq{z9+1Cbmx&M zv$E`nV|}P%LX%`iG1VkffGX-Jce$u_h9ITl58x9nC-x~5`!Lu!iNugJHY72OVB0>Zg$!;7yEJ+n3zhzlv#^HJ7 z^bz(&__*Dla;DY(0NIZU>mo6II2Mq_&$ZTn6sg`udC)V;;xY2rn%-Y!oRc|M5x<+v zUtW?UL%ep-^ikY~O=im62yw#Z9WpN5=AKBbt?;Qn@$MZt=|N{s-ZLR_Mk5o1EA&X2 z6dUnhC8#`NN{cLp#bz25998^R5M>qvrN5Khbz#d3<{8c-{#(E8h;gYcs@=5b%@!B) zUTf7^UH_>kWd25===~;1U6sD7ZU<`jjn^;U4SpIsQOWvl>a}BW!A4QVk9tzawwL(Q zZ&{yj3oVw~Ih7GYav{^oWQ;%Q7nvIn-+%KjbX0nH&tS8ly1qiT%DeoBiiMr)$Ew4n z^@@b)>qFvsxzGKx88bFfqFv7_?xxDA+ekS!vSDQ(B+M7^f~u-X(^h5nyByzq;MC4> zclXu{RaXd9m7*@QIFaFE3E6fLioHnjJq2OyW! z`3a2um4gxX+>V}K{EB^o4Wjp}rjM!Jq{Eq*DiIg1$H#c39bnd(ZDk30_2=xyng!%0 zMNdhg#v4PkoHmaxE;uwh7n=lRj*kgHCr1;=g+ChdF80_r*~7~{Z#R#&aQIA~+`h0* zdl|RyVBbEg7iZUt+>bmq7Pr{XLWz7Ulu+%wXz#gp*(Ba_{?OFCsQI;+l8qJC1VuhM znoeiWUHi0!vGL9NLq3^c9{qsM#p1EnU;6abAs=sM4kXERU55LM!m~&P&c_mF@BXf?j zlJ)OJB5L!;H3YYOL`i4UdcRMV+NBt+JX@Pp%SC~cJun27o_^w=)!X!!RL7npkcsEw z7RaMx{2Da1wR@e#Jy(QHay6Wceh-he9nRs~6q+{f7So*;C#8AP9`(y>ofvHDv@~P7 zu~h%!Rh)`i_NI7)q*p~lJ*hF$$kknZhqQd|NA3Vs&@i^|A47$9s8r=G$|d<6jlw{y zrN)Jvw!aWIHp^cN1g^N9Gvd=R>fZRlD=}0d%TZ0$!n2x1wlN7I+OhQ}G3eNwCcAs& z!mpx^!c8t}LBn^Cq$B&ryLm@{b1D>Bts22Z+x=lc(5fI*mKn!DOLp|$by?PO5nmeZ zI&@y_`$$$iX;F41R_RJ7JXCME_iX!4bl?$l8=`7!9GsY&(|oo?#D2PXZmIi^qm3Ll zsISV>21(I42YtbmV0J=%zgVhE+1wb?qsjb=3aVvFrme`^M8v`Ul>0LiVmpyMV7qmc zy|+<3pPW1JrBQ=&4qIsn|>#}~w?p$rzBrKX`d;*pulszGK{dDtsg=jw+<6Xe5*{Inhqcv zoVSSB+!Qrx?5&pV?PgfqBJVeu#UvA=-PfOSwE^oA-M`GY=^Whp#`Db-SN#upDQr7`Dmk*c@(f)A+H5)l6SHX%r^sP9GO)(*>#S!|1#oWYZk zf(D1lQ)ML%BQGdxJp3GUCGH(9PMrQ4rA=dQsRcbI+1`)f=;+oi&klFh1gk#MY^!)+ zkMffu$TI7QHZvZ$vr-`Zyspt`lOd~+;WR@HJvQMYY~>nfHl-t&ar{VoobHA4i_Gks zvC6F#*rS{S4WU_#JlADt%c$f7{mTNn(hY43C58~F{=bw7*NlicfqebT*0a`|g@W07|pje7jZ z0|_GY8@S-Y*a{p+;c@r8Q4y0-4^8ycw7h3D$c(*yX0>n?c9&Xu^@9n@d}}d5uhjxtcC=vIcU_gHV@2(su-~Zz}jTMY8aF#)!YREqSFqqDT)Krz4l`g6I z6Dj-l#keaImZA8!zU$fBORL}hTV2_`W}WNj!c{0oWq>wT77~#CsaxqE^Jk3D{$J<{ z{fOaue*mmCx_d8j-@h|) z3Rd*BTx{<{)4TCNLZtBP3t+d1j1#I4B&zQ{pVL9l)%0By#Jf{{{0dt%ZYyr;{S;tb`vYh--cdNTl_|s z3DqaaVzJ22hwuJw`;F{J?eKpxjaClr}Mi-}0P)zy1L}&r%vNd0#_U*Q_Fhc~etgn^pVtP zb~W+4mQvM;<=Q_&4_r^%uGV1qd-LH7$Rii!6!$yDN(S zeZUwo|GQ)U8yU<_Y{&)3q}hwm_Lb%I<%xK4H|>VT)DKVOF)`)vfkA|JNouYMbF~>@ zN(+ggY{g4>zDs^gsxT*uKL25`uzQl)T;~=QUO`vRUc50&A8dHVIYtA@Gh^N|1hCwq zCaFy5u1A|);#`G>2GP^4%LAEQKVY~)zYnx1YDPZ*Q^+G`a|VM;5!6AaK0&uK{#32? z$8Z4k@fZ+w%Dh3l!$8aJMWUTzA=9$};AV+09>f9*sc(?BH#%3^_GTJiJX{H{8CD13 zSA~M`wOju1_v*ahBug*hz1(taQdncygQ7lLadQ`e*p5g8CSgW?cPR(f`}!SpU1^QY z)Ee8`I!-Q~8gHyr;+wb{lHO%@0Et$RBQ0YL0GK|l+H zT8VL!H*t1t5q25&z_9423cVPSM2{pl{9xGEw)=}fMafoajW@#t{-J#k=_C;Ch>&OD z=H6rF9JQ6-wjE+KUOU#T%ku+>{O^E)p=gX@p_QM3!Q0RO^8jeQGNvhI##Yg#+6HBn zRib+@_|<{Qu-|-{8Q=1)*DUtFnu4fJ#{G~@1EBOWu6OPMI9ysfR%z{nqsj%8T2L|v zW+#!p?{u57!Z-!X_ebNs7@H)&lkXlG>+WyTx6N7CF?O(}s+@?M4K=S8hI2^gr_;cwZk zuLcN)O+kLL_b3cj11T50`Y&ss0yaN;-`asP1j%%O z{cp!%2)E5gHWeg$yt+BfS~9-S(l-J-TM)}GFX{74j4cXXq&p^B_IztVK{h&ez4}`A zv3R!;Kf>#G1lg=Nb|Zf0Dq6-Dc6-Zjcn^mPm)o5T&2HIpJ=ftDHdmIzul|5SPNxis z2tXT2LtX&>$^J1$M_nD`;u53Mq2{PFuSDj>Ki{n-+C@1%kpH+6XXCSY&)T+Y#{?fS zwXUCw4?l~Q!y`e7ZWzQBgwTI}Ko2TDr66 z+%*?Hgf~+pwq}^n2)CWWMGd%bzslsYrnKxpiSPW(`58rvd8UUULkevjUpAcvU5=$` zG5wiP8qtmT&d-wjku%ET%8<11d1*1VSnfwZ6x$S8SXEA+Mq_p6)5%=C7TI12G?nS; zw^U?`K?z`XFy_A?S&sKqFOMni?vPdLIJXw=az68P>}PBz5>K;;9S=jXJzXiawRIAB zmR>wFGn~rpa&X!fw^@brXzMV%t*$%Tnk41lnP`%0EyX&cFKujdu#>Tsh-f8jt8MEl z7C+%199)K{liSqkEy&H{?Kk!5o3?rhqIGFtJoWRx1%!m-4Z89h3-TNNDs+;(wC6mx z?`BFJr+m)Z7t&oBkL*}m^#eucQ`ON!Q>&))GyL<48SUL-Xmwr7j?L#y-<)hB+d4Av z&$o+gv(qFcGo%7MJ#TK_A*xp`XZx-Z}ICbL_8CK znByc6Z6z+v5BSEl@yydOv`q78`dQ$h+D0l^eVCrC1_; zLuI$IdKiwQHH4{`Xs%Vra|q=d1JWLm95(Y7Y`+WE0|B-~?0QhBsBX z<~Vg8G`cO39aWe0qk3!Hm#%`OzqH>WMQ)3=ERZODHk~f`yXwLsaGj=ffn*KeG_YYD z5?Z|%EB$0$E}QF}c5z%8vvC!RzHcRrqVH_#R&Nm+mYJ|S^>uPvwWb_LZ8T47heqQY zj1P8o+p7zyqhlXMVf#wD#vQDj4B^f*;Y;J+@?&|+c$CUEE52EF8FJ`Zqse9CEtJ5l zYPJpTxcrO5coyuNxw5;;MLL86E_3a$hKbF)yS%b%t8ikJYofh<2 z$D=hufFoW!!d)URpOZG3CZ{-35y9COGoHw!ac;&D&p9#! z$WroFrDE-wE_aSo70$mYFFNNYpJ^o(uU__)04H*Bb8~MsGFL6*Zns&GP zm^g3WR$9$&F+Yu;ffvn9wK$6$vIkdiEscQA;e)}s#^UPZie}61HX{Q$gre2CRw~zt z^4pD(Xi3_Vzx+-uoBe&Bu&TvOJ`oY@p_s?P=Q)Q`R&yq7C>t{@t;{>D^$Hl5^rY#L z*aat#LCpE5%D0PrD7PgYUQ}`3JIwr9vrbGpXr@eGn{ilM#N)9(o3&vks;k)osDCdSXqv=tSoKhC36+MMSg24 zQARqpB{(=ZnLPHxQb{QitJ4S1#5BH(OT0e@Hi9|$LHaZ(5|49GIac#ONS4<8!UkGI zxc2SHzR5&dALE2YDy`2tx6;+w`)2(8OpHCPoo&>=GgUF8vBR?Cx#?K1_*Z7udykJd zNDN5~7bkU*YGf4GZKJsmUI%F2E)@DpSu@^)+svza=VPVj8D~u0E+&_C^I(0}=w6G} z>vS*T)><)NNTLkNv0J^(96MKLCrmOR!f|l3Pa>_=z2{Xl5*cZT_vBvfV9-GGYVH9{ zp{5nIger`gPyU%o^-MltxVDlDf+ZU36VX?e(y)40t0f_^f;c;e^W;yEX=tuW#62&3 zDqSACI<2Q@+4DFoD8<6U#4GoBWvS0ho3a?1Z=g>BzPeLpMN=V6N%0;eb+Vvi*ExyY zt`D@$%zIq2ano&y@?L9mKLWzuH0NZdcf+kwrl#gCf)|syu8DB*wIwzp^vwixIXSgA z9BC`lr+9`hrwjbZizZ&*3BqQeA&KZ>X&|QQ~(0 zIMJbYXm)VW)5V#&Kc5HDQ!Hj5x;6GAz@jaIarUD5_m1TbrZ#hw@0qZ;`)Pu$>Tq0x zsgIMeaHPD+#xM~4Va#CdHJ8$yz8TwswTdP*znMnKTZ@v?T%@Eu9lNyE(h!^|CDR@= zb2B+FA4f-5*PF62_jwV=sAtX(J5L^U>KZrcAI|T z^RB6Sy{C}}?ISp2=&cU}6)WM3m>$x&aLC0rd;?=GKbOe(jXx`xFW7o)tG0gu+{ll1 z3FsCu-_kY{IQf^hrZxetbl-8Lnr3a-oM#{VC}BV&{&=b?^F^Lg->s+lf$X|U{N0N= zqVqJVEW@eZuDSV_Xf6z(hCw#KBi(ponr?g(SRtk=A$CSeIJFG5t<(0n9!HEm zJt;RFCT-K@$ws#-sd(Zp5+ zCOOX?`1$g>=Hw3_H04WtIE8O*Eq%U-yQws^d3tgsAU8ezDFMUBR}jptE@FW=Z$U0|kMQUx zXnt=PITLeadu7u z9Opp~F2&UyXgi2L9V)sg1fS+Co`_M8V=kb~ywqaZPEc;ujqt#GO623M;i;|Shphn| zHT+;4yOr^y4Rgfys>uac_`v<+M)5mndIz%HoLn@t%UWz3pj+tue(D-dOpnaDM&Nf! z?wL@_U2sk8dxW|RHUJ(#^|f*aCIE3oH{;7Y?I#YUW!RCCHhK%OkC0KSj@V>vsxzy! zUohfTwyiQjkD`9tUDRL6=x(Tf6w|e6=#_3aa6QbTt>@_aAoy47A>3wh}32PDxd{Z zx<8;}-QLvm7iSu((W8BLDk6Ru6UZq;g_Yd+Dv9na86KOQxuD|TCqg%w|2bO1Zqewj( z@A-5(R<#mNC|F5ibCes1_eGV?J%y92lgq3K#ZQGAo@(lc^P@d_(8Savg=t%^B(mM0 z$M{=2k2BE5$+bAJ?uo;(qzDoN<#wY&Bjtt_bMbBTM&2n-`Q0Ah?U;D+g`#tVdefpm z>}7gnzI!xn`Zp$o_)h6oxy?9=wfeTubu-J%TM2#sjXp~H)3-WR!x&rHGC4!O&_2u9 zbJ~Z?f^KCGwV=+<-#h!PBVYJT^%LqdgQkLD%G^}Q&YI{p^ZeQ-r@pFz5o?8c!m%HN zo^)~(htvc`er14SHr~pHIiE8dbM6fKYz#%9s)S-;Qd;F5XGJw7Y^nR3n-n-{oQz9p zJWF^E7LyD9P)!G?<>)Cfu_R`WeU%?Dm=g6~^WFXqM~E-(mU3=pXU58{b62~#ye90h zP4|^h+IM<59o2B+MqN~C#87oiAAw(FQXgJ@P}Rr+qexyRVf$+dX06pN5EE7n4R}UB+daCU?s0 zP}g4HtDL%C+~+xsG$g=>3$5n$-|D?qRFc!zYFR=cLo@*OcX?zFHlZ?d);HjGvd;3Z=GmKtjAn%41sX0NCwY zOElV(m4jZH06Kao3#U)swm}u)W0bVCiTzn{dFJCfg*wSlvP|mT&U@TAD~-wLdy9c5}BjyXPbPguUn-tYgRKF%$wK{s~!eG*Mq8kueTbf?zKr6tZSFKa9{(*kYvESd5}X`-XmkGUK8ZVCpZdh%`wyZr+ukR zx$@M#KVrc|z1cl#>>l9>o4N81CbB*3j+VPPRSt|VWn-)IocweXhC&Q*ATbiFSD$UP zaXS25;_BEo^u`cJqe(vPZea*&4gX2R+= z*#&+&akGmncXJa-`=UCYsiupXdQ|O7vtjtW{kgK`Q$5WxT5Yw8Vhb`vCle3x2--=f zVar^+l>C>1QIaR?HlDni^Wh_7$Xd55a~>awXl}zTJFn{>0%OU$tp0#%`Ce&{)G&WG zhUe6{%WvuKeoYNUZge5bTAr7>lRT7_Goz^Ub2i=UG%s}9?qV+O$1Y`ebG^-IcSa>a z29;7Jk|-w~Te0kUpUcrwQq{H?Poix^3-X_PVe|)lGQw*3v>U6aE$*p%|Ln_jG>Y8T z?}fIYQKki}XkV(m7bkXUi@W_3)bSK%SyFRw;p@0&K8u5Pw^BuaxB z_4dt1GrFpfEX?us;fbciCTTB{a;~h>HaonV6|59p8Jk7-(iOiG!Xd(CZ_c=!$qtAy zL+T^$8{8I%2z-+@INd&COKXnwd0OhZ!GdL)+6`Hq+~r5{zwgIj;5adRU(XG}I!VSf zfucs5l_Ai>ui*gu)yEqMuRjJ5t=TZ$+gb}%)l-@L~`s_r&L>{z;5Nrjq?SX z87=clGRP-Wj9~9wno`RFq)#vt5)jDz%{Dz(Rim2;Y44g1ZKY;lqiytl^z=1(>PzIH z?PccL{_z`&7H|qKGd5SwNP4w1NOk&FGdZNvKX1ym@vL@pQt>k&GLASv`IvrFTsIfv z%j9#?n;Ff)beW}!s|HvhOvUh=Gyn54Vo3Ym1dy4s6RKF-h$2=uYYjVp>ZPN@$fa0IiO;?abdIgIYBM4(Jg#*hUcg77ph>f70nI#qwaiq5E5XgE zHo*|wKFn-X3`uD=e!91Yy1(L1@2a7_#LhJjo~as*>dxTGwuNf z+sg#Z$kaU6uR4K}Rd#>&NI9q0I>hnioRN~Lz?0Ob2P<6eWxd{yiKz9x{PpoUD#>7R zp$u$YaR>t4{gK}Z1VWHxm)G^TFC93vK!zReqJe{H+~S{#&Thj z7gH9o+C5t~{9A9De-z|dB;8uOtHfW3dD;PI^vt`9^_BKIWR#zQL=(mWY0RP$Z;9Y| zo5`K$KzA_oynmeP;bD^-TkTnS4qOW10Ao!xStFj`nx2#v7F`58O(*g>=3nIMp$8GJ*yR28sk?s~zTJa$`u)2DKtqWI*g@B8 zm3|;#@;vi`Rc(0h)vU}nhCHf~{A#*wkCX_ng44Y=*=1MaCb_G<0UWMi&3GKog@Ok- z8w-fM@EHBW@PQ`F6Le-c+}F4f53ahi;Q~z(-L064+lUI_e>Oa)<@!Fen={_b1P>=x z*t~#qTmV3hBtugi+=f1j9=81tSj4~F2m#yt4ql)xFOpUy%2+J0>t#FcL<{!#wRwGK zqQ0a-rIhT7j61v(@7SkHIbO=oC{C06FRffElQUN#V8-+(u9HPGv;Z{5@!)XW9ohLuzHwY2QYPX{2t+zGl`KVOGe};@W`Cq9onTAbB$Hg+vq(A zmKD7$;Z$u36)r274aX^Zf~BM1_C=82v}C@O&UVM^*2{}rp`K4WzI@}`nD(LAD}DE+ zHu%5)7+);bLXksC*KU5i z_U_uS4AwByT-WHfZqMsSuaHM&om0TeozyPZNsu&8aj?PHfed4ho6l#LAhY zTDE3cXb+g5L=Q-uJ>eob!%CT%ZkPGyZzEwf|GwiD0!NYd7!r;ZJk1grar#7`g?N)) zL?2%=&OkN{BzQat^valb)Ls*9E#+okeCn3p#4s!0#^P=_G5Ag5&iCDlbDNut zZ*!w8Q@;$bJGSWOlp-RxIV-C%qT2?b3j%8KfA`b<{(J1OGB z@`X%E$G4QPg3QXdcP4o0qcv#*94ldo8~&8##NGL7r}B)Pt8-#Z3!?=XH+o^S*Obop zl~R3FiMJpq5wNVT>Dp2GA;T%bDcu&^T6ax{+vQ5r%8J-g~hEp;+$EHdx$Y?p{Sb=U4 zUCjoWl0oBRS~553j{Zk&QE#z>=45*Pk41PuQY~Ma4DrD;`UyaK#z7#T4py|DGqma%Hu*3)!~Su_Y}jd%GmASgNv}?7W=b zEZ!^+=G8Em;l47=?kstuhBurg^`cAX{9_cu=5muhk5doV2N^7`y^oBt4IyB#q?NlE z%CS^He=u0yTd-RC1Yf&ZDN*9>>#05A$=&pl%cV^1bSP_pIU4s{jE?E`gXn;ol`n?i z7n?iyf>Qlt${+FcbRQ<9yEsm}$D+qf`8xM2$whb1rww0{UgTE44>AxxP9Iy`sm%AU za6aIbk^N`t32mW87dVQ_-^yp9jX>Cx`V=S|X}Mz4dDg`?5yXhY>g)}n=52x~zN`6x4!FV;OW?)9nJs?{6PzKaq5 zJJUpps-lHHRr$PTjhtX4NAjjfVT3HgHt6|ZB7iEEqQD{ex&G9>lrx$6Z~oB9=0cxn z>Ol)SWo%bp&#}Xg5SFcra<+dEY57#O>Wy-FG0xrP#m&^9N5|&nF@BXs0-rT{7Cf`% z1jV{1y})?-J2Wd?@j*#B4HEA7;li@d0GY_;U-I=LfrnQDt zeK3n0#D!Be0{mw+<>djUYP7*=;5o`?Q*x;N)SaeA2RKbB~X7 zScXCxfI>*gHc!R}!=6wqix4Si$jA~>aXEizXLnaVh5|9HUAr^%^hyCcu* zY`k2Ty^MW!S%%ayyLBSk)C)0H$su!Cr-OiY{f?^{`oRClEaxLmLgZA%L9h~CzZ4mi>lh^aS}Q*t4FkqV3jiHF*o5)y0$ez-Sr zIrfc&5TQr*;!oYR?r1UknBchpi5J@p5KX8wW8|&O7F!i2e0mRjFgh!}-tdw=c`Wjg zwi;Fskm(2)m}OmYsS*x3Y<^oyN!v8r(@jT9OL?N#C}H6E<6*^_)jE1u;%@5hI4^hd zp${?ZjBh*)+VK&TlWPjq*7J}vXidzpV(R=A%-c%D!NkBF!)1~nk!=>xh)Ktsp+ur} zwUl+_T6;%A=ymeN+aO56v7(BWhO&F<)|#I(w5NS}LBn`z|nD z=_hxNTSE?PMKrLN0`pgaX2CC|A=C<7G&|t9^fy+T7TCU5G~sEF#*Wf2Ne36M#6=^D zpLq-C`5r48V81ex^XKP->lghWR&e7JO{yc4Nd6D8*{>G{HffA=hEdASnh0_xHN3+` zvVm#{y1XA4@FF~F^QP<-+b~a0obKQgM<1;-KUCf@r8R>vV>TeG%qJ@5Mzpn@4w|P) zx(`2hCdF4e`!VEgbI63SxK#kB-)~Z?`ICV&uF)Ld3A4u^^shx7RXS*NY%C}wL zo!kPKC%2hrS7YCRONN#nfD!L`MtUQLvETq}-G{TnK98>>@wi0}3`*?QcUd0$nbSWf zlP!9Rz4Oq+B1KAw+*5uG<$?fOPbMKQz#via33~8!6K8<02;~Q-I9B$%O7d%)=7F(}6 z{~UWR<-BCu4EAqY*}M&FjJ>lr~SSI6#PbC+cJon|2S&&tob#jGr!Q)~?mFXS3;cJeYN! z`8pdM6F;R8|5El|-I~Dp&6YqKhxG+n!-GAd*>`{FYX?YK+4iqv-zi4XT+#&^3LhbLXPd~8MVX-|$25s%HX}=jPv?dJs=TA<2 zZVD8@G(~B#b3sVAW}Ttw6Wh$g zEQ<-AhaRDELlotr`Bq=uA{3``qn)8ZA+A19ASFPoA<9)Ue#-d+zM%t|YUG+7R?KKIQwycIr<;?c$b1#Ly*`oOw5x9)HeWSC!(2nSa zP>v)hIqTyELehpl$2y1gnSMY-Mn`K#Q;x1iyaUJfwRn(pbilF8A|ls>6N{M7E6LBd zw$9qE(@dnxWC0BIWJt^EWpi; z<>USf?62(;i*k;!i2RD``*Cy3Lnh=+dW^DohQO44RqpJVJB!)y%Z8jI5)Z}~47AN| zn?_1D)HlW{H46vxoQURU%#4=T3y5$hk15^0A8QXbMmbmjefFxT%;SQ_B_#vkVz=UR zwQieciz~m%=i}ybT-Io2i!r}npmh6sa$0o2@d{Qd{I-@&={I13EG*9gv;$7Hfhiee zZC|Q4Nk%|o(c?Ek-f{|o((&$Y;b!BHplIzA&s=@LByH&m7?|ZepA~vkEFzIPIb{!( zZ!?yX8r>4NH!oXT9Gv*`5Y=0zT>rK+4MhMconrzhEn$44M=G(p#cuaYVxkRuu4loT zC4G$XjkevN)jd2AktZ}+xX~v?u=vfzcV=CMTmn@zcIC`> z_4W07xb~JeZ*&5_{OJDS|FrJJ@)uJl6(a!KND^pVsGD)q2IS|SrJ|PyadyT#`L$}h z=v{KAVk~{ZcXfIZ3)Tj`Z9*&3vKK24#xo9TRck$ZF zHJHQiI~rnpcLuLyTJ?y|r8YNl+wBRtW;{Z7xBh7ZX919^Fo#_^4>ffFII#ckR?NF= zN0*X8o{Y(mqX9Vgm!b~d)1HUAS-qE`U;;ewuV2zXa@=$(M-?E(ZysEZ4vK4k{jGz6 zHg2Ce(C)$euzlvh%YVh51Hban=yCx-+pr>Nu{47kKgO<(ZI$5o-k&6799xu)PYag+ z%=6bTCBLdQK6!KgA&-C80n@CXB9d8-iUv-H1b?>6C{JC?WN|=Qcm^wb{@j%td;slwb5#l^}FKO9iM9K@Jq|{|hey zX3BD)y}0kgfJ_b~$}bAMm?CdiLHF}c62SRX;0d9B;l=gTf4HTB*guICcRJTmB&e-- z?4R5RS^OUkEP4S3@Mas3v^%dUPlwQvSV z_WY(mQbxjV$RIAB#X+C`wjb!eFLfn@G{ZlGXspe2gW%3U<5(dcl(K_Lluzrhu2lzU z-9ZmQhVQGcrknx(g+1U085`tGM97t-vxDzZeklg@&#rFd01u zhAO{{`fDKxjamU8pR@>uC)o@%!>R zmki3Qp(`1L@g97k@qG?}wEYZ7M{^P@AQEGHP?$HuK+gRTpavBVywe5%#H4@#H@~NV z0R2ILADVyFz+r%o3h(@rK$yWZFR-syWk|dS`9Yz@qCuF{H;+KBB0-od4?g}U$<&)m z$b_eYbl?0ZHacON1OhaG)YZK38f~Qo5CsQu0RO`-bnE9kAbSwI-&yv!-lnvyBO^JU zzou<&%TN2#SB7+d;eC9NzA?WDW(|3&52fU=fMbpX+gI(v9q)0aUS-`B2U6Gv2SHk{ ztNPqK1Nzpd5)%^WOW4&k0H@7c&?i9x{uikP6d0a%fe)no-$-GwCv}}*AAFm-wd1qpUmOxy5C(|ncPM&a8IOwt?eynzAXZ$t(DS;f z$tFJ`MXX^Rc-arI@lRIck+;kbAF!7fFhRPn!>4e8rNN%7)b1r~qHYy6tU|8(hz4Lu zuAo=toj~6aO8v!fp(j2>#-sUipgdoX3W+K!~>a?noUC^mCc8>NGI1 z>TssWrDEpMkvTc3{gPm4hzG>xrx8DPvSYeS+)wN||FS98E z8!k3mf>=^fZ1dJc!@^wt#$q%eoB=S3^_B~{kjNA-Sy3bHZ#SnGj0Q3-M(psCE*BT( zox=58kF#&w*|_!1!m}B8D@P_A+*10^(A-tOQ(?%6W-f?}M@sV|&o|V>DYRJ#*fk=s4i1GkMbhCp06~x#%^< z#`L;Wc5St;kC`xZkykdAyE-RRq(>tT5Z~-7WE~GH<*KLeF@Ix*kM)LfAiCx!Ei|3% zygn>f39i;0y&2D~QBqO!+)b7dHf`LGMgw8Bh99(;7$ISFY~-rwW8=)pPA`onu{S0Q zTFVp84}UT+4YF(Gg}VVZpU!u`yGG0YwuySpg#pqiqz-s&NKvY%`v19v^Ipg4JA-R*oknugSr^BLy3F_L9 z9i>KOjBA>mAw)08OO24x>7a#{@+*D@vUbK+W6*-V&&NHs&OPUHQR zrGS>H5Qo<0bESj#-$xciP}hQNQ{!}ds)Ah5CIT2nf&)CL23A5h1ux^`&`HV9CepKc z(c3~h=^@qD3xa!()Ew0S6T%BGGyk$HX&z`c$CsOT{q+HFd$!7Y0g(TG&LF8ai?qHV zncX)zbRrz^v{P=^WdTH&)vTxjf7FClmsUA`!0W^<1e61=@gM>meb|H?8)mkeRLDp- zPado0%S~#?)dtI%d{DsPQ0~`kH_(#t3R%nLaN$zr*2nHJ{FHFx)FGg4sQ?V^dFQ!% z;^jP1YZQx$4eBOsE!@pFihe87*G5*d5=TF+<|$+TS3N1*s`21afV)u#3GgTtKWbJ) zUnQzyFi54&o&&Y|Vl>JzvB45Yok)?Ea~v5!U-7ylyK`S1#R|MP1!fAaR-|_en(i^~ zbCZXsRo$KE>L;FcYAMZr%ODzL++MNc^^|N5JQAJ%&~0ReGd%063y^8n_<&iZ*d!mO z+=gCo$@$>4zhJ`ZRTCpI?+v@iN8PTY2i2CM>P%`M-5k$96$QvLFbPOTjBkm2_%dL0 zqv@j8gKyd)_IK;zTwS_0f<7OiwgaM;1`~?j7$GIZy#xtdFI%;Zi^L!7PG6TUvgr`C znTc6Vn!K{AAvw>6#gH069$9k~!DuvCq(A&e>fyD*NIj6W3I9a8uIb6%?50aM$L+da z?~VDo@|)wu)dBbSsH*X~OWK&rSOqYHzixu6fN4!zS%X=RC>TRwY>epl&=XLpUpAP& z!3fbEf$$K(FY}<(=|OqV^!jM}>a0DK)a!kP9IXBGT&(D;4;Kf(Vxtin)Y3aDj;_y- zD^&wC9(kaD!5(B}9L^X9*fZAL9~h68+T2AZ5}D}0jF_Jil*k{?H#t$|x<|j?i-dc? zfdwEl3J3r1E2aMf?&M{0R@10;_P+e!vVPcSDbQU$9jo5i(IuUDI&f8n#z;$3nSe;; z7d;1N%)jhqth&AxTZaKT7XArl-q!d8z?R#S_tQ{x>nJI5v5HR`d@%4axJ2c;*~FiZ zGQkAn=?h@Y8VQ#7*)CuGbuM`A<70XyU`D5Us3@f8Yd)7Ds)qO8@dkPFMDJY}23>mh z{@j`@&lOhxlME)hr?^wcMF^yW^xU6fQ&m#;*8(u!QHWVslNVB(s2&1%c=b1n&Qn7X zdCgN0J*ntSfRXnB04=aHpP_vYBA^xINz8+`zF%&JKZS^gN->>O@P$wNrdY!f{|(t$OGwT4yucz?t=Qsy9NTd0O`k=7i3rA5QxC9MH=)_Sa0wnfW2y= z%OHEk7a{hdFaL)=9$W^+nfEJ1P%St%`TYWkOAIoY>*^2z2OthELkQC#4z!^cpq2#e zH^@Y9LcPdSDWFK7z5!k6%6$-E`(IEjfF1Y$Hp-sRx}c(AfB&c+;Ee82Vfjhm?LTy) z2LVVA1uftc)S~-j1X1J(vCt1uWCivsVEvy!3ig{;g||Tp9)L+P>}d!H&=>`>_(>ZA zCUtDEqzlcN{HPB!_2-}=Lzj+05<c503iF~jV`^oh`e4+pXzaPdwxm z1IKwG=u?AsPcJ^1J(2lsK{_o;p@MFd4q3Ia^*LLOUvl@x&j*sA9&5yKy$Qbo0sfOY zAjuKNw}Kl4-n5M2T%CT)__h>TtVnr5Vct*Qe>roJy8lRt2GZB@?t6e!+GaM3?Z z;k!Tq0|Zd0kAwmXSsDA_NTFD?TaIceFy!@eLeuYt)D0I6dt{eR1VDJj{)DyNnnWLd zJL^xdmAdvELcY=*{=>ec;SD9}eLMd?&tS0<;W&fF8Ct3t-T4T?M4Y z6S{i6XrTp?B#70zzn^<(moc zeD8C9oL}e1`SHf zFqjz;`pKiyO3_4B8s{tQ^iJNBBa6LZBsU~`ov9_x2sQA=5t%F<8E;%}@&o(gO?Uvy zQuAB`sb*e23}q`5#1PY2M#rGJ=P>x#IIrE~xx&&PA~e!pU}ueD*!cVYeB?Xm8h&oQ z6E?-iZWa~hz+U0BQFVp5{KsqU*{H*mhMw?OOULp7*X?sd10v#&hlfs%oMZE)y+X_E z^uu8?b6Ccw%emrnR_dE=H}%Mm<*!dU(dfGv36}bbML#Yw6ngm+J^X}rz5^$!Q0l@ zTm5VICQ_%_Y;bG+p~;>BQ`fgcLTz{k!@yU95x2qeXm%dXy6LwAbYe$GfYQpId#bWXE6Y4sSm47)f`s|46m7H~%j%Sdy<>rQ ziXJM`8DTy7=!IiWukDq&T-wHDBC|6b zWOr(#BRM)C@#Imo&LZpX5zZ6ktUq}gCJA#!iABVfOW;3Y@m8A( zYGWlqVtL0aJBQ2rZ=b8WH9$j;a!g22+rcH4MT8XafIFi$u>J%ollnXo9U%krsgJ56tBq=X21B+tNh9Tk zYGTaB6@gb{zU2>Qr?YY0E5fSwRX&rS%Cv1ag3YlEMw&0jrS97fh0i*IrIE(eD++|t zY>mZLNzvFyxveH@wm=tO-@(lQMGur7)?#dve0U`0AiWI$%1i^5=0mbGz%ot?9UUFK zY4Ii2SOQzn*5vNqn6p|6ny^WFk!hROhC`Y?7scUtD^W$vlDJjsz9FY?qp52{Wo8c2 zkJxDVvMM5CpHR;C;Ia}$tv@rD#Ts9^-JhJu%5`t=b~i$ON@%%fq>3#uRsRbIa$klk z+D2%*CbGtvM~Hp9iMW_f8@OAECRDNoZv7#;CxD5M1QcOr;EUr>&9ay1I0#taNC@`7 z>j~*$_ZZy75(ou6gPFD{`GvsUO*skqWs*YBK5iWuCt$3jJ+>ZC7Zorj&JkSlra(rn z%+XPIMghk!K2%Uts3>1GkvKHqIGB<;&zz}59T{w7^d}&D?;ifr9O=hiWyT&@x6t#Q zQKwh7S4DySP#L?G5z{5S#S=Qzz+!{^_V_E(<||tHEmNsP(P*(9P7bTtS))XwK2cSy zNL$@^E!f>`aKe~phcdCufmIT}6X+W#m)ORhUYHvm?I|QJP1;gnOX(ItZ`CoGY?(>N zTa2|4o~kNF2m7ev95ZB)Z=To>J#cgyO=)}b_Fl_?L`-Eq{o;G0j9b+2qEiD|9}CiC z=pwvv?%6?QmUA+W!W^jWnzuHbjv}ae;sDVau{TO0NIM7m4ytBxadBY-2RpX2vu(wt z<4YZ-8 zz7%*#-?@$Bi>ej2)e03Uzc-a7zqi#kpBQb!o2aLwv<{2vv=UBK8``&!J5hgY-3F4h zDSU^3+nITb1gpPQZP#pDbv+(*VBaYSYxeH+_YCxvl1B6{CT|a02<7C4_{LV|C`pw$ zVcloO8SugXI3#9LmiMHz^-B5Q*=p;G1q&OtAs>wne=d6U@?IN@9Vrvei=;9eGxBP#@pZ}*wzZxu2WN2SMSI&n!cX6o2Q0y<}Jn#Wjd$XC13{# zHHbdth);3;PD5h9Ahi=td8n|<)F=V=Da{FBxw)R!3cR5SOYiiBw-0Dyi${L<4^`%S z$}t4MEOdJE64yQ4WVOMW!zT~*?nMPF&_G!WFcHO9@Czq!X~lfVn#y5;*(EP!fjc;I zak;sLJ|kT|qL5+==Qvbz7nPMQ6nkXQqR5bXrR+;Dz;hEl97@5|@xq$I+;1UC$}rh@ z2}pCo=p3prk%cp<*jCH6k{L~Y31ju?tsox!a4hHSx*D&U@qIC*FBy{KHiylnW1?Et zdW(8A{uMoH+u9o5^02jmu@X}9o*tH#mnn<+Co78g5`UeVq}5T&+|ZD4aF?fkRjYZ+ zD1@hjoqYfh>8v+gl8Y;T^I1PDeB$kw>*b!ikyX_Vo+SQ(2mt9# zHN}N_joGb@oT#>>wN6V5MP;iQp*mP6%ScA0554--*Fk+@mC;eIuH+%%vGKg@To7hS z4I09^ZyQ78()32zj5fgu01cT(dO36jcpp2oAjntW5)Ta(@|D+r)#G+Lv;@evh7Yov z$=?BZI`DOGJyUZ0_bAP^+bNu+fRK|dEw33oIBx-*_^BFHDJ;9f#u>-pwCi_0R{_D zG|^;W(2Sweykv9%C04mc_8+MEN=2L)a-@5=Lq;0BKlHC$>~Yyc=Qif?Y5^(7YN13om!v}p z_&nd}^)`Dp4EFuWU;cMUMC`VV4_ALmrC41^m(ZC4JJ z9c7sPaaDmXJy=Zq0`^8ZJRn;9F_Jfu3Hu0u-b}*%h;I0iiKEtPWmB}I?ebam{ayid z`A{r|;%QjBi5hZ&?6{ygJeA{iY-@OH^ISS(c{pcUVQ6c3bAm~V)M}>dOPN-A;= z@6kuKKMZoim5N1>X_0dryv32(+296S9Jm1|fpf^JuMJ|$7vl~%+24?vYuLu8!zPbw zR)l)LUSWDLj3&02j5$8q_+iJd7d(u2_0A0m$&C@uomuW_CI`x?+t^0Pv>9o($KD+m zmsxPWXE3ct;hNj_zvbEsl)c;8u(-Eap-&)6fME55qjpUBU@*-vu*yj`?EANly0EZ^ zFT3=IHpJ1X;nSitC|>u*5nS`+1nd@N7A!0%av0i@12;MZWW6?F6%MnvJT|L|C8DPl zo3MB+qHjJLeCmpwoLGMStohfWhe6P!f)DCu02jxm>#}D_mKHDzesjZ^G<}1=VPm^X zxJLoL$#UQC1`j(%y^V~S^1oHP3M*~=!fy>h<$tWs;PnM{6XW8FyV~|=(Zq;Ce8nl3 zt9BlkT;6nWleez2Bs9NQUk;gUS?L)q(BLBSO8%04CUKrU6t>hxAT!^$XEtOVP5w1hx!YSyIKpc z)jVd-%evLwx-yZJ)UrNqYte@2XT zy^(I?kC0`BaiZkxGwdg7_qbEt9E(ss()hPSBRA5~__B-UqPy{$NMC_Y+mN@y5xYk}X?igqjD59PcK@Rl45p;bkIf9@ z$y%^I;6jHxk!8yCPnG2B$h7@PVlMxFpRHz3eT1v=+x9CY%1CbPs0b+em@_YlbT>+G>O1tmD9>An z-NbR%{#l5^`iyly48VroFNL!0;O4)NI7(D*3;WAbsX9mO(7JK;o+sk(#Bf~A`iQiy z7a}8{-x^CCv*Mj;`QA0&Fnndxa5Bcxr={A{ntBxFbB{HZb`w`tJfgevOtOfF@tGk7 zlwCGHo^ufM2)`lBX_QpD?r<3)2imj=*yzk0v2?H$va2!c-77};(LgKl zjdRJr3lUXrg+_?k6a(KDhkMRbMah{xii#G>+Bz1ZdJLLiAy;KY=O*}1#l2dPEZqDL zNpDh5o6<0!zaQa??!BnR_}8V-j*+ZzNX8#&Rky4UYNIC zAHV#aLA+pl`xqO+d&oVb+@VEwb8ua*Dua>@eJ^G0RvOQ&kwr$+v@U0wZAF2MP{s@c}f;ZWu{ zv6793ft$KI0XwZG#Wydb1 za>wP^-pXhipWJd}p>2mSXzabGTfkY?yK0Y5gxPN z&*z&B1uGr*7+CG^``&lwHF%D&d{=GnWU`Fk6RzJ_`f`tELZ@YC!4FcR#-BbulJD>y zrPh3YE+wU@=0~hEBhEoV>(k1z#A@bHxZJPImVxXjul8MdzIVwa-fua;!-M)6k}f8?Ayu-;0n538-+9=QJH+3o84>BgMjoAJiwNSN?4K}&bD&0ttezdduI+HHo~p{`8KpD^TAv(b}UI%dr^ zx;hzIP93?g6L$qx^vNaT0@UlfLoeLz*xUpaH4d}=FDCV+jLUfz<-fkM&e+{v!CRSY zn~;_^os*oF7t59UOZX8gF?3M)N#aSgkvRAl{ALlLIBgeEr!;~!Y}W|WWw_z(E3h1} zxz`g%yHMunu>q2Z&AzmCAc)sp?#d#HO^2R~5o12Vi|9NeI^-KmBh<^gSp9>L@l)LD zgM4K*^U}xTb)v|D;d1mwOz_@#%pC5*`t`Dj`hc~svGQ;6viD2>kuvfjPeA!dAI_=U zi}|9H-~PTRR?Sk_8EbAZk5^?X?%dssCl>gO?u`0AaqDa7_Ztf!4J{W;YZO*h)%Fgd z7ifGQ;@((8eKjZ_sU)ga7FM?w5_{R%zKOFyF4vgt+;YYzre-eTIjbydmxz;ol|=Pn zAxqy{cknrQ`t3tg6#hyF#ffa7mj3{Q(Q_WnqM( z1v3EI618B*go84s#xX~6jGP`o=azlaOr4S8FSSQ_tlw7sW}rEKJ>muvTiKKW&TOjPP;2Z8-sgHHR&`yPkOiKR_pxXm8?>&3hKRjG7DJcy_E$HQ<8`ytwP5!8FSk%a zHZC1>#N>V&Q`xXaY_$252`-E#1#DE(q4y^v_i^HA!ZzfUHL3Akw-bslaRi-FV1;pG z(kMhKDO8$Ly@!%}@nM}^YYBT7b?@ft!g8Q(pDLWg!{dGK`fNQEN*n)ugsP^HOxubA zBqy)=;HIkZd__SMXQEB<+r}EZ6tMPrO&?EP@RUYB0#bpx!=7}lL8=LS>MwuD9J z7(+fIm%j;z`~gh&?s>SlCIlN)X?uiF28-h;4V91?_$TO9v*%KsE-*L^PUANJfxv-Rb2gro)@Fz*;&%6auB%BGe@Qbw9;PbVG57%05)09u z%!z}h0Q{OLShOppusOtMqa^LEgzcaXnJJ9_CZY_$hT!s(Hi}G|sXC9_?G;fyO`cw` z+7aXEv9Q>n3((eC*Syqe?cO8aqYYE;Nqc8%#dn(eXF72iy`6DOpi|J_C1IMoM+F9B zgMo+Y1Yo@wqMK}!*EO7&Iywjtz1AQgq9 z*&+w>TBKf-hTG-0@wlE|OxLgMsU!4A;#`%X_oO`Z{QQ;3?KR8Rqth$pWBkVLd-|)c zP+IZKkFBur`Qlw$CF5R&h?BKsZ_VE$-;1^;%s%7sEHO_%St&}v)CA(C)3;+Z>B3rf zONn6T08Qc{%eTR?YbAhFe@vb_KaOe!mk9W!uY$#(jh94XGZM@te_Vu=5*E3`<-Ib@ z@}t5wxAEpz@MMD~eCLyU!LY{6WY}XUj^%9Et5QqMw@FG5ey8$cTo`~EAox@0+ zS$)hV#l}6*VTRy;Q(Pf!fEonaOvgx@m#j6vi zdjY>M{H*qu`0~T@=BMFh7iXu)HpUTdZ^vHtj=BU!f#Nk|cweg>R|nl!noO^-X@&%| zw82bp)|i!pL*;;aEnU{QnRskVTnh^irsi_UC*v7)OGrV1a~viygj;r5=!n}UhJZwz ziRVek#OEUI?0oLvLO%toA$*tIxm`E9%g@j>WzO1KDk*}*58AkGS?;P9Y(`2ZJt|6y zRw5GwXwV}+lyXTnDK0E);YDG^KWo0*ua7y8zWgBlTDEw_N558`=Gic`PWq1=HU**j zA4MawLt3(8qL|+1hlYCNERQirzuw#YN^np4Y!Z>IW2BxM`WbqN`k*=)(Eqyhx2=-p zv?crcZx)>Ak877C)ZOs;6|UvsDZOU=vrrC=%iIw^lXzOHf95v7kRAiFRNXuueidW< z{eDufkhSk6sp?PGg5j5%!1nOkBd2L@XlP?tcCUZeu6{3!ARZf6R={O^L4>;C_uen@ zGc?U0AdKHUbWSQayY&X=0GaDFN1AJzr7hO-DsrN@)z)%KNpaySE}0d>iTUBz@1y@* z^defn<$Hk)^d>AvQ5IT0T(TU#QKwFUu8yn5$mPD6ygK2H53c$8tOWEHe1{IRA`w;W z<3TyQ-py!Eq*6^~rGIITLv`jk;|D6Qg51|z&lZ;PcRo=Ek{?Xt=Lb!-cqaRQEI^Xk8mMBv^EZ%5c z+MWxeTFmY$X#?wt32oz@Ry%%Rp#O*5H8+;)xpmsDpU$Z9vKOmELuf1V?;BJZUg_b- zCFz_!OWrR)eVDN1O^>uxbJN^(H(o43SgSGJ(4^S751Xz68R^u#KSrOIyp~-=j_}l4 zk?UXu3%G#Fluu4>nEEm}@IaM)doE6iQrIs3&XrQxME-z;#63l0!#6w4zAB>y(G@<` zLqcs<-P0<=hLdIZ`uu>Q(#gQP`*}`Ir2cDlgo~Tr{V_%5c0ym#2|m{Y_nj@b`K%q) z%>FT2>#@@D^Yqmh+-QP`>Z|#Yjm*O#oY-1sJCqmQ8d~;tqfN&069Yp`scRiBN-K-G zzL(SBp}|bqsw-uf~)<@ z^5zn?&2>a|%rUuHbStc}KqxjnLU9xEmaq^n7=KI8kq8>Cx9f6Q)c?%1FyOM^V1EkBwfs-Qq}-VqzfV=q$(j#+T6J z6CKm3Bm!e#fJw?gRtqNe$m6^P^MHc7g z2VQ)%kbWP_>{o4W?>cWci_u#+1(7o~dwgj_OduI#VNq{-(b>44tBwA{3yyq|60P=NGd z94-6?Qiz8g`PQjRZ7AA1uq#<6Y@UztxCoPAp^so&5kWt(_fwMN)6;H?-Sh8@tXnPFuHabZ4JGz;>xHz<{WwZN~e%1i(7c~{RtC{J`g(KNf_Dgci_fOI0mjbU~M7qSE+GM72xt`&!e`-q9! zO(i7ny-6(%EYtIKc3Cla*m5pL(;?wGHd@eC_4md5JL}FDq^oCqX*`z3cDe+dp5H>s zF%K4iG!`Jw>~);l{;G$R%jo*0=o#db6H>iq(SY0K)S;4SW+}(_Ql6CK9E6Qs4^AI5li@9fuo}Usd zpeH$##>In2x5Y_sgVr2l{pG%nH57PkPbj!Wa>PkRU|%qt%}}c(Ea}NCZ#P>>%~#a0 zb0joKSV4M&=b;~_KcRJTr)Hs|U_l7wI9bOv5@}qMTNB_Zwv%mz3hAgI#NmZx^>{ZY z6Fn0H*th4)^u;z#yz^IG?og)fI`<{Q%cz(j08V5l0!tc}uSrqHBjlCsm+-27a=2Cd zT1sD`_dKK8*l<6Evzep8c4x~?w&qaS4%r|{X=zDElOW$NG{J78U0p8MtLC?es+AM3 z6I6rvtL`C~@QGXn?d%KdNax)g`IWkjsohD0r>Jz8ZJ$-ja^}TJhw;$a;XgOu%$_)w zZm`m~zcK!klpcf^2rnP?yDYusYy?s&z+NfSeCwbXgE_ zH~Lel{AL}q!Oa(t68?XaCtPhWx0NLCMg`3vQr7m=<+e1()a88$^HUaG$?`)FYAaNb zxxS`UGfQ}rJ=*VL3HhKZFAw72J{7WKp=@$w{G za<2D!oq&7vOnRn|?2{dEOkm^Hfoc6!mGB`jen6xxY@;r5ATdsU#|`1X{e1H^B3`w_ z-nC17Kz68&p=oD${l*Z2)AI7zC}Ims+69MhA#I>Xw<}y9>6V}!&n3>CD9}I?^&9q- z)0u5%e*YOuPTIg*bScROc?8M@>}@COf|gr+@2s(y8npLs9DZno8HhzD>GVjqH7!on zam{9-^kjpGYIW9yL)M*}v)FmH%Q_L<{rBcdSHQz)HW19d3+SCv6Tk7hZo>ro$;s3* zH!4v{r-ZU)=YkBWi`Qg*VgjnY_wyW6WILL^`1EezXH$X-^b$H?huJjO4t2FMKH=FP z*n(waw7(!e6A`q+Gc=Qh3hXMu&aX|QP*+OxhT41)GV$N9Y)zt9dBxR8`(9({Nv=fk zA?LOP)yQCcw^W2(IV#D~7SYz8C6I!autg+`M1xsF8%87|Q{nc5u`)+&9!%!oC>I*# z-dKJ|H=BZ>?eugA0po$&HOt@%sK9o}<%f32?SaV?1aM7au?~Y+6lxYQ9Id*UA zf_n0Ps{F2s=g7Yef6=?WV+rz2R#TJywRL^5?UhCHU)a=Mk5)}Y+gSySJ?6w)xVo+` zTCC=^&8#DJSE_u#(+pA89YUzwnH4Rv1($Lgw3Htt)41e9)4<$o1Np}oLKI67w?<(J zdH#ffL%_jmSSa*8e(FMod2;tWkOdJw z;NZ0HGg-IiE|tusVU5!3^MHv)8n5rYGs|+3mnRYA(coZj*!KShS33Q?a9hN<)RCEv zAee8PPzD+Q30B6_?sC)54SeV8|3xmp0z34+`d{z%sx>`>FiQx{GU{tX7(Uh|L~`NI zm~8zlNc?*-5G;hfSaHhFV$S|!&+|MzarI;|RaC`$73NJRy{N)}q25mZcW-&I(#i7k zar`rS=gfalc&|*#hc^LD3sgmo8Eem+~MSgM~Fx4M8RNOi&go?(OYnj6XFXz%T+AM+f6 zfIR+Swdf~6;Rt>O0M?NU5BY0un5c(aq~B|VYSfK8rMc(*C*W^xtbLiL_SQ`drF7yO zF%_Cs!JEENCl1Y7rzojPARZ2QpQho9kg^!7Y5!DiT}lwh%oFqA^0UUqEE$Y}deK)C zFprqaLkg1vDM?_qw&!)*?(+#%O_UooPGIzG+zK2pTI$NUHo3QPg)0xP_K05%g$(bn z$N&3YuvB~cinfKgRz#4Sa5(foN##7&2kGQPPlT3ssul`#G@_l&Ge_;qvcDeqdyLxY5iQKms z$HNAx94v(z6n6$EqS%!ksSIV=!_WQqV;h*LFPf8`waLYhaXK9KU!$6$!PoStDs-iS z-sW54f889n{h(Zpre2FFj0K;3_uo&Be`R@aSyYVn4G)9~%zqI$fa#R@pn$tIcKQ?q zJ{RHtNw45d>0A*UrC4v@W3by`br42JPHDhY{agkQEnmd;cw3Y97!=fecj#*cFji&W zIonxIHPz%7ak+jV6u~6VnfuM@#;J4AE`>w$q-@?~e{igPffHz0C=A@(^c)3d3Qa_J2vDac)Xj-wt8qxX`$xSftvo>AaNu@A;E@r zQVd1q1nCzz#fuZdNLlfZ^TP-c95fn83@-0?(@p}Q9=#Y&x&(drwY0jOtuzC z3k8V)pq^L-0qQH=q1$ZSX+LugQ?;ub=*ZjRLtrB{gWE~|IER8MfN1Vx=7cczMTR2} zn|V?GSKG!!Xkbln;C_z%)8{WHqK|=if~RMEgZlluafB9{*a@;1g7GL-isdTV)ce1M z7iogOLXX^LJ?j77Rr2ZV;YX=fi%y1x@`mN7oKk0xtZb1gEi|8te%Jk$8*7244UkFFk9q7o*}o=ri6fo_RIs}C4=ol*tY1)TEeF@8nzmUD^2?InO|AQ|8a z2M2V5E#sRY@BpQUMiCH>TMpW;T_$bCm68^wq9NXrxjDK6Q8xIISdui_-jv_FGX)K6 z^Mibb0Qk*3S`Z2|wLc>lj0e9#pRS`xKo|G_XQtZKBY;77;D@K)L*M`Rp#v!VFChK{ zhyUM`QO%khv`XNY{P#8%W`lOO_8*N2L%)CvMDZYA4t#z!lpAB&|C;wg)xV*9_l^OB znzrFBe$=hA)tjftP09b=2K+!Tf6-GsWZDBQd{SUdx`Q(Uz{~T|mQRa0M})FAfe-`&AL!wGy-) zs&aw&kPce=isw6j2*a%TODCzVO!1EwUmg^rpgK4K?%H)P1(Lsl+U@7dRyg}e(l)*i z|82I`Tz^O+_=Z4CP`8!Fb`ACE?5%! zQkpeOYj)`$;OjN-j3^d-0&h=WN{#({p5^3!=q?@vkEzxN)cxngIJHtr*|Ro-TYOpz zUa@}N^tj?ZQGceXHGe6fwW$0e5Mu89w#z2w5wST|v$y^u9~Fj)5}aYDu(icTApni=qF<>a!sexPeV?Paw1PMCKWIs;o()@ret4 zi-XGcJ}@4cNR-%2t-0DLW}HZBmJE)g?N8)xyZQIS67|43BPEdaprG1E<0&1?&>ZDu z*}`pa{t%b38goDP8UN$pggknmw#?bFAR$?V}soO33Yyp6a z_q!C6&hy~Deinm)e>@!@=Ud(vPbJn9Y1_%BsWRO#Qp?xKK!^65MWAL4i@N7DS$>W|<5nV+6?YyX3h!fk1t11v6QboF~& zu2h@x$?$cZs$l;ZA^<`Orfnao%YIC7V1XVkn1o7O!Y~aw4WFv=Uuu!n>-fHt;9NRZ zdzEpQ0+YpQX0`bdY;m5}yj3)V~Tva+4mX*Ir>vRdfir{7~`gRd7Mw{@}@rEA!&I^?hJ2uyEaUt|w5^+Uy4# zpmF~c1+ZA!*=wV(|B*KEb#sd^+Kp{#9Sh5FGi&@5xod(Xgjh1AG zLf({5iQu{)FEvM;_m^w&;!VP+NC2&~`?!tbBo|`hD}6dJg?1$-K>&?b+JmB3t*OzsGXU8e*-y`m8S{*Hf_ z={I)GC@Ao4*ey>z+WTOH?oYQ*< zE_Gh(Yzf6IfDPCE47w?i6K3^*(;}EtvX1_}@$5W85CDk1Jk$(z6q_);m{WPHOWwQ` z<934q5=L^xwC&6JJ+|?vkA`pDr;-4;o=Cn(v-&I1p|GBgOB7eHf=ZXoPt})~0C;H0 zD`aC+IH&!m**i2<(nIPX)D;v~n6FIV_?4%0f8=1vZNAjL+!JT4E--H9;mmTI5qy3t zs{+CHizJd(k%`<}rKW(>$%;rh_x;)-&A?|>=Mbdwjq%ny58J1vKZWrN1HU{gpE$eo zR2a6k=$08ib9_vEc)jI402lqi8-X(+Nkm)?>xl`$D3B$<$tjTEnvC8ytO_Bm?8WVj zKO!30#P}4rasuZE>UiIWE``P8gJaHqaQishKp$9s8ALH*x@O&S?@tJV6d*n4hF|fQ zo96hnxhm=;^UdX7qb$JzZA#2>r2-Mp5ll4`AMO@? zlV25PLP{v~`6dLe`}2cMytsDa-68#se7}%CIy*4Q3kSCWU=@1DqYqpJ61xB(8nCxv z--LCvhL#;DaE~^S13eHc#R$XLF(RXW2=dK?|0p4GN@ZEf2HfWMI7$8ulXs-{X4eZ{ z2NNoC{-MYuGu;0?cM%S*=&Rhwy`x`F)*UI*&@W$(3=rtz{m~IO(1k+6fwK|%4gj`C z_7!yT|G`5W83($^zl8OnLIero2>~4kivLv_vdNRl&UccF@Q50q$}*$?#&5i4#|R!w zLjHScA_aWO|Lj@lK8D*6HEt0&4~LF-|NN2pEKonq!>Cv%p0?!YyHBh9K1X6>xNt0R z9Z3Z!n%@CS7Yp2^r=S5%gl|$0&Pc?YNWn9ONUd_47xn^1W3ewrq&);0sz?phJ`JTo zIa?`ZpMp!Dbs$3V*naP&$Yu0gC*}En)A(OrMcSn3X}Etj+eA`fMCe2Bbo+A9hr-@G z;XW1&0afYxS>WQM)#h~~a0^Abn#GR_Y-IVm?Wg~AbWzGMDW}n=VC)RgZmp_$hLPTp zWp3cJ)^qPWoo1?Zz$*>zvhzW8rFWm3i@auc;RIjI(}kJwUl?4RF7qdk0$f6f!)sHH zM8EJ6_OS|sPsZaZ5^J(<=;D&j1b{u$qGzhO8E63O;>>KiGodsrg6-N*HK>5FyG8NF zyaf!Q#Ppl=FD`&)m|+48e(UM+Z_htlzfyY*g9AUN4bLpGx$QUyrA5CJ1u@-p^#Ds2g%#8g$&i;;fhESQnNL_aNm7EsI7SX`Q7=sR5( z(McbwzyxBG6}dvy*O|-iNah-b)x(($CED2{(jqq*%4r{^QCc zmNHGa2vnfR(>7*Z!eGtS>i!&83S&PHf6h(M{I+UBKXuC$0!lF?#uUUGbSOg2w6&kN z>9tQL)}&4&0i+BkVdaKa5ie1H;TbUXSEaPDx(+j1HcxzaWeyz7-^heSHo!s=&QW}pGx!;%325h}Ot@N7RFdkfLg-SaWUADV(Yt=}KvER?L?#9xO zCpZO7EelWykXE?_a+v$Vc3V~kuMTmr`01!@#`Os&exl&|(x(k5coq0koGS{gf0=ey z$_V%+K2Ya%dF9OY*JjsVvwwxq9DDaG2NGCDNDPxv5WFgn9x}Na^Zlb4o}%GH`jCpc z9IwytxZxA$$H#%G?9$A}mudbWVj-%Dx=CL-_vGsFr1P)YZ-ZvC+5(?nsQ^sPUa zgLvM>&zAy<@7GmMAB^7PtPx+k~0MJ6q4og^E09qpLPA!TM&Wc+|RPo z3^y+T<95vgvL@)g3bDp|G#AsxRCfe5sF9+S(TtIS`wa1?0q!pv!+yi#%JQVp$H#xi zfqcw{y<7J;t8s_;@LdHY;LJxwb+w_${+F`dZ4`FX|93~w0JD`WBXf0-&dhT+Dn0He z(-kH{ci;Ow&5c#i?+20uP`TfOo;H;VWSwo<-H4g(d?@xah`1JaCe-svxke>Sq;&MR zRI~i8k;X3kZx2jr~Cd)Q!Q;=G{8yyWfy> zTuFc}sc`*eni0wQ*$pk5?VPzl6HwjcrY}b@eAO`Y^b}wS-Q-HwplY`U{V=W`ddIhR z^M=q<4k{IbjW5#s^iN7)yTp+IA~;uw22jm6!Xh2cez!+=8JTUoT=u9+0Lh_}=|1e; z=u(3;5tu#?a1He@$dZ0C{aH2IBsEvDJIm+w@g%H@uPNLSTF|cYmjVp`y}L3^%7Cas zFKc2NO94q%I4nSyqCnPua?MlL6+fTPbWH!achFkqq!;2e5}>H)hk=&kaZ|qFF)VR( zO<#WWPVY$yOj*Pk6C$jpli~NvH2l3j-+RcaP|3`R>2Vk1uOV_2@_?uw_) zYj!g2^}7zh;7wdJ-3uuG0Mu!hHvbn4a9;24f)@FXU)|~@39FjZPnj$Gbcf~q@#iHI zYO-imzO$i6ii}xrsQl5+b_7C9ohfnCZ8fxtD(+k7k_+GDtfL%3ffTLDZ5(@dMLG4P zJGhNi;b(}+9Y60@tdp2O$zkNqLz-}5tLGGu|An-5^WqxqHWuJdHzo{ ztu$>*XO8#Q%?N@kU}`WXs>Dctqs~yH#L$$-sshwI&FMocf0;bb*QnCuK4wIwCf`+t zlDO#|YiEBFA0R%vOMzH58{DDSnNBju_qx6+!)KYrw3|VJLCq%ad5ZSW>OR#WvbQX$ zC6-jbt4?KDKy+sPe8~=c)8u9q)&nWk&@cQhT_Z#Yo_`riDxV(Ta{0V-PegW@p!p&1 z7}Y1`Y*|jk4c(g})tM!U@jJtz-@Yv{-bg(DVGJLot& zXl|BUdiw9i*d$rdvbf9~FKDS-n-=At?Lr8vaopnM$@+Opl)<+R_`8@Oz6^;~DTWRe z%@GQ)s%TwBLVMQT=aby0mBufEEGP|xvp}8UUat}+=daf3+p(eNDu1T-rqswfSZS|- z)0LVu11*soU~AAKC=cvqT+zf|a5 zI>>ViPnkJ+deM?$yzR5rivP)S3t;31i9Tq5WK_*!X?tkjHA#3Aqn3hskxp-{5FODS z0aG5bE{;O+`KU89oTV0Xrxj)B@hYW;E5FRUS^U}N6e^VSXp5hXqk|EYiLnciPW=B}hua%$?qwb_s34>FrzBUko|B*4&_(0o! z$!(comdGMU`%%9AUj7H-uegqi>iXb2LWO0)SG-Tz&uXp6;$1}}g&8{JDT6_6((XZ- zjZ+wZY*nPWTQ5D#@Y8eCJDo3R`^tICe^&4hy!YX^>ZK{SXK34?6gy$tM|0Vi$1cXP zSss|s;GQ|#Rjy%}%Xt5EU2p?8{R`;)K<|9B@y{;VrCH9y*DPk}#Y0!|Tqy!RLXuu| z&y7KIN$Z;H>GOs@Ln5<+M8AI=Bz~{7>RpdsbarB?_}dlh<6HT%?8Yog@IKa(C%zEW zhPs6s$}RxmX*&t*XF_|`IEf#pG#KgiK$&}kKC~k^kagHj7}E2DlD zRIr=mzY~L^#eIXAUpefeC9}!{=2ll0j6an1ot#d3oZsLe|GCsc;rouZJAxhP*XjS* zXsD$v*Qi{cYS9mhNMqJ*;@tF^&|I0B{#Rb-x_sAL6tpy>M3sPFSsIV`A2r;4zO317 z&-~hKJDHSZ*l7{J^#0#2UE)RuEzY=91@7Tt@VuIs)B`lu~%H4_b;5f zLuZjJ@$D_v0rw(~ZgQ{HNXWppurQRkAR+=bCLXUAB_3Ox5`0;Ezn-x3SYhgQI*;dq#Tpgz>DWKt&~Zr8NLREOeX7%!6m@rTWi zykpRLtbNlQ2R$S$gU(wyQs0gu7$k{v5F%>Yf=$lHFVM&DW`hsDfE>N>^EH7xFxy7q zg&zIeNFZM{*DlbXG)-{+mV1hID+2(0HG{!0*N3}wpKpTje^mLJ%QTT0#n{S&aoL?e z0Z1T3m0X0-^g#ICRLHoa7=}VY$YDvyszh~x6$v0a4{#tGXGq|WMIaOdgFf&(piT8V z)aJ^;CFpsY`hR${L8kbh&;Le)4ngt1fcRfP9L799qsB-p0%+2ti7(>Nb#)5-3c&}v zZ9>{1ZO9!@+aZ{cJa?9%mZS~&eS-!tDEoQXQM7Z6v=+QWTJll`n=7c2{V)pDn_$e^ z^kgr65k3`DNqX_UPCZ}f82l#aUKxJ^G9ptMgrl#4A^^M^Y)srI76x4azh7)`Ip#dc z7UK_g1np#jE94!!K3}7^Onm~lsOcJ}1!f_@U$6{e_BZ%mvw@AyLN4a|zr#P6z)f}a z9}xF7K*Q{p7oYRC>v_-@hRNVQMxjiO8pHpUC#^ff61ITfgPSA*$ro|#&XsKIZh4j& zXF3Ij{iNbl-*TLr0>f3{?48v6*I;ZID#&5{oVc$Cyh)#LeN|pwUfZz;!eC=%MRUah z0JyuQ*iHL*S-&+OryR=iL)h{q}oK3KEYK^onmKZ#S=8NGEW`1=jY z&ru($=4B(!0PrQd7|+UV@RaWvg5lHLZPT-9?z@nK`+VacJbT`8Dqtd;`JuNT%8U{C zoXGEk4Zepw0fzFf(j$iR&i_8qZq}eB2P66l{m}9(YPkvYl%Ba^V*&t4dFG>QH;!Ke zFmt^;k7HQRDtvs0c#vH17kLb$hx7bvG(Z98S37wl+YOA7YZjGM#<<+7rvgm*p8Ox8 zzB(+*?)m$sRis6w6$wctq)PRMq#G2a1nFKvnxz|Qq@-IoJIxxd&}e-oFnev?L}QFgQR^l4T>GHW*#HP+l$bdXz$p zUb<`WU!}P=W9(084L7z71Lv*tdPj@P>XW2~YI?0Ki4&LB?_%Y8ZgeySVmHZL! z=l#Ao12E8XUxs2C2ND^!5Z62YSvWS9TSE}@4K&BT&KsaFJf<2%%Fdtz-BqIa25PA; zyGIG4d5g@l_-t2~#L5%;7-J-nk9+@I$hBe;1P||X(@attRWgwpe)dgSsk{{#*1SNvurPcB_uT3 zle~iG>_Ad|dc@`REj<(+GJn5j`V5i+20J8i!yWUA8tfeLO3K72tVV%~3k@fn#{DR; zOZDo@Y-_{P697x!l;Az#0kM=vt>gM}&*X0uh_$%%$$C@B%12X9P*op2%sDrD`@GT8 zMBz~wJLKmfdVC+n{57yqd58H5T;~$nG!*EOYAQDiRTjn<9LS!6th6L9Mr$;N{F>md zxN3&@U;Zb+hM`lk9*=z-L+E80qdTH;(P`%K=(k*`#W-n24or6~XfHoT<{Fg?90^G6 z&=|cY>!DVp1PNH(l3aXTBqBUKoIwRyJ+2x^UZFBv`wKVJ<2w=nk093C6h|L@29Uo& zq&w+VUT4j_BJ257%KaGX`(BF55Du%3CJ|5@g`h>t*`f^|)kiglB~{1kYedLSK;Ze2 z$rnGa78BS|D;^@E08MV42*h9>w7J1LQYyw({WzrbMT*` z?56A}%mH@44BG(AH;N0lZ~6H1trQxBK0<4k3&tNN3g!UfGa))@{Ra5IH9#%Hq z9#wZiBVmEsYo=UOgv@|?)pgJ4t-LU?k9%jDW~0qN0_e% z8oaf8HN9?(1`;JLpq9jezT{Nlg#e=$x<;hXoea;KjnrQj;^%^uHZ=sY{Lssccgax~ z34~8jfsF<{`tDD~h^;KChz9*#(=-zBjY;J-m=*o2X_5gbzX%yBs-t(95-r+VM-p!! zBKIse$rIWKvEXIt6N;+?o?qwO^3w%S^r=JA0yL!k-d%CiaMrM3BqVn5tyCsA4&+3T zrQ@uyRGB~BFgkTHLWTlG7}u-#?SKU0u`&$zMz$U{M>GQYz5BEz7k*bwIL{37+}vFyDYF z1k`d@)VUyl|HAkmuW+YRP>*Px@3lOJw_|L~d4^K*_BW8!52n85v4IkX$=wle&j)@k ztxX~PWl5oz#eTDJEMBv`=a%ij09y*>C)SR*22RR=dGR6f9d!v5S0Ryzrzi6cgP2fQ zUnFKi;xJ4i(2jkPVGSeJzdv6X?0J zU^&=%P(c&*4rG?ZZa0+z%)y+|t!CrnFAFbZocd+P%O@fWqK6nkvww4e6;OhgIT>?UwtJU>zVu$F8~{J}<@BBBYynE)KB*jG*65z}kYu+7xy;YD+pD@Rr8(%IqDZ~nS_lVT`p;K-XaW6EU$SlUQlN%Y`V*25 z@{pfW=tPmn69>LV@NkbA1UV}9LFnKft%#$)%ibGt`PtVfBKF`R%8Gqj-EQ7Wuy;Ps zWayumHcS5npzq+#hK6b>t`O9@W&!lo;m0Q@IkWd6EL~nZk1f#4T3XdM8DDyC3i**Q zx)e|b!QMp!wgW{H0qmd)*jY$x=(Q*^Et_qI7K}9j-+A^>bJK{R^vv(|YF+nTe;UI_ z<#mzT54Ai6l2zsMz`6zQjn(SM@N}ZJmx&E7|7R2tI(J0&aNvxmmMI!U{u1QPS_4cW zE(5Bro?n5F-7o{_4?m=0sB*l<5;k2ry3y>mOPv*BdyNA`lw?V`u4B%Jf2Im=BNYVl zLm(wJBTI3WP!FpvZJf=g_z5j!N0poPSZ$tsmOYO`@q5}gQshDBAdQQZF*JniTT94} zwKmHGB+7)$9B0xtEhp4sA~%NoR1a%ac`i~>L8b+!RJI5mI`8>Q$m@`gxB#fbn>i=B zrJ-DDOo-LI$##?@Qsvu^YsnGdmj;oyv5|1=^PH^(2{1`=zy@l0Mf@%WZA`$d?yMIJ z8sIbmwEkjP{?Fb9$pC|6fg_CIvceJ;UE-um{)}R;b&wTASULjusc+7^6cw-O1`71_bhqp@km09d$t>-fV(@^eKu0IX{AXg$PR&lI`b6mtw~L6EL!4ezinRamAx|`R#Yuw%pJ5S5PggJEBhZ z4m9*Ln~S?K7}4F1O~ss}K=4}anvGV?ex?<5t4+l8o$o%j z7)Uuu0~OF6!2oGQ{Rv?jWSb)B>ZJ(^t`Yh-%N|+8UT`R$ zY{h%bi(}|nuhOUi(LJ&A_{2(NGVTH;biS%r8+2HC|4pMOXl3r7j_H9|!@5*X;T5R@ z)dI!WetX|lTL2AuQ)^wbF&RYs=#eUuXI=Zm#fTobTKf-%a9A*mPF{1#Wxm8YaK6@v z`jXlm!I8)Y8N7Ip!16ySsV$riH!LbrAiK6+^%DHFLJyup0m9&@cbjtxo-Gfr@c&|$ zi(x?bO}m&lj7 zVM1I2`n2`F(awMFs64d3(2zBVDN?8j->d=mmY<}7N35Opge}0t$CQa7XAGoze4`#r zCB^h(^3-~AT*tGaUi7=!ke#hYs7f6N$b=7^!`;^w=0oSo@jMM7{ICWKE1?t&KZ1@Q zpElKP9yj`8SfSc_ClLu$nS;;&`-=Ncd%HNl%fk=%2g9~OtOgkwdJX{;;5dZ?ET{VE zg@)quk+EEW;D;b$pi-f7ShpYJ1R+_4xg$=L@os@b=R{~P{W4amhEeJ^L?%C0P%q?v zGRy<<5BFm$#_c1btH~!#hDv3+vpIf^`ie~>C@l@W9qvPE1I%*1|pXG8z(x7z*G+OnHm+rQ}IBLfBtSAvNHUU%0iTH6gpMJ&3<|1s*rCBYP*e?WmA0UZO z{l&Vv8k-e1w)~jW|HwgJ5%3sp6&7ixgjSx|ks?km4X03^#2CMJUYN3RL}*u*rWXVH zO}sY|+qq{pz$Mm#GQrv#tlNa&m&a;#83g7PsEVRCDsy6R|FX8mS#{OA% zJqG+U@S4vK)kP%$uNOdGuwc!17Pvm1CS{A}_i#zhKlyB9m&g#Ji*_6xXg*n2AI<)P zL7xYXVC~$m0Y%%u!@wl4n%j@AFFp*CLk_=^idOBsJ3^k%8>!HIB-hOn?tBFDizpr@?jff)4*Vxz|`BldjQ8~|n z^@CtDl!WW^!{XwY9Usz-Xjtc@bL00CxZgtVuu-rrlWME>3{hEXpu1}Ay)gg+8HnfU z!Hjw=MFrx@72F`-vrj-~x{s`~V{Fw_sB`gqEdB)q-Dn^_6TUOzWrdYB4z7!Hv=%{k z1c6Pn)!ZZK4z-qfV}s@NOy#Rcm7sjRlMzc$d0RmC3E+|3MVow)i0>AqsP-kL~bGmR92 z;=$eZQvU`E6(R}w+(E&Kod*kiStN8E-mwR=v#1cBE(sn!Z`f9^+1yr*$+>3SeB82) zme5@MypPU}2}`&}x99X9&+~H=Z|2*+gR#0;>22=hKHL^{HuYH#^(gi;GlRc(a#g z?^ju-vxEaSeF_c_IYQ>W8*a@aeB5>Bd@jdpkiU3N=tkIcmy%f~YW(!tCvkLkb*4+e z#f+-7T;x|vhUP?K0?Gqi)0MfzDp8m8mk)nQmPd+K-bxMYCU^OziTA95-*NS+j)18_d`ICU8kYL4oh^Z#&6&fs9r)Gtm4x$n{!VdW@z%gb z@y?CUN}r%Nyqv=~5lkOeJMY)uDe6N)E+NS2F>*tc0k0C>;(pwZRKYmd4%QwC$S5HX z1RA;qh%nFuUy)E~W{EzIq&)w(DA^YT(X`4LpT87ZX~m6N=;Awi&ZiOC0T0Jfg2lDU!adjN`2ggvN5Ic_Ywj!MloiyK;LSdOriU&I% z>NyN8N=Dae?hRgl3-+Kso)z`S4L_W8sN0&uJFX?0ikWEHtCxRq2%A7~@jRuLk|1eTN@U1DSbeSvE$=CJF(2PGX%g#n(vraGest ztBAx~Waf76S<5})oxK}VNGmn(k-RgvPT&28I)6j*IBR}qZV@f*qR3>b*k(WuR?9Bu z;+b|u#q@sAhL#*YxP?Ax=K~iK$&;BGGJH7y?a;HwqNMI-FZE$to5c&0)k2O8E+a>$ z?URnZ@AJoM{)kd)wdV^2|c*WYBh`_^plFWB{ zqpdo*35+&V_HNJ%J3ldy?i`b%Ml&QmWH|NRzS=5CJJ(3P9P~-ZU3z+$ggMFprK^l^ zNbb+i7UBE+h-q%cloM?esRy+^EltQe`>pR+L1C<+92tFZAY# zuTrYLBS{BGEiU0zvlr)Er`G8pUys!3o5(O-sA2 z@NARN%YaiWpMZ)c@<(JEpisaJXYjK3B9PZBAw4t?z)m8iz25-BoL(Wep7Xn396bv0 zO(n*QwT>{-%5reY$@)BmJT0`}Y_9ear~BEi&#eZ{t{@?OM${%HAEg(V zuPAZca^~HI6PRx>8tu@*n#9peO15-&x3Pok@>kSNd-xdE-nNq+8jf@7LdN@x_a|9o zn_A)C;~Mbor9!>yiZgfxeY4PE*y`t9p<~+3`fuMK>l6`IcY?Y1A&hJckx`71Igc8b z-c#f>Uw7KwesvW(9q_LokEV$<<{`($^rw*uk`xPNb6feZHD-g{eYs!{R9uHVX36Q6 zhT_<^ZI2yX=XN0gj)J@vq?J%haRpDyo7*N*pz{ymaQI){9Cjb+uMS{NYxzv!g@_k=}M{pX&+R| zj$E9Fi|ZCT!HPx8izJ*6_rHa)P)bH)M}gbZ3RFNEH9X05QnPb_*VHh>iL=S|bSGhn z$$IyDAZ2-1*A{uOViZ0>E<+gg_R>z#o$U+0V?$ImKT6_f;>yeAU|rE8fsIkB^XIo6 z;bXpPzU@>CTZRWuCn&=cUc_AueaZhkNzWQO8t&#&jK^A|d8R$pa&_S~c444jS4Qd+ z&ZyUAR2^4HYpUGMPs$}5GwXS{LzZ^=Gv%^o);tEEgtnhMY1Y@r11>#2(G@#*^CF+6RselC^y87=!=HiG=}XD+gEj}goA?fRXA zt%RAAv5v?Lycv6*q&w{r1=*(7^mRo)=2Y~)eu4jn9h?*Hjoe}uFOYtt7BfCx2Im3?UDZ9ta^C{ctUb6{Jqat|LZmAp)_gPEBNwq>#mr0{Oma7F&sAL?LKV66=NE$-PM;R%_v>7+u*#~ z?@3={$Irb{wobyH1b6(gF~Tb$Ha2yo}N?V zX`UZTft~*P@w0IH=6f{qb#MlyUO6#*O8rppc>LdGC%*{tN!CWM+_aACss3i^Ix}V^ z_QD+DJz{Z_gay%u{58AT`6S`Rdi8MynQN?G50*`7Ox%fe&l`(ULl z%3Dan|L)cu!HqX}Ra2%U`%@K`No>@D2Xpgtg&c<+1W#ji7EG2z9<|K9*Dm}JvnwP= z=pZj1lvtz|3-+Cphcz9oJVGEs*~fRaRue{oYiFkO9p#aR|8Imc1SKO^ytbsGHCnjx zh;*;}G?eJ0n1eB6>B%B?_tyNn=)vvqn5U83S`zJFB3hK`jE%Noo39xZZ}5Yw`O&#! z1N(aP)g@09-#)oE=YyY>mRaPDPnw$day)o9?%dnNW3H$s0k|FAbtJj%Pt#-^ZC z6O*UV?v(l)j9L!64;-?CyqK6cjbpo^WQSA+yO+Jgpb00XezVW4_9mh#-yx?zQzm|-DU|AzDY$>GS}l}T!V(@I z`eIgbzqF>}I3}0=qo#LtO)66`4{f>B&j5+VeK7xHeRA@AGC%fRl%|<6Gb?}~)6-zM z{cmX>7beJ9{2DPl5b_`Vq7c`Zm!rV0Y*88+%h=i$@tq!wr=hHwQe0{z43xC9*u7; zsiQ48(>{GXb1g4!(uctk+ewXnG2}nvYqFR3xb7L}ufH6iZx&P=y9dy=BsnF*B{O9>gtk({U|hB?29>9&1F@roIPk-e-|oonOY~}U6q@1bRm1(v3S@> zn)mSdJsR1&c+=P}f3=R(g)-HjWjp$5Q^T9}+{4cMk?y03+d^%m3ON1Lvk^jjEEyn$poFe^u zn881?pf)l*cl0BYPXLuv&eafFrZ#Tj{R{s=pA(S4YC6XRuj8=_Fh*+zsTXi(qK;}{W$H*HBM}{BciWi8dyeJX3^vRb zKg9al&-rw9m?jqGxXWel$NpMD({eXc^P&~qeDcFz#p8Q3H+?3ImZ4=*hAi~$W7=F} z*=?-`1_>_)1}mIk+2i5gz6F`{P)bP6iXAvJHhGY_efU(8Js6)gzM409nx!DVs>F1m znjkbE9T{+H@h~Un73;S_nbq@80mVIgv2U_WyGt^Pg(53wC_}p9EzJvvJsQ2>2u=B@ z#*+f}3U-r$u+B_ifu!Lnj@F3@Fv+*_IEn8>6J@evW1s$WM$iZ{<{Fgv%~kr77cM#N z9^)L7;+oDiTY&_Gzl$%0AZZ_M33|czmKpM67nROE^}Qa$ZoYP;x?PC1+WnhaFBzSc zwr^3e?jgoZuzwa}<-U3$n%x>7g18zi-M@>~Q#fTej#s(pwrY3dy6H7L{-<2RnF6O| zqmpm7KserduUABKb{mUG*y$QKdpQhV|K9ca zt8gRH2b+(rzo9N*hHY15M+R-6NmKO}9-V)#*!-3){Fs1@*2pvep!>N(>B<1E$5zZL}pGs z)i_x7ftj*F!G#fggfe1FVP8z?Q13Vui?Wp~TBN>?^7C;O{WJbi^?JzB1BSVcJnl(CxADuI6; z4Ic*QYjSE-u=v>Cb4(y*9vkQ-qq|JqwWZ`aU%$;3lwthfdlg6`9(T4 z=5kUP13h^XK{4GMGomRM93$TbSjg40lI#pUN^ zx_E1&+25%wq7ECC-R>d7tImSUj|2xv7IX5K=8#(7k?G`lPpnLB!X6MK6?QbO=1UrG zW;cECMta(6r0`TIY_Y7tvtOh#@P+LmZ}IN5eVa!5T;LIfgqe??&s=}tTDJL5QOnS$ zTw;dz34$Z=V{)K&G^91#f>03uap|b#5F(+>s zW_kH8Q!g7lDXs2Be&uOvVX7_zA5cT}HUM=vxx`;K~ z>1hSkRco*CL}py_L-zyyE4R-hx7j6H+?cy7&D-}#y=*HVVhL4iz5da>ca0rgsnep5 zQ()#58dSxQy!Cgkd%De2KmB)e`tMb&i>CxevVSP;ZUbfE?XdVXINz$O*o3pvPn4Eo zlu-*~b|q>xLbc!dlb-X^{x<2xzg{vZ1iUIVmc41-#a4Rksoql?=goSd_Wi>ij?J6s zeR->!KRF)64O>%ldg4JV8b+x&acauqv@EYPe;eZC{^TV~toy^Lr+3^m}RcMK=L2 z^ybwfTke0~|*-UFsscw;vl^=s0q>j`{k!J_*s-NwW zkMADvM@0%^MycGF1x9O42u>!-FL_V^C`WZP*l|NlJXUOG&(Q7k#71aCILqbb;{=+g z1P<$2QqJG3CkA#eLtF!o;_6d}QYLMfJw+G0;btRk;1n>D zF)gZ0x`;IP`xZwosooxhyO{Hhsgwk@M-Xy^aVWFF$6gXe?{#d0aps37+ck4NofggG zHHGpA-pS%1wF-QxI}+U7qWexJOFZ>dco(Xa-*X6Sxn!NnnXdoPtdP4DbY5Q2)k`*n zDQz4)v(3M9ghGK+%p30-_ecZIq+3`M)L9T^t-;XlmzwIx{{xZw$&ewBO6G&5fAN{_mvZ4{ydfSQ5VfJk+RbH%vI_?vTIz92m zbYFZS_6)%s_j?k)$aP|0%nP4GKIc%?fu>F3-kXU%3Ex_&m)C3h8HkGNu)8f9zGA<$ z4e35mi*}Z>8FwBmEX_Td^VyWq7vinY)iNzoTJ4N7(Tbx94q|RXnX}`u`<{>x6wGnA zp#%lOM!#gmIXopt?2w&?6Uw1sR^Af_V{bSVlnlx#{tvrs&bDB*3j5N_+BbPGPY%Kt-j54P|W;`QyHTQN~xXexQm372Q zug!+L+pasK?%G?D`cDj&f4A1=r>@CwD~5Rp$~>$Iqo+IvZkivhQeAlu`cC6rW0=mx zZd*ZXJjheoMjm;Vt@vBa#`R*T8yQ?mNz%D7`gzgUMFc0F-GxdYs5t{y&-cNar;O|U z?-4y%Dwvo_=ECE#6e$r!qol?a5ag_$g~7NsW%_NpPFLvCU#;|`r972QJlKPkuW;3T z5lq*5H0Vo}qF-qv`#AOD33Vr3d)AM?t@ax;JaP*29)~ylcr)wb8E~<`U4U=S&6-heS!oV1XpYA;N&Q zwT-I4U$esXx39)ad`FK9-X;bOu1EIlkxJF+HKy?5|A};>0ZHnMpq6 zQ?=4^Cfx|qZocGi8xC{+k-^(HM^<|l`1~EO>wPvD9d#0A0YzGG?k+4;VMovV%(83^ z_ooUph6U{1FaF!vi_ddTfqqMscLU?RYxyxCzcp|k`TL3S))eb z3LLt!Rai8?x$s5MBzW!m=B=*UkP(H{Tmzo}aAh_M%flTUpoFE)`L3qy|EQ3akWw&V zW_MvFiq&;sq{d?Z)6*xL<&FXt)-m^#c|Aw9|MmIXSJB;i&BfxBAM=N^wa%vKrQ@5Z zEn{vk$(xgB*3XV)@S2WpG9^m%*~TgBglc_`d-j+Ln(=E@8u0ed)MMgYFSuB^Q8yT< z9=V}asQ0>gHK~qPeDo8mdpGB>=t9x?6`L&cf>PNdN{wXZ%kEe$pU(W9i{6 zCe-X=ouwv*hADiFhHlNM2Hu}^!iL1}eczXmcGbBEPQIhBh{}^n3_1N3_wo#&a)9Q0kP=x$jZ#X=wuQ2ts z=vtf7*^@DT0lbhd1=!{D5z^hZPcM9Kdonl91jm`23hBQqyhvS;GT`kR_PHp0l%_pS zBsBIUF>rLlGVSZMq8C$-;pA?CT~lDaroWBgh8pE=MSr=hWYMdhEtm>*^27%h7weLZ zq3ba_-xEhWpOd53Mv35W0S+HNusyzCSan{X-cWn8@br#f5rnMcCb75_C`AS28McWy z{FBMOqZ|X14JNz|OlSepg30_cBW3@g7J^c@0vz ztk>EYskd=|w@OI41CD<3GadGBJ}z-#U0R}1N*gq>s$!wTZHBdHqpiKlfFMc-ir}h zbtg1*OKXb9ihDMGOx2z7x!l?2o~KMrS=~67#kFn2g0wM^2?B-;y}Y)^v%8J!-%z_5 z^3v=(imQOb#RbVLKE_%bXkmslv8TBim?mpljXbU%i(*SM>C_~4{ooUqoew{XN_9-E za;uPD0P@DHFHc5!)9Jw|0JQW^(pnS(;%LxHcW)={gPfT6`G!~YG0_dZJ@TRa=k5Ay&hP;XQkDW>LzRi+u+olu1Y?+nv z23O5{o8%j1?qv!dx>GVDLZd$y(#Bo|rv%5ugbBGV4(RBg4L9=JnPf)3SI$u_htWu_ z?VY^9c*6G>6x3HHrB~~GGE%&y8c#(WNYMc-6cWMT42>LGhkkyo=rjO3DY3-MB#dvq zpCL+3*yW!){=MjA%Y~EVuOE|>wOPw%w4V+J3MOk=*~HoK(i>3yp_r%9@P_Md_G;9h z>ut>o@A+P}WzSy>yLw#?_51wZ?&NtLmIo*5h8fF~Yn8nfyUbLj;ODaTFzh4=enwXf z;*fp#M|{8_`#TQ?g)mtAJ1sWEevwvNCm6$U736n){>Yq^{eBZJAl+#nM?gek6=c5U ze&?Q^LuaJ!{Z8$ThrN`$!_0VPUN!-6`8Qn)-wR^BHl~Z+<3g7lxOudkZQkyd;IS0Q zH(HK7&nINl7-t$FpNt8TBxiGsih$Q`-E6zs`kwFjyY5KyNl$3XNNeS=YNYV32IWok zVA}mg(ZoSE&05>Nv4K*_qjj%SWAQV7sRyl|UjXOkBLfg-h^8SeC8iJ1$3W*H)9ftT;&rsqPWuTi-R3iV;(zyCv$FmPEEgeBO8&9iTvz&%Cswj4JS~e@kV z)z96;DInMV!zapED<_fYgLIONymCR)+>iZu5qY%*>WeOr$0-Xk{;M1*E7n2!KKh=Li_2*-Zs1O& z1So}?77?$)f{t-EL<7mb8?{i73}~i>E8r0pdK3z69kZ<;eXz+{)U!2OHJFepIPsOLtW7kd7sl4`=>HhdGKI0ZNb6NCx^g%2usYXrgQZW-r zFn-z^dLfCxh(E9T9H&zn!l{_O@r=_eO0_ql)`%>?eBrUaQ6sv!R_x~dx=_>xr{XB- zHvDpmidxCUR6Y7z#o^)MpUHd~2`$mMFqIw{5pkPw!srj_MurArsFV~*GoAHYhkK3d zKA^j1x#j)QKn(P=n9%+eK!&u$J_pP0Y{n!8@$9-8*{s|V3Dzr7YYNu1YZ5i{c=Mh* zqr~@5Hr;#S!z-L!ftzm)I|e4y%G9Z{7>jJct3c4`nv;ShF>RZ5Se0>++%IjTuFS8Q zna`AY`2{I(0>_K>$nIaj-;Elq)%P#NC#J3$<*#+>kiNp0-etl{n|d+)ZS_0jpRfCQ z2esQ1HzBD*!pxiPe8Z0B^5Ol|& zy5E@E(3I}A&OL2|aeXFq4=qbQ;_g2E(|sK|(Uo`d-lxaKGuv^zuKiwX87gfZ;p|Km zFYgj?FhnmEV8%Gr)#q*YtTZXa)yc*J=<}r2{ zf66OHL!JNhy`j?P$ephn5nl?)Co^M0iMZ%KSjrDdWR_Kok@kK1$hF6!XI0;Xv4MBZ z_-^pSZc?@4sI!4U*|1Hb`S|!_rGDKwQ>~=zM1-uC*tah<(V-Iw?TIvUv~r0wzZpI# zV=a_^1h-Q}Mpn{sJP?9tQ7VcGjrA(ly4cX#gXI%TrYV&*Ig|+j`+i(V6NM{h#3_%E zgqlvh16?>sVY*mYr;B@c{aUo11UCvs=uU6wYO++6m4q!%|Bz$%+y3-xSN%;KXhPy1 zx3hU$t9ti!ZggI`BS~b4+o&~E_;J@nZ~Wcg^LM{Iy?v{#eW%x}1yKl?e2j|nLV}3s z*|j8pxe=loJVVw@%sCGML%4fU^PfG*eOGQ#r$$$ zhgzC;R9)(8J$!=JCxpL->x36rkt(>UH;$NFNHchN|Ng zhSA8dhMFe{oaC3_;1D@_#}~PbSpnF1xkUT0owLfvP;v+VnYoSX!7-I@nN;bZ*V2!J zw09r2ibGRn(}L*k$*8GCdhJR+G)zo2%xI9~(5bA{qa##NOIq@EaQb^UE+;T1=&LYD z)m7HS2z}4d!zJ8Hr8whLk{Y6osfm?VQb>qC&i)-z&29Bp7z`VCsbk!p+b@edsPkG+ zkq^B5G1>>Lz7z!<`xl0S`9pz|*Z&AkR`oZE53v8K1<$l)CODgtp;53QO&Aw8N|S3~ zH^gf*mW@zRR#r1)MP0)U4ncte(Nums^)FB<#ZW!0BJJyIkEzEsrVgyTqb+iJq?g03 z|Gh>jPuodmJ%ETFWuWV@Fbh%jQ&S!DU+3S?Kd1Y%)0<$lqa4rsGyo6+weW$n2Ooyz z19eb&0MQVKCO6&QMf*l)HMa_zTQZpg^q-U1SLapD!cj}_a_Vwhzk`7et97yK{%AWBNzeeL=^|ub+CT%J)?CZPp4G`i7N0*T_F0HCX!uRPP#rZ z{f+|7nvMNtfXKe^j@w%_*}e(Z9DP|ZS#4tQVxQA#RwYG!u?kUe4~IO&V{WZF#ddmm zkZvGCS3F-=Qugz2At)IYWW~5K&c^skSM=|H)?XsCzN-)nloy7OUr}jg(YH~~*LL?r zy7EtZf%6BOn9-wD?1Rf+1wSVsGl>q_JhtBWwQ`S?D zzU`E#y`yg!)_V9Up;86T72nWFUsN*D5Q>cR;f%F%>cYZp3|@-@@P;!5O08M#sBKz znmgnO2H@-4-(Gwcw~#&%C`LN@fYF!mOV{upmfoDE}}oUo$vYnubMJW}oIsJpCmKr1Mn7 z!9!Bk^?egLWSQ@bAaNfS!Xx;4wfVDIoWqyIEt{rk|4Y2a4J%~ub*sIAm2YTgnlerY#>$urLlcz$iJZ6RM()Kei~`rPJMb{|Cjbqxy;YMM zC6$4XX{+VJ&-XM#T4cpcmn%PO+_K(TZbNw9M)&XR4DA_ksLs7gZjKFkFkV7mG{UL0 zJhPmCFCTtyRcq!x$%5+cJ1xUD; z>=e-lUqgQ1S`jQ1s%i(h6sCrRW-*#UVp5V{#3Vn@RBvN|t|&-hN*^Y)%{f0oB6Uhj zn70>`oNT~>-oCWu89x*#J^5l`Ch!XvN)b9Vy>QyFryOn2d~+3s)*!Vy#gw8J|ITs) zFW)#s5Uw^_Z(uNrdcJhX{pqLg*_U|rvxj-f75?|`h9}zAIt22jhxzo$kvELObEiL zQDTs0f^tsG4~0U@Fj6+r_V!NvRm5Xi;FxRyaR=X#y6Jfnz>HUw``k)s5Y8yZcdatQ zsKx%ao1uc8fMdFmcsQP&D{}hX1s@Aecx;fG^JuQ{b5fKEC71P;(ZulRR~R1a5z3Al z1Ji7{TiEcVW`W@bqbwPTKZto*&V8p4XE(@Co_!nl#r&5{S9AjokXE$_5otJtkZgLR zMjNOuM>^y+*9)f>up@Xh`m%F^5OK0883jo|1v@?;p)E z^o`~_4;${Z=Q%)r#jUD7Js%5HATA^W{gy>U%gjI|=E9?)fc(PB9IPr#IljmfIpM4J zzH0sX7{ZOpx1&;19%%gA-?u*K0dRrV0e04Oyw@X#gOq1s>+V?$a;=uX2PoQ~=i+yp zPjXLZlhq_X!*Rdru&{w$k1g*rq`B=(_Edz&H=M+^aR$?K+EYFe*2L8%GQ(+_*jNmG zTz;q2{EbQez!xy`Xw+dAwnjTSvk-tWk#+MqR(6>}!?{$dvf%Oh4|k1X`dGF?Eyqgc z5RH^6-J2SodV6#~wV`}P88i6&(NR#8g)dTL*Jx3Q zu#aF@gP(2rgwUIR6=1(laH)_eJE|l&w6KijC-+;|VXB(8zQvenCJHmZlE{%^MC@I2 zO`qUjxrUSj*qqZwi_Mo$XR%rx6GYfi?9?7t9r3;<`K8ucG)-=wP&Y--oQtmwt(&r} zLbHy0O6P9wQ8iciVv?x0mma7Uw?0~hk&tm|KDsH)7Y3=#k%1zPzNK+u(w0O%y$lW$ zwU*0M&QmUTUd|L|KjqXb~aj26o?czBJ+_Td={R2tn^rJ;f&2pJF|3G+cs`;<;7 zDc|}q-_`Y=KFD*PGjFf2B$0w}Ag`kTQAwB#6{$yr9b=K_eLfa})%jg%!^W6K57GQ~ z_VQO#J6NPtw4&bmFxObcf9u7~$dg{=pH+>sGLAXVr@u0+x{yrWyE8(H$;zxHL8V2c z^C2rZMTk~E`->bZH^V4h_h_zK^k(e7UVKu*BI!&iL^hVTQvE9Td>g+eYCM4;sp`(F zt`g=iD-Xmn6}b;X&8-fU{`>(>4y}(5BrMic`XdkSq?FkExr8dWtl+W}}0u$j= zsPnYmIYOE6HC7ZJ^p|sJ3+cbOV`0v7Dh^+BE65ToKbX&^0dr6;%-i!%yS_Z{#N2=> z2%h$hZ8P6mALgX;ai#c-^sZQvW@Jgv>Zo#9X-ZC%;%Cc`Xm-&V4Fr*w;eU;KUJ${E zZPAt{%F5;1aImmBD2SlZ`xYURuU^&L;h~`%WZ2cEvLn>(60E zsaN>e1U`HIR98+L^t+s~VT9NfgsT!Tc)3!wd^f|g4aMgps2!t8UT1+iJ4@nj7{%mg z<)^RO#U%a)1wG6y)J`oP=)1CIclVI39(8g}Y4q71yLXHzTmRV24kKJ<+DNRetQ1n3 zOp*&z`mj{SVZv^l5Hx?-{Nn$x0I}_neA3L3_{U~O3GZxWhy9-*J=GAG`!lrL90TDN z5pYzQ`mSisz(5p#dE=g<9>ey!$(bkM5u|z`_o8W-Ml*LOeS2;s6(!@H&rn9n^d=S= z%k?y>N#t_zP<4Na@M&MP8n?AcT~kXkO~!kLrn4Ttj_JMn=~uNvUJ}I)(X!&*ZiR&` z_4spi)_>ZCxK|Av*Jg5uIfkzGP}Ojup;rRigh@=$6c!wD_Ui*9Cs&MSW*ni6bRuCs z&5s_(?>1KM#V@7wj_*#FU$CejHI3`%m?$(h6g1*b-yDdL<#rWn)!8s{N&Mt+RK~FN z#LXeHRb^wR;6LCb6>H>tX4*r3>_I0*^F1_1GJ0|jo%GHpx^6U=QVgiFYk0-vn(mGb z|HM;8J%BZrb6WX-G<^kIn_aLiR-EGQ?oiyN5ZooW6?a0_Ygl^`ts#qWa@n?j==ZErJUQojH zjUslKH0sY*aW|qoOhQQ-0HalEqm}m}fipnwOuzALMf~__()^5Wy_u=e&HXq1K2>Vh zlF#Y)S(lR(u5;3~JCJY!M`I3(d1j=&xs6Z1MC1h4X@okFt~^O(QX5&XG$b)IamyT* zTT0B9_>IsGul1w<6N(uWltAiA{WnWGOG^tZx{-|>@WF22j!j-hL}AwpR@@U2tE2tt zG^xU9qr*bDm_PH!+A+~j#P!ug!L6*#D6Gt2(chBZN!O8&XG z&1>kN6R-<5zTOY~0%Qs5Td1;JC-lXDxcW~s$HgLcPy5PK^f$YyHU480Zfh<I=~NljpuQJ$4#ar%Nx~8@RUqYZl=R-qvx5e<=*+NLGr72syHLVD`X} z#nvh^TId~5aEH|9pNME{qw_ZhKkZ^eeU3?Z5mDd09659XL>?xcH|lNF6^{>AGSS{{ z;~N$7R=XYQvhK$BEDxI<(dYU!@7VGR%yQ~?PUCv_ME){=e)!fo!8FCj%s8betb!ux z67JXlX~W3$44?Al(G}7=b!C1$?Nw=CQ%{)bux<6|Kxpd|jW`Oa%p1p`mUv5ub4#>e2A7LI_c+p8k5P&TZ^FP7e1gf@cYm zB*W!@$`_2CI;IXj1-L%scCFGg_e)D>jI=tLJL>Aauh6iLO~9kCQQ{AQEkx8t5g zDDj%*MI@P=azzP*pU=aANKF5&-O?{C`HTp`NgxQ;-{C{LsN+b9Y~W@I>qoNJTb;!A zD93Ypkx+2@xsH0NLxt$JHi>(KIIpElJCSd+CoQ&hvfWvc|ezzni#wA36G^>2NW6IQMT- zyZb@xy_|eWW>Y&P@ctKtrXKu%-dc6HWA|wZx^PsX2{=Mu z%;xzx-C9eh6?N=9oN>sirA()1-oM$u9vGWQ9O1S6Gqd%ULDw4=@F-;gnr+iMQ{mjYi`13zf@$Wd8HZmv#g*Pw()bGIBFE9DnS2inXoAVcpnW#{O z4G2kdY^vimM#_!0KSJ1p`!9iu-%82W7y*0*trm&{ne~sI2_8WhB)-&MO7ROg>iO!>&w^uNT7pL@o0!s$% z*N z8}4r6wMm4UAxi_n5&li({Vk00spjpWir^CT5zJe7#(-_yc~kN6yj~r@4RfRM;g)Q2 z4SF|MZOjnj^AoC#KYH877kg`C-}L(aQ8(nMae=w8E@mML3_x_b_sQ!$gYkfrJYfL) z*qMJn4WWY*s($t&L4^a}XC0r1#_ivO0Cusd+gB2Xe6ciQ*O8wD3^6(X{yN!3Iq4dx z(I&tax5z9Te_soJKH0jA*$ zn^skT!(ABGbQI5I$>SZk~p16 zE-IN{iKSq(nYw>|4WIRj>96zY6=yvJg?Dm!vrRzE0)| z_C4eA#(ayGy4sH48Wr=srsney!L8k5=}`itxTHaP0AQv{@E&S;@-H1o#0CHdI(8v~ z3A7MD9~QxX2-u6d9O-I7c)J?;emk|v|NOfsUgW;}fz*)L-0^R=*@02bkfLs?0R3R? z4Y%DU+MbA$xUbOUP-Y5hj+t5Y=c&M8(B`rRMuFLvyeBdrnrYlhBv;*2#ip+rL#kVD z|GdcL-Ov_lULwgmUOOwZUjhyghz5@Owc;-|=bw7OjUD%-x@i@XjIrG{kcW>r5$ zf7m4R@5#KoT(nha*R$XP?N~X4aH;C$3eSVQhaNWDUb6C@_Stj0Z+?b1TP0VDrT(Z{ zQb?i+fSVY&rJ8LAll@}}r%-~2YJ>p!P%J^C|2elrlt#Lp$|O-cWv9&3WYfmBXf|T< zfGdkUav5XiltdQzikOu{J?FRI0?hbo`}ioZjVFI?wHADHz@yEao$TLT^6VyVhymDk zk_r?pL-;P(?8VV>mbr+D*^6t<1Rpzz(}E4@Tba!D&N;f<5}vB+v*qCj&buX=WGn{( zJaKNuGdtQvL^?$y%#3S99Lxq;zQgFekxUHV6UF?ssCMyTsrKWLGFzvV zcCAomO<3k^r4}YScMZxqbmd#RQ5>akr3gf`;)ZWA<{NgUn6fQ~q;`}kS8(5ors!** z!h8-E6ltj(t*-Cj?ZpoW$O=J76V(Wx`kv30p?xN0oIZ-XL_i zt0(r{^)?ysA`!hKKN+nbGZmG@WzQ#w*a_4>9P7qj$G||X3KJkIRK6m@5TXiq@+~e) z3NBk1OZWpVK8~k_EtUNUnC`h}$J4_3jzdhXf)sVa30tDdK^>+$9YXFH;SZHn4tP4? z>bYKTP&jpw%v>TgmgD^vDmeEl!SdBA;Ph2aWc*2+w$LD@LQ%M*IDfl^`LTp}%GV`@ z?JNy1#4(z(>E2#dlP8ez-q*+CWFppp-dx$QjTM*|PInmHJW}pmm}V|nvB>h9$Dsn^ zPI$nPUT-Lk{vtL>O%#6`X)IGFg8SlJdE2Dg)l)vua|qgkrDny{qh5O8Unwk#zcz|r7&Y=5j8&e5 zfmF_PNUS7CC9|VR6VT%6S##c)eVjzm^3MB`TK=z+Zke6;zF3F6-b)w_7C~y6#DT=6 zGN~LL+gmvGn_84dGA&^pl-Vc!9#6XCvC=YB_8QGhRJM z^8MiUd*+o122u|goKH{+NF9*Ub9aZq7~O536sihl!G;@o`5rL)AXkCLQ4q3RT$?pFF*b@P@n|xUX*a!ua zYJOKjQ%GCN`VK3Wo1z=x~aNmF-`8up6xXx5@ZmL z{usa}d?^xcl&co^3k+ngU8E>7tWtFtx3CeHig5@Jr(5Gu-o(!rJj!6PncY@_&D^6@ ziN+d8Byp+(Nf)1{7VP!I!!oWv=^viP^?ctw zF8THuVSG6l(i@vt>x~j|@0TtgAV^ed2?~9!=vkTMuxnp3y_0j#&zF4bICu2dS}zl zx=?PpFa&!hCwwfQFG6+&ULwP1SZxes0$%kyb&5JxU}I=Fh{>qugtebdTbnMOg!r*3 z`E=XjR=p$SA(|T+gI<#Zx@MN%Zy#olrGmeQMQBPz#_)h$z1^Sx_67?%b!IT#`9!vw z|BAha&MYoJrEP1lD*G-D_^XBrHLZ(hH8f)sSQRV}X&kYtAJduvQ;~;xi_p+!>l}2p zwQ2N@6Y5D!CLZ#FMiy{8!drQ&J71h&34)6X{H+Zi&A7xKKj}e%?2>))~_vGrwsbSwy z8(TZAF-R1@YuocAo}Sxklb9|}U_&eC`s0$1*za)b1-o&6%!Z6pE+Qg5_M6PB$cW45gfQ6>9VH!nv=w+~^~*9Y={P3%-fPH`BmBQu?IJB$oFsFFKk=p|JVRlZgj zL^VZ)lNe5Cfe)_3+)lP@JYDVOZ~KF6&#v%|C;u#EGc^!YB6g;`TKuiYa%9WmNnA1q zhlSm16B&~~?KDgpjNb+CGYshH(ka-*d5f~swK&rn^pu7!!Wlmy;2OHvvUyCWlnka( zXa#CwsS^pNOsMQ;doi{9LS;HELFhz3Pq>K$OVVbR%M<02_ah=QGQ3BNq8ofX%zf`h z^Tmdx3diSfo>pDIq2;Q$5!t=#!yInL$l!rR1**`iC$$gMPQ8n+aDr=mB^HuY4$_tLnGN_SL|M9&UOCFq`k1Y zr5P(n{9sWs0{SGm@b}~4`{xYX(Ii5*N`QG}OvikdX%gAbH~NW)jO8T$6Ws#)Y_u0S z)4j3<^9E~DMS?8Fg{3r}m-B)I*Vdw|$EU4tSX*e*`+;g1zgIa&8@G06WR?2tZGM%= zMAj7-bB)b3^Q`tVRG^3(fBsFW!2++vYWd;SHDj94t!UiybPIvISe2E;UUraDj+^j3 zt1NFu^lLi(Z*25(w|J^noBz4W$Gq~^QF1FX*Uy2Bp6Ty+d1T9M^s>Msr&}JF<{)`R zfS^MI@^-}J+lHon+miMEkk`A-P>A&!RoModk~m?r($U1)1ask&xdmS=tdD}I^0IXk zv!-?EFpJoZkdcaRxfY>6$11KV8*y8y`m~k0WQA6=7vls9{ro|F|C|+2sk~Zawa!-W zCR5e;UB7J|t;T+uHUdb2IlZza=z&Gb1a%d7!cEt9!mU;~FL$75nrsx$YBgEHq#gGH z8RDcN?O;iUyeRr zd-#w79^zlKtd6C`VKT59IHWbFCLu%nxt46iw=eh^#6lxUWV(`z)(7cjR`yS#OrjSR zpt7#Hg1W_Xz4*Yob*Fq7g z;Q@`OtAQGP(?ktVGK3GI4$P?RHKWB+r^GeQVc9d;(Wzd8g2IMG zZt-{Tu#Aiq0T0WD0<}63TIHc69VIN&v^e##W-GLKt`V|qI=R`4yGkV;U(T+#o3uuS z5X9Sdf}XVM$zN00r&U&CPiV0lSrsYQFWq@h2ueX+Pox1RzL<--49VCdoN17mL;;Z2 zGCwFX2Em-0mMjARPs2UFE^9a?kil!w_Acs#72E&^btEiVs93Ht&&N%KNi6@|rrzb< zq{srFi^n%>8eUb9yySk6f>cGqkF2C_FbAHl zY0*R6A1*4c4}>wuI7pg1l50uZAML3B<~&n1D?yzXE#(|;k(>uh3}l-xe05^;D>d}$ zgoYv^Py~-JYTRGMX-wH;eAn=yootf#vgE(@of|ne8!Z~_ zvXfnQ0>EjaPO*yq*AO3Z2JHdL`7^>}7o*|qyiTqDV}6XE*t(-g-k5dyZdA=vQ`g$` zPv*L0tAhRPljHF2NVh=uX)9|}m9|tzizJNONqWDaCFs|526fsk(}uIhC`d?fwAJ-w z2L?*8Z{I#3A$gpZgZDGn+vRF3D9`&C$W(#lcNM~K==&e0#RL4{CyGjt!{UrU`#El5d?c{G4=D$JuxsdUQnC;8<`G8qxlpUwq2&x_l(SXr+mn?FK}BM& zz;fvZ3vacuy3!76u;b3rkM(#m^4!4rpAB-od)n^Q2m^mymZuqcok{P*Ew=}17xDI- z>hri1x2nGbnESL#cs@2jM&1i%SY7VB8R}@dnOhW@IvrX_EFvjZuUW>9dowp_xj7m} z)lT}%3%PxcC%_ZM;BmI33j(poipzPHu=&~qOwLIHnauK$;<*mFN;x@U7l9YyJ2$W( z>(tJ0*aV~{=Y4Gn{tm1%(BsK3QJpgkhK>kIrO_)XN{i<9Tv)w-p0Jp0CqOw#T}PD% z+(MlGXaH|~r!p#jy<$Z*Lngjczo{U7U2)P<_uEszd$L%wCC%n(eaV=cl*rw88Sg);%tS2=rE!VzW#s22^v)pKw$dsV_ZTdGWEZCK z=PwnyxX*VCpl1tDXQxfm6cK?rh}gec`W?2Yo4a?Ls+r};plxCe1_dOO8u)z& zXLG8h^{JXf&aPggaLGwj3813vVefgp$o!OO8OADC5pgy$MoQVtBII|i^(Lt#P9_<} z7C}%y$7p991hfDZ;Ol`<&gn#z@yR?#b0Mm?YJn%N!DU#?i5VH?=7Yp&wQBCA?NXeL z5Em#q<&%P}g!a~MX{7ug(Slf72MOCo4ypvK%KcO8zi|(cX-=P7jf~8Bug>{Kz+T2> zo!);w@2V`gr8QM+i%dMJ8;(Ab7t|B7@j6(EH&S*`2mdzxGw7J{sY^+tc7g$)|p}Xv<+*vQ$62d;?zEoET zx*Slk)8Bt-zvxKW)>bGh{cd~x|3Oar#yFmTIssQJprtlJ(Y3|$`)>ZMJO>>stugyp zIlX69+osWuL)%WD#$d%p-4c??Gt$m#cgSGpYG_J?LeiW>;HbqJs@|7c(Yep{o%n9= zobS$c8vuWBW#A-wZYI;hy|~M>UOv@#wlF%WI-krrMz8HXFW>9MiWG~c%-32Hid!s} z*xCYG9$mKKn{ElREF41&4jvH75c7oo%_75G=Ro=&z5vwsv*ypWUW1BhPsq4D}5bc-F%-i#gc~ zoevv`m==W$=HX8}Kk#uq5dCi9#z?|@EtIi35bD1DXA9E$Oo9X9o9kC;Y9sbIOZ0f| zW_0EPd=YJuIu2-S^`vb1bDu(WM~-K$)4~jTR+kX${56~&2MdyxT{-JU+oC%ObN2mv z2HWk6thUiUoSHV_Db>Hfrt#nFUo!G-lqptc1_@}op$W)(-*vG%;P(DJh zlp7H80;4&36{PXAQOw{D#KpuEaCWs-zKy8n_qnj|zgQO`628r?dD-A@Wn#m|v}4g% z02CJ%ibA%Zv2Oh=Kr=XsyDxz4Hmo`CeKTX$`iK6qo#lSx>DLcY;D``7zKdXVQPzy* zVZo0ii)SC~xtlzj>b_fO!D73k~0GELv#;D$kN^z{gaN#$TFBu=4Ok^tHY z!cK-WxzF*3)rC?Jt=#NO_r=YyFK}Ul3+-n@B&P&7gyRhz);peG(P8J; zq==3*jrcuTQF_jjQyziTH6>PJn3v6Qr@_aoN!_V)Y3g&p?C$IHZ8&a4JP9|QfR z-m*A1Wigi3A$vV9DzzOov^`Fj_tS~W$DT@1fb-Q@z&l8bo}Nxe0Y|P8(+mJ~c&jkb z#4wii5Ou0L^0f~>@Jo>#dR+w5%W*Z|KXcdufPILy@Q5)) z5l7xP!Q}7TR&>bvjm* zyH?pugB#ZD0;GbpU0kbKf;oBjpU`B*#u!u51X3!rQ0nj;m$&H+?}m{dbmbolxs4%@0U_d1J9$wEqGE= z&vTE)>!NNxY+|0-=k|%$j`URuVSCYaqPuQZl`LIDZi&Sita;vI?me@eG{7{Ku^12b zcD+%q@84VO9K?F&(2|Nc#^YL~Ell0ZkM;(nr2ta9`yQ$c0O+PdN(>m{zn%VzKQZcI zHFNG&C@^$z;Vf~}p-fp=6rp%_206HMMF7H$y}ITSQHoNeYXUiLJIRBd@7LiEtNm~B zVy$aw$fGNC@K(`%~`cL zDz>O_B^BO}l)*Whz)tVG`!y$G zY$&Z*Otru>B_;k_CEmuWx$3J2ikH4#?olgy2MOc-tp)fKfYxqI9FdRIHl0D0 zmMKncA^59F)rLK<*kf?OvsJ+B)6=0b93C_7Z@oHG8q_}wQQ0T+1TM88+`LG$u;_1y zy4+>!>wOJZa&v=7Yg&Yhpq=g3MP=t_*ZQQn#I5=7?(x@W3wRgfH-*21_7q@|`PMnw z)08C;<-Qi4SKOY(?0lB+rt5|>b3#A4xFDJm?Op8<`MAA5?f}lVs8j&#_kXkLv^QAn zxm~51m9012;p`80l=_}}p+K+Vn}J~1>5E=(!dw>z+F*T*Y}^+1+_j|DH&>dDh#1gS z7SVLhy=L1@y4H!#;(3!rNz|_LX+lsx0YM=coJI@+r0AOd7(1FEEgIA!h8QS@{xaQ2 zd2{3UzbgB$O@4PL3Qk>3Mm32cH60#;TN)YxU;oK1M8$oYNjtloJUr9saoee?TY+Fp zuctfZC{tF`j?04V8EQC$Mc_i)AgCa1cH{S>o2ie-j~A<~B}4#wrS>9`39OFVk0cGd zD#GL$3wbgmN^=a&0vOzW;#!!~&Y!LCRS|A3A51XwLRHj+IoTlgwz*_HO$$oJ3W6HZ z=T@a!E6~#6znwQ7inDqN452g}%xH0wN&@CVo*&f%SsW2Q;}J?gkTiJVMa++9H$@ha zkZ}0@$4Ak!c}aNtXKl<`EJT2&i}aiZ$F0_81^(A(U-cT#3Zce7Dys;aV%N^KsZw=Q zj7%Pmu@2!_o0NN^QqLo2a}OsA**Qm7@~0)QLWUI%3;-QnQ=x3vDJDnq$~T8u@yUhY z{94p_3{DKq94v`p*@C@aED4sd&W+6O2Bu~pD$L5z&?Ys4C`>d8yokvu(H3K3n4oIU=dit>4wgyujZ^!Wg*{guNTJHyB|$m-0`Yn zn~0?O<9QRCz@~tIbi$)|E56uQsRF3;c-Zx_ooz2k+$iPW88f;}Toh$9PR~$tuI~x4 z_Ocahdy84HqP-N#Lbw~QS{`fUt9y;*ZCHNk$LB>2|H)dC#sw04>au0e(>2I$s(ewu znZRhhf;M6@r&xC@J(dtIR^V$+jQWHWZ5qI^oFnqGMR$y$w7Jemxrgz;J}NkA&gSd> z5M@Ez9QBU8XcQz2E|}oLNy7|`!Xd&)5fGSF`8{3Vd=W;dHL59O&|4@|?pSRm(R(lx zG}3A|b8a_kaeF$`L-pHW8%i>aJ#+sb+alEW2Pqp0gcl|@Rd*Wa<@sF=jNMGMfpaM} z4W*=u5b>1Vh&nK-i&0-_LdKI6K`B{FDh@f8cvrI`2+EX{)Q8VSAcr77U+>tPpRj?Q zYAT0XoLn#EBa7=+rV1Hj#}5>$G+0DzoK)1iCSWa2|AeNsoi}W!1LAhwmg7BH^D%Dj zhfe!|CJ~U%mq4jHSZz*8P*eEomw~>EU%gIS;9&~7<$(=Q=}t7Dfg`)E=NyBRs_ehS z;m3?RWCIS;gaIkmDlRc@wIB(VX%!mHmoK%Z)Z(a`5)n-p*Z>S_Q&%@Us@EC(Q^-*T z!Z*&yK7%UcJ?-bqQ{z+E=T>+f?%riPEb>piUL#>dLXg zo_|7vgWUbS{Z8tNgfjDz-v-@rp^(HdWx>fW3<+s~&j=$L#Qvp2iFm-$Jh@RVyt9Zf zO`17L?-|cP;Ms#;_Y-(m$DIlmTj#ePv98^>K)}90A~fUb66AZoeWhcT;vCC-HZPTk zOb~QzPRm-lSv&4p7FHkRR>vE+-dSC{h;2jHJM zf9qqK0HBzm0Er^ZDXbz8=3%H0 zO})A6j~t6VA8b_j#Z?y@eJWU?Xo9a`2!RVEop*`&70%9ptE$89&E;QkSP6AhtC7{w4RIXrf^pd2{Y4#-aOK? zxtMeJ=g!MF>0^G%y++7YW72~DBzvadT;be!9s8bmIIlF-{aa@bS&Prpauho{@AJ3Q zbOgQVd9VcpNXpNeOvq$WQ{I@`1rOlG-hMrE!|8!{BYmI_NeC{0DO;?p4E~@4ARd!~ zmC+?F=_%{Ne{02JBo!s^xlaG`q#!O~L)E0;LfnrJ;b*~s+DTpPNO^=oscxh5vh7J|n=^AOy1i32!aadmXOxp7Z6O!yGOi(H1$67vn78lwWYPvNI8J7; z7Z% zHB~>6ZFUZRUizlG^&9=KRtQW4RFQ2U;QLnQaw1?rahidKy}~F$Zef8S*q;EI_{xc>91ZFof`}UEkc4W8xZYp4 z)`V)b>vfdEzZKC5n+1|<$B7pUWf5gybvJq0Pi7s=(*j?4z;khR%hX+HglL*3Qk1-g zHe5+Fr3bvp%xrNm5a-K+KGhh{z9o?}!YGld@V~c6STZL!Rf45w#-Ph2OJ0|*=~jZL7vxv8QB^?dZ^6!GG(z)(8vZw zCl~Tm@HlkDpbRe4N&*>WbXd~d%ubWu`{w$f>Di9g=c66oya|D0{8bWKkt8nBV~4%$ zX7SY3!er5_e>VGylj8YT^0C+LcoK+&Xvmm%G@$YfqzSmY72D6Eyhz8`U}XgAhM0sV zr%%L;_EU(u{5dqB;L>8n$yA$mD#T4y86xLiGa`k_7ieoSDJ9($nag*SR}o8Fk6X-V*&h?wc3z@LbHWrUJS!5@&gT(RLWLSu4F|!1L+BJ zKb{}WTCR=`?lw$Y?}{NlVUTB&4q*_VQts9CoY+CR$LvZ;r->nLJcX>HRRBz?toag_ zW52FcnZXN~wDa`mCSFlNEvP?`i_gDI+NA-FP@(NFNFx%mo>WoYvxuntBiaAv;GMi?2lCX}w&YP=4+mYwHez~BZrG$V*b^Z``+1cibKr4~8}tFAQw zUS={D9txuJmp~MNE5AZ1rsMEUOyx>PbK{(+2Bjnv&3tv1j}x~%pttK)AClVi4gI)) zVYKk;wW!01s}bsY+4CC8!+8K*&z+Z3Y4mgH=VU-_XLAa`F*qQy{ujO!3l@R`ieK^i z5f~}EBo>ZUJ*B(rMQ}+uyU8%>W!vSH(Upx%5+5B16Is91<5-_VV&AaDUx_r1xphj) zkZ}^@@{*k%Y%|7aj*;w@ZKCdtVy{up@4HM+2}KF3=6EAdEK#fiFN>K{mco?E|`{GK;{%&%JYkT{apaIkW3#@FTLSxR~Mt68WYZ z{H>$XLD)_7L}7)8^`iLM!z(IB6=t9`MS@VIai)40HI!_b#mezPQ`SKdIw?(GeULBY zfk=l%J>+8Rr$hZ54q41ZOv^u<)~=@2Fc7xXL&_k9l=SET?k^Z2i=%o~vgWKXp;2YO zi+2gBkbx-?Ib0H{1KQ^z_Jr3j9!^p+UI7}^BRHA3W&?Ul-&bT~>cq{fI0hr4ngW$K zxrreTQDQiKn<<*(kHwdeaU@SHR+@W74G$>{2CO2D`NCwWStDmbS9w`jqYBzhvE%LH zI(;zPGS6+M;w(!8#&F%^C^}o1F@yFKPakvp*d2;OMUd9MM zg~YHYBcD2hFQe{P+K^i~AP9k?C0}Q(+HysS+FZ_ezi2UO&S{;9n|7l0$I{^B(kxns zs?ittvKtD>_aRb-+#(6*XgO|Dy(Fzsna`qrM-yxHPiYxs5cfw>f9~%0zFu=HL*y5b zgr`qQJ+CB$G!;{-pEWsA>eVh@;a@Y5cm@f0pn)KBa!su0(#g?ka0K1`+yatHxe#qg zOy*wn<6o>uu$9Q}}p#^i0uu;G3Y+!GiLdSc=K_`IGN0%Dh{#NkxFmJ+qDr& zR_hry;$zC&YNZyw!|H#|+#LElAu1(Jm{V`V-}_w<)%D+lCRd?>v)f=G*$Hz}yGaTq z@noyjxC2Z}Vs?@mRD|s$a+qh<@vnY$eXjodHB(7YUt7k&bdgbmou*r=ybrgrJkN>! z*8y@lx;$u##a#K35jx78VRjGc*eXJ{C?hgZyqG(2yrYqrqdekDSi>Z$@%Uf7)qP>{ z{#>J#Ow3vO|K7d2{zN7rbj-pH6GoY}k^GcriZM8L2ya5 zGnF^f{i_&|2hJ%~W|0m3FBYSoCJMXWyj^@xS=!$2ttkHCieb>_|o7wQM%B2n$dq-+{EOm3nl0gwpihyxuWxnkcgk`}e@w*^yy2Pxtg_b}`wk z+QuK$A-9PCMfr8HP|V!rzcx%#DWqGU{I`n`WLm;x5p71a&zn-R{XfpD)b8C?A5*!F zbnGwe%b)1}v)HfS(tB=oOjjI|FuYI}b-1!rrKGc{UYj{A(p> zLf>*sl^WMA&+A*#u25BK>?dC?+a!xpi~`-YH!+7gXF0K6YM!`L1a*_43@Q{Q*H_;DdO{h;D z9x5^}#&#@>RiaVjf?eb8nXzF*bZ}@fq)FmR!tfS2(vo$Q_U2kp`KD4abP5PSK>xKe zRY(k~)cOdtiJ_P@P?HKM&I&g@UiRnr6#hLQ9iZXLO=5T)I-f}8TkB!4WohZKE2Ett zGx|o)51!OOQ7^6ck=#VhcVV=3x|NAQp#g)^{f3K8H{@JtfGGj{9ebo}8V%O-<5pda zB-!V!#q#1+jphRvkc^t8p{Bly8ezU&Um2Srjnq^|W~HxuOy1z=+-`B)c+mVz!C~Ag z@n;u2xE!@AS9Dz>?5f*Hx~zY&$odRt^dYyXK#*i2{>&dP7roD`Rf#Y1V3VT0umr-Z z4i87NgHq+Sgo`baDiqi$WDzVrHeC2@Bmtaxub5c-L2$1)@{$;~gtXjDpN4zBX=dp& z+PUg?rGb#YLZ;Zf+YHKx5vZJcz(P7P`CnWn&haxqQn7fB_rI zpjqH(@oU?Zp&nm)fuJm8Q99~3oNBB+4uvW%u38yW=U*8`W`WP?mL)3OE9MC5%ve8{ zJ=2XTP0ezG1&aixA0-iwF~Q0&G7W*&bxeu!#aK)+1kA`NK->k-p9qDf?m~$hcj0q8 z6%S;su@@U%e(SP>ayh6dzhhiPD7)Q1zGazgb-9dv&iRFHTIt+nynilyHcyT{rc*isY}umH!Vjtls9>Qn_gsua`=co z{ImdRouy?fm!j_8HBz_!8@{&Y^^k`(lYxFGFK*Uce&iA!G{OX=NwUfirg1YhP0AuEl-N-ivs9yL}Edk%K>l7j3)lpN^g;u$pkEHV+|| z(-Izre6Vi1SHI34Ku4a6LXvY#CV#%ctXAl#u>3e?A==#{FEmt2b9nLoD4jY?dj^b( z#3oGcyYHD94{Epzx;=R8F#5Y5rH%pn1tQc>e{GWGW=3Vb<&5@c&}$4aAtBz5cJTSE z;(|{`IW7p?K3Ve!M=$R8$f&)KzBCUu$E@zYa=lly!-$cET?w zV=@OUf1h0$myY=E9)~KmFOO&Bw0k(2Y_;%`<9I!|z`O18tbDQ1Vz+mGxNp4S^*aB_ zksq=<(k+mAu9jBr39tG7AIT>I#>|Wf=MO7=s*&VhDI@w~S^qZ+ATtbs=T^mr1)ts< zX`Q(=BN-szWo&Q-(un7`Ez4}z#O%0Vntqr8(Px3sLD~DPCF033pE89+2(EtlIGQx5 zUXOg{MgQ;h5J=n}ILa5!L9cP#=N}++P=$68>7e<7z7*~Q6YoUonW{@D?#O@xQv4H1 z8AG6wy<4Fcm3Z|qR(7nbFb=4%tKTVm+TFca_)mwzL&e||xSaGhH8Lv&yo<)s#a=Iy zKYkOt%4b%Y^N&g{R8wQsd-ZyGAVWRi7=-quoE=$gAnUWSQk^7gvKoXftBM-Pe zglE2VKE3CxDY)_^E#v0uyNqz60jbtaN zF1wN-P)CwW-EP;&j}y6}IbG;I z_=j0c5!^_J|Hsx>1;y1w>k=$@aCZo9!QI^n?(Xic!6iWg1a}+U9fCUqcXtmqINY88 z)HzT0d8%e=_w?>wpRJWL&^t>}e8s&t_=PmlZ{LWT%*-tJmIGtFr0M>Hal}s~>8Ck) z&iFSn(?f&gpzDpea?c$8B#w04Hm6yEc|sRnJjf4iL3J-s9p~|g5)B+2CK>K>x46W zESKMFf*=amh&Qr!(KGNM2O%by>fI|p}4i>T$vgQPvn;u#NlC&mYV?J6(3y~m7 zzz^Y(fq-p7A5C;vFIZRTqQ5v>Ix1e^5kMfa$W~b_ZhjSh zSrzG{)!WE#*sR+DRMuIwnH9~wpP7mw{my1h0sMGFvvZJi5It*rjIikaWN4Ii zAbKeEQV{574!zvbnm+!Y+>QV}LZ`hLL=SCqehM@NfPk;CgM_cl)bfxUxoF`cqBnuL z`WQ)SGl0thN_Qhz6H{d*NyqrjSyiC)qu3FFvF{SK<&hd$CHa&0^=zl&iW9qk1RaU} z_c%fvb+q79u-L$$eTtovGvjttxFvcQx+~LxIHwTPbnUF%aD`SjV)C{Ma;$dLFB)`P z2@cdRDrOY6WRO^q;x!44*b5->nUf@hVT5N@!FJcD<*eE308g6r_cZG2+g;k14%8OE zL6_mt(8h87J}FSXtXzT9M%!94MHzkbD8qe5!9nQ>T~$@Os7U&Oa(qB~OqHs>riSOE zNldrR#Vn|}<1g|uNtMltnX9d&j;x~LT9>wWl~+lM;A2iIeU-vW(+0}^k1(B53FqDM z(rMBqqsmjZr3oJ_(FG5YABkx{hLu7ObaH%$%3qSWn^-oBDSevL!0b@S7)H zkxPFs+I+P*%dM#g3L;ZV?~$N>s#o~qm`~N}zsAefmgV+H4B7!jcJL4F=aShxlQ`zw5auKP)Qx|J?t{OPkS?Jo^-%E>+V8;`bOb6WKYEithlZ7Y&xXDpmfgV ziuOIgIWcp9$?UKxjiDVFj5W+UPuNwmO6KV{wwii57T<9~aUH;Q#Tf=%7|Iz*`!vi=Hh>Ec4j~6?<-r!__k_~EhaizmLE4_h&VC$Z1 z=bjh~O$AGxBOIhE>Jtu{4VJc`y_wLZVv_(@PPG5t7uQ@Ap=+@Z98+Bk^E-Uo#bIQ3 z6{BHa{VBOV-8q-asJIeEG}EmcniXAT%YzeeG}YSSda1H)<=cj>m{DGv$hmBXa^t`^ za$M5vh#9a^EH6vZzdp0@vO1XakpA_dEvCXu7PnCfwfw zDL7G1ShJm%(OC_EsL}ToBIKnlq+Sbx6G!zm^Dsn1P#XY2fCg#iO7XMKLv0=Ecvi!y zOtY*VC++JA6yfj)?&vLCk+CDt;K&5azCDoj0(S&6il4!|8@n6tmmSTV2f6Jp0IIZ^ z0|ZLxZh$z3_U_|`U?)COnf9_PNIGCQw$#`6Wm;U#zD?Q=DGL4+&$2UHoF4u?FNLU~ zt@1MDc7@>6`R9_#e1fZoAjcO{_c8(33^=oX<#T7f%){25^&cTUv$vb;8BvB0N86YF zy9<*-)S>ZAlx*A^@6V0KW_eC`h-5dU?^Q7~EC#G?Qo}#3|MLwMO4ad1J@q-+R=#ZA zPzXsRoz(GnT6a(iN_kdR#3nXE3C`+JFDdk6Lz)w=CNvggtDH_0!C zf{8fIj!#0Ze($xbv*%~}fQK)}eaK^f7F?Khl>MeSKL-}qg=&8B?vO4lo=Yb$<6ZEY zxlJ5HFnjm0#t;)6Z~p`^7>?^!{*1{UdBUq7>;rTbGbo5@q~Xj z<{=&`VO{b(cK@OC!^2S2uTplQcmcl24kh{dXZlrBs;<&80IK?NzwvRi@aF-P)fX1B z*&WSn{~4;K=BlotQ@^@GSIn|v^Z_og_b$8=hSJC5-!Sov#9H#fsG?MI)}>fiddQ?8 z8pSnKQE8a6@VYps`tq$h)xA#D63KP#BAuElpP%vxiV(*n_l*xb7*m$TB%;!R|HOl+ zDQir8wzy4*9hQ?gzd2VPwqowWGxlwX4H{Dy@Jc+>@BNQI4Apd93(p#Y*VRMM%gbB> z70k~Q6Gd612h@CSf-EM2E2$?S-NqG%Lgzxg@3)8S$zN|5?!b3-3IV>#%hq{;*dINi z@Vw7zRcoaHA7qg1U5|tb`orHvbiPk^H zPLyOf9Jn3YoangmK`VZH+;wHXSnKe6cXnM#H?>t%*CBmYlg+S8>FZcjbV117o;)vh zsf6FWJXhxaHQCgInA7AiB2nFAnWnW;ozrrmRpKKfmd+yg0KKkZNEhw`)foB_7$C5aeQd*) zCV&owucE_lSDTLY#(WCzX7t0!H_v8uFO7g%E70psz+hWdyr`y_j?G;M-$G9u`LNjh z#8@*6m6h{)c5Ebk(IxdehN!fBk6KB0x49Qi9aExW!o9@0H@(t2s#nAf82u9uToD&> z$%ISH-z~e`ub#5fQ^0N_q_KBTN=vNlc;1rHp1HsHrlB~6qi8;Thu(7i)CH`Ks=~RO z+^xa1ecf>{0NyOOL> zoJ1f#8=+~aROidzbHAgr@t+i!rjNZ=&SgLCLmpJQhJ0N9rb)n&?S4pPsF6?61>IAl z^jc)dCxH`Z^HfE{$+h{vj|R8*&vsC9Dji0nVYFb?lcUy#z(pFxQ5tY0Md4Svt#fdk zfLvg;Da<(CI+Z9UR$Q&}lhAk&-H1Rs{^qytxm4`Izi!-Fr1M9<29A@QDF@3wDT+%@I2u&X$Sy4Ef9W{zv@zX!8a_1{Mwvf%6r4Mrdt^br!U=dA zBN4($h{t)sbh_zrARMB?ZX|_sr?9ESrKd-W1R<#P0_sJ)w#dBodxZp+iA4Tyar*U0 zj+%T(WbyvC1qN+?#NX^I5bZBp39EnXi+fKX*t23OX&AB49I-AzJiGoj6gFF?$*oTiOym&p(~Dn>O-aqka6-bCYr&2*(ybBR zo+f0ToY!(LBo>voSpfT3tzG&og*>hH`tBHYe*Ge|+W+=9UmxLv0||MD0l72bxYP67 z?XOeL@q(-Slq9~8ji)KAtpm;|dJpFC4@^w?5nDrZ;7;`LHq2b%gjnXRg zbA;x`exrc?sQ%jclJ$m?tNLG<_zpNT3W8eKwldYMZ`#r}@M*~HYbEoDW+j^z3C>@2 z627vOz#u4&xHu)MvSQ6xfWW~rh})q^u<9jJM(tv$=>8*w%{wuVV0cx$t|7g`w!W&U z<1hdg>Z(2OwW&_KGakBleAiWFv`&)7DK6?dpVj5^R2)Z1?H3NyyY2XlE~h-(CoF+0 zI=lw7+b@Jta{dhe32nR zv@0B8I3nfwJX=!8#5hqu8JMOX5Y2OOVe4RHq3BU=efBf{s=m)ZeQCWq3Szl88MabX<((XaIQx4e_vc!>O~x<)U*g7c+2 zL1X-YQY!{gYoGR*)8+GY`+(yr9 zt@&f$Xkz)eyqM1Vd!c}R-LlKq$0S`YT^%GVrXt0~6Q?jeokzCAW|PVN zZ)RvOF73_KtaNqMCZIf}#$p59Dn_b8&jbDn7RhT{>t;IE4LLJ2WX4VEJ5XJlSQa?d zlQYx#Fy5X9r&o}6Id6?O%Q=FwkzZoW=6bp0NC(ydW%ill=ASPRKdg!GkKf5XiJ$|< zNHYfD+u%Bw?BNY#VED=C$k4+ANmhuW6nB9K#Xul(!QFS&==+Hv;1`j?!^OI8vhiAg zP)B!(UjwRoUmlUPX?bjkLh%W?^{}G(u-9|J$B9E53tP1bb!9vyeG?zrwuAU{xnflX zb&E}*xtG56BOk^__=SU$#6ANoo>63p7|xHw88*VTLP;0GO0Z%rbzwl6fGkTDkhqR{ z6L0;ud`d?l{cUjm-dko0Vtv71zkk#vaF`Ws>~}_FN~U9qHV!ly;3Ls|qCN>C zzm=BpNEZ-=xiaBP&Xyd7OM~lJDG9k5IXV|U#yc(})~XJ@MNlt^fI?M}Cxsv)Z1sBv zUu?7;Lgzs6v32MBzKc|R5RhM};`akenj2j%3)MMq?+&hCWXn2vGmv>aY`Wh*A_k=l z!orM91n)fSu3aua9y}__Sc2~ou_ykm)mX5;EP{~8u8I&ST+H_?O8XV%cPW^u#9=H7tgb_Ec{F}#T(!25Z^j!!hkjLt#CqNdQ4p< zwaMir*%uV}QG}H&htptVTtOv*m&Q*K;23`Wt$b=pXbW9>s6;mnN9GV}+_WEgcj z1NY`sJ>*-Wa^NjWSfHgG=nLboSBPBej0@R8g|ABO;wLGs3jDgEK0QrN$E>~>xD+xC3GKD zRMjT}DxyBPx>Y&F2*nYRvR~rg_WZ0UPFrigNq$FwSc%s~f!R+>D)aADvC^W|peIo% z0IdnJ2atPmn`W3jhpY%-H82*~RE1o>g|FBt%D5uAkI@h@#t!N0k|7K_XmAAI$VIeb9D&-ZR3@Q~?qr}@>5=?&d zGYD6#KBFrlvgdIdoi=t+k)E-Naj>j13s=ne-ehdMt!GcoK%90EFg3S0B`-tL)70au0XV|w^0j5w2_`L`M8#GI z!zR8(wLYbjQTun0_3*(Y-mw7Ae*LW%Uju#L(*Ab>m1c4ch|*FWEqZdvfl`=?hitBo z#wU`=(opOzioBjqhTeAIq z(;)VYn3;zbE3s5oHeEJ5c_cSebn8}{=hJKQN^jT``1~UtvrvH!qA)JL=Q1YKHNgibk0xy z`|Cg!Uw=~c>JzW;^9?7ZMc_v3{n2lpYaYPUeU_6*WCPkR4D&fIZ(B91AChxuE-x>~ z?igAng9>ZSSh0jAAr3{YV|QW3nq(o~>U@M$erF*wJy^^R^f{x9r%*Mn8}}ZK`+O%Q zyC9-m{}n?RxxYVO_e(yk2^n2Js{1Jdv@)9Mcx@6ts-A_?@IzUvl6^&-CJn@INJyj4 zbzjg$HUB^WZpBpmWfp#;kdZa5G7(g*WMxu%3Q07H!K(b^U^+E*j;69A5GcR?LJT6$V&O8W}EkgIfTf&_SH`MlUCrq|`xULX;6Y9?oRl&{?0|RN{P%&ytNK zoEo6Ksj=E;x@+wE8R+U?XUdMi%!gtNbCWYmoKb`~pFMvzd?#BnxrPv2n3^*mL4ZR(Ye#U>>WvsXsz{cvpVXPoY zXG8jBJ3IfXt>q0op74RaBE2N-l1)P1-^I0}=j&n*o^%O-31Do$*}6&kNBuSg+N{w1 z94dh)+b#UI=hjqMZ);aI%%0miTaZN8%u1Vjgd(P#vu=&P(dpVPnYCb*(%Pq#9>@`z za8882%u%nev=X(Bpe+urnxHD%nbh8B1?y^#T6!w(#(q*^wl_ICOXue z8stuBFd>wp_U$ExBTE``Rn><#KQzmHIjILIjm;L>kz*v0vhvlqp0Thqge7yu=9RL{rtSrh+f7O}L)Nry72b$y*NjTf`S$m*Kl zH{~-Uzznd*VgpgCf-Fy|Tu{eqOnH)x5t&1_le0Dnr<4{2e8eHIYdmsPG(i#(9!kp4YBtH5g!K zAqpY83#m`KqMC7P9kT6lmt(ZLgVu^Lg@}XgDzjD(*pdKn=3+AYKt#&7C&0_IA|n0% zkHc|b_*fgo?5JLeAp315*BDxKujY_f-evJr9L5pXEKzLP9uD&9vZ+&W+=l(Q3y%kwg+7wnPVsO1t#z1>1%FRu7nO$MT9HxA$(-CAEu**y zv$nGhAZum%t#}j)Azbb6)Qk73-hed5p_B z6;}RT#_-2U>ld?Ly!n{$iNS(LqG}Y{eA%gvt!b8+D8NSXl2#8GS)BXK(r?H&CK-E% z*wLNnjz06PcHT({6L@@VHHX1Xo^z#tf8L5vk-3Ef1T~lF#6oO*t#f_Wo*K5xJ5@Ad z;cgA$2sfFTX5BF;8suGOAmcN)TuhG+ z+}Up?3nyC2o*-uXstS`;9c?hXP)u206$hmJ^MoNWwBbLLi_n1AWGO{r;NXGU2)2+7 z12xj>pnC4kp?;EalVLdWf5hIsBeR9eov1~(lX(uq;i(p4PUnb$dZ^Mw8U+dVw6YId z;w3>Lb*g}c%&7o$wM19ylgLJo8FXVzDuEY?;SFp|Mbb{8L&&mFB=UB3=>lrS2#F>;n!)JxD;X*!}$F zyC&f>R4y>LMW57C$!SHwXZ^-zXIY0Z@HuG;*cBfyJK65&J<0PZv;?BG0b z^3jK-jg`elfxp^f}R)DJa7 zf7-cl#rHq5Z7bpJ2OT;~9@k!B0_~_#TF*XMp}|$0_*w$H;%v)M1f?*L9JUydjT&=R z@oeHKMhZ=9Pz>^`b`Mflk4@YoS zBMT6-6T3j+qbi)S<&2g8smiw^BCD$l4kgz(ADKqyWy$=JM#ApNOIl@GFc}@GQBAQ% zECNg|5%h1Sl#=soy6sp$u!cP zL*{Tya4p{mJ6fu%w&uB~>e=d>IQJ~@OX;C;P2K06#Q^|n0I5kzea zYK*LCTtI-NK&OFWHzT2A7HtWBJ5#684drqNxw0V2Fp||9r#@r02IB9e1+YmD|N6Ju z?AlH#>^>)N+-TvEt|vRtcy`lpJXHT#yUpBwR$@#xwB`#M1t^1^8AjQz+?f~k>dIggwD$ zSRdN*yqqfqlql2${@q}%RVK`pIc zxsoJ?HooXH=TI!q5q5OJPA=@tZt9BLYQ@aKel`-Gpk2<;yYE?so9hjF_e=M~=lg8- za^{p%O!YpBHeT{d4n*MGc~SBC>Sd5J4pQE|E?S0zdHip$3T97-6k+gSer9qet+*Jg zO28dMke(n*i~MnrepqdGL`kct{e7`HIbMCV5%_n>ew^7>^+W9!zI$2?XxMsB**m~u z9h;`?G+hBXJ;mXN1#O6qEJ}cfL1`dNiV&66ST^kUTIW3I4*5cm(_w{i7U+9<{gv>Z z;XChY(lJtKG=$SAC2qwORsuYf76tfjv?G=sA%dgDOMZ@HHYl=G1*K|^ITQ8y8kZs>frm<9m{B5VpEczW$9Z)a}b)t+AN1FP$d}L8Z zj(2}ZXq}0R?=2)PB+e2nVtY+sGLRNlr-jOgSh$unaB<>RX=Tl3jni7+#JbaUP?)7L zh&u{!#=ALRA1D^F+k_FZ_prOQX<6B4#p7-3b}sY=@A)1q9_7kVP;PI&?A3Gjye-~u zY^%2^&z+97rPvzdgn%M{BakO3i-#CB>cHUJY0R^koDFfPp4Mhj*pbh?a-dom&08z@ zgjZGP8Ag6jc}pl$EFe{`1sn@tqH)J!hG9 zp0#={M`7`0AG+xg(Gd3>Ou0@$vH~P{Z0}>fmwzGkdFdd-NU7bU72dqSfd`Qv)F2X+ zoh{}-;&g}63UMqk`LpXrIE&Nj_SUc(mO8rjdp<``pfOED%d9q=rb!~TMLqji15Du> zmG#n4z<4+}xr|BXPN^9PnhEiZCwH|yK;ahKneEyL*Z74Y3NAVIk8a2sg*5YMyk1E6 zl_e*m3cU4_KZf*_8(+E|k?#`*Fbi)0d zc27(kzuqZeO)gH-o~tlo(+RFvdcPBqzi7;OR?t#JWd+Z%Y3JdYkAtbK7zh{E2Q|~4w@C2;_ayX(*w-m zGTP#L{l4$o#F;8euVMv-Y>!*EBy3KE^pm#^j$f|WIj84!cN3=)SzbQq|CkY!rJt+i zCU$l(aQ~7p&qK(YTGT@G59I_qD*ePQd$=}olXJM#t|h1Er~qguNxuz5z)0>AFiHBWsTe4Yvoy@VOo z2grG>f58Ddrt24XJi~4sZzr3e7+N?yf%Qw(I~3m^8fN8D%Z{JTNK1LoNzBS4l3)gq z<8XDGzx@3iI9|T zQW79PAQ^^`o6fylX1tM-GtA;NjY#JD+m{<+lDhF-1Icm|Gmf@!~CnY_~2oby}ZuJRlQ zf#XRSOR`n-o)Bdh z9aj8@JO;(1h0i3g%0eq3OXIA$ll z$Opn_WHM_(LlJP}wVh>r74N4CD9WutJq1HxQ)`IXa@HVdi$InpM19&+>%~%H%k`F@ zn2;o76<~wx!Y#M^0+R-AP?-i4x*eyJ{ZyO1$^;9gm+FJcW2*0k||wo*#Bs zN#xpQ4#w**VbNa~q)@3S`Tft%~$iCIU-UXK;OJF)zMNrqqV8Mb?s&lo|!qCx3x ziuu>p)O%~-IruJc+cJ>12G0J$l38f;cXsXyp^;(MBdN+ z0k$kNg%nOj`8wcEhXCkG_ANwqvX3SIWj^ImFgX#sV8`-`p^C^t&y@0~UBpz$Cqs;; zpN=Ur;6#UGMNF39qvC1q+ID4>e8GI9X~Y2cgY?E%&1IW&YwKTtH|fPm7O}PYK6wu) zU6npleEGZc z#HhYVtYLEnzbyNRW)a*Gzx=A-!odi*rfHkxYIpHr?4~!Nq>kZ_3I5^mWQ(49aPmt* z_A|Z?L{d6r%guwe@ziUEMD+zz?CNDiHKI1RW?MaBmn}X*#0k0vUKGiehbdFj459ki z&I-?BmWdTco&SiP!0tM5x%;YXD8A8c`M$Hj*RX}M^O)LyKl0R(QGCxZd>Va( zuq1gJ@V26^)Sum4^e++XMr@AT_$&^SVN{P6WdI9qj9wA0>@b*^5OX*&dOE*BJUsOH zoT{jCJ;1YoZ=i)oAClWfbb8KO^6^oU8+DPbqpFGJ9Pe-22?x+6GW%$RPAg|PEao5) zJ~q_C-Pt@=Mwft-uMq0kj3iMcka}VC08)>}(mx~}SokAhn@=CFtOCpSU7k5MWZ;f} zSl_n}$?)?;&1uG!G)MYcr`tsz?JVXTJ{P-l(q01Qa{EwpnzzE@dR^PTI?OIIi_hucaq3<*p-R2JV`g+;#ISrJggK9PanKhYGdcYwZC=$0k}!azCpH zF#5Y%Souo+N|c1ghXudnbePYE%>0}Hq@Y;JYUAv`YCFz%Zd#q1+|6x->6#q?0~r*x z8MeMF0_fJTHnyU!SnOq z%GufnHhDOt+BSGM=Rx_w^{r(lSox@ILk1v>>})&C1>q2B&C{)3UB_QZG=BbXK6e&z zyxk?I9bljAj4n^92a`Fr7Pm9Z*vttaABp3B9yRTbDRG*Fp+5gR^Vj@HSPV5ab@@CU z9HgO_tTavs&u=eC<-8imy90RjhHgtLAnYco*re=qh5Bit&6~yxc#D>aPUVewl`su`}`e!mcHJ3GJr|n|~LO5iBtP z$lXsu3e0dZMdUQWRMp!c;*SFW`t;*peX5{kbtC zZsuuLBUMcEiLP1aGMmkZ{k>DkpaC9yzuC^OhyP@lpvvE~#r3uMZ z&x6ogLv!at&q%E*iwhOgeU&v=tN_r_)21jG4XvHig$#}3R8-3_jFH zDZ&{af9fctI&uZ0lt4%5q(Dh6g!eiUxWFJ$#xaKq5dAyA#`a?(UTeXxN>a%HQj&** znbU?=Qz^hN)uvr2brltOXqQ}!kj`46J@Z;=y8*K$u5GF|`P|!We0blO)ey4@d|#=F zDJt1WJ7)TRbohj4@N@c0mIwsR79pXCI98ur^pD^qUH@9|qTqD7azr0zqDp&QiNk|l z8*|(9cChNDJ3iNVq4r8nTgb2NA}>@gV~!6U&S#WoGI0u?<>m9T;<@>Q&>}TmPIWpT zPw(0)cs~~ke6B4MPI6!Qk7MKI4g3^}iq2(hy$gN#13#)t1ic+#z7P|&)V%9g}>ag(A z6->=BxciEBFzsk%EtH+xrk5-fZV_7azVA|# zG{b`pH(LS(on(uvc!^dPtY5vKql#0$kAzlfh?v=<_DI^~-ncQPZM@+q23_+WNnalU7Tbe8(Rtt_T8=_3@d zG)(*W*XdNt8>z*81G-A%3`_=7Nv?n3o~F&sJ^KkT?U_88OEf4Q?}@vQe?BUakkte5 zttY5kefISlvlNkP@@<`Z3eguIvU#ahF7v!sllVNP=3={j=5DTCqD5}Kk!i2E-Z8Ea zNVL9!?tFPJ*0u6KtL+&Qs6LNhtg0brCKk;AKDaIi&%Em|rC9pJDQCvq|3?Xs&E~xX zq@1ok&^t77nNF-L3YuWUomXJ6T4N>vj?uDAf<`(JcLZ|53E1xlMq_<7>EtiA3iF}* zu@zfm_%K-2$sJ>Z%_{tT_Am!H8w?G+FQts*+W)@cZm7QezWP+bn-#q;`O64PJ6J$9 z6Hye+7P?;7s0cp;0+Z(>Y6Y_%+=2?`GGc0G#zc%jqfltG~%m%I0GAm_x5ynyG2lh+7;= zrld48)V}fcYYVP$B(Ag0WLK3aJ`UEO^g5<(DY`ETcI(&Q^xQZ$M}hn3FH3~pk4~^s z@BL?Zs52kY;c|EUES9{olpE?!<9Hs8Z%5N7bS*RHpG2)J=Xo-oVgPv+!?s>|1?N(; zl#(8ChhripPcpMT+(<~&P`c`YY!UKyZK;Kolf2-v zr7E$-MX(M*{%eC#O@sSNf8f=B<*m^36Z6~F+1;P0gzX`je=LJS)`BALCqF!o%GBYl zy_dCNDxfX7P3MJU~pXo40`D|w;sv?-F7L!|y$o;#q~-J-6+9=UUL zy;>)!JmoN4w7xuTQJ*m2gZSmCY15|Bf?QQFJ(Ocy9?x$S=ae5Fac0f24JD^#5?xmf z8Z0``Va!RPpL*fNe`+-OYLb}Kd1p4|V{!0K=su3&u zT%g;);x7xsZH)!WcbqubL=kTPOld{!$MN5K|E9%E+lX6BG_z{t0*Au(* z#^Ubk2yWQk0&%~)cg`bg%$2F2iL7&XyC>UM;I7zG6>0)-fg!%%o}lK0DYrp-oMCnTQT9xX-3gapiwFBMgL2ayi-Y=ZO$fm`OyM!p*tG-cbjMG zR}bQC->-Cl>4;`DRIoT~kUp{wLvMjDh@S~WlHur@jte;FqtS!E6c;{wGCh_wF0gG#q`ql~k0s$ZVL8bK5b@7y}(aKcO zs@THLJvZCTu?{4c{_KRr1-pum7ILOZd>!%YI6li99D{DwM?8Z}SkFyx z7abhO`F(QU9C%=B`05(C&0HE54nEtbCy)@DiHkIwiZ=6gn%eSPV2JI$xqSNwP*A{L z4fG89$$*zNY}&?@=3WUKi?5CWT?6hNh&i1<=?y~^x>FTWCmM;xCmB_OCu1x4Q!!CC zKs5we6Vxb72^Tl5j#{BqksVsDB?uq)amqviilkV#w7!+QrXV(IF@`4*`E3_#wc+$s z3q`Um1z*FqAg>YVnCJmj8fIw{gF1t#mPPz){M0W0cqVL2acub=aM*8lZ43YtLq0e# zZj3@CTR$8OMP1F!DA7?^bGtA8)j#$*sg%;CYEfNp{InK-z@FHB-H^O@+g!z=&7-hu z=X&z^&5okU8m^@oyPL2027l2=%5{)km#E;a0P2{~*Ewf3sQAL;V3so$liJ|+SYo(E zo?{Q#qh|39D%m3zXt}w38;8@shY*0eEz(P-=!>B+`Skpc&ewyHk<-*_gH9j!0AsB1 zykFyWfjuk7HMAMkH@067E?@4t=jqmdyf6KR*XFI6JsOw?bJ~Ur=Avh2Mn=Yw-y9I& zY&q6fG7BlVF(=ZSz=M`p$|cD@-3YC2WvXi=8+L& z>WY;c7R?;hxa-)54qFMq7(FF$G zH<4ioz|qD1Rkb9_oTx_Tw4Y1pBG*bDD_{o(SxOZeOZS2vouYL1X&&SEPPk_ZV9+e%D7XiPm33j{laQ+LJ(1F@jHz-TFjU#zs;{y z0n^PeiSV3nV}Ymwk`$eEH}3DqNLjPn#vUHg&_lz>#)LbC%)wq&kYe)(-SZCLqi2un zJD0-S)$}KPd~ma8!6^ny?D#;O`jTrDL%wuB{y_BUpa00uPjVIf6U%?JAI5@nUN_qU z_N)C~^iBr8yCbCX29$@{)cn06p8XSF(fKc-JIpRUbdDFrI}q0jO|JU zC(gDF+Xl{j{yY9>O(!qiT&(t76+fSvE%-oD7rp8>e_ncDJt$}CHz=UCDV02oCKl2r zDY2oJXV0|6>mt?F0eVptQPg|{Bqc0q~Tb>1dD^D)<@G3WJW&P93$XoO0vz3VYK&q?PaS$ zp=O9g5a^#PE)JPBNJwe3lFMtEigsqxi5`hxZ&0a`V8G4eZR+maY4A}*89N&th(1xj z1&QSyJ8+9jL(!Ys8OfvmK7s|u{K@WvP0()jL{rePu-!06Eh{)UAb6_Ee6iX~NDO2k zs8w|=_;L5M*1bv57M$aF%ilns{70CP6jt(BJv=@DFa_h^ado z=b-KES?Y9Vxl!^!x~vCu@)vc6Pwy1yk?F(?cah@Oq{s~2QJl|UtR6jx20QM{B zDQav^obN=5LF(>}PM`h!_k!8KQlUmE@UR`wJGqPVc-D;@W=p?(Fj_oq1nI=g>!xZr zcGMc+QS)cr2aR;NO2KJkA|vCk^3KSwzYIT#3%wU;ItDx%HV8d3zb}_-IvVhQndXVj z4DD+(@M^7D%&O`W#<9C2(r@m!vhLt~)e~|h$}aaM*VFm+CH9UEu8&2hI-i9#m}k@O zZNB-fC}*Q$wsFW>gr^58r!e#k0_gr^D$x&}023Q5jk}yQPgjSITT3SyY{r4AhRwHp zoAEB>>q*Qo9w=6Af)%rZ|D0DdPCN#wr zcxz`l$$yiPJ?n4b+wJBa;CgU-%Rf8&Dz7Az^X9=j)4Zi5rwBe!QFKmQk87RPD@HEw zZ1|kxjHjU6cn!tO)FxTIbM1KR$$$fljCS;Uy+-yuCCDjV%z1sPaur!;n>YV$(pgYs zLT;J12j$u`SD{AWg_gWgb(VKw?TOSdmDqh&?wFQ}ik0B_HsRU1D|$A?B;Rd>XW;j+ z7QtZk``xPEHyf2wClRaOtf*4~z280@P*{scqt>I$=O z!<)s2?{in)<#&+1`TQ+#{fYmu?FGZwd$lenl{Ye(w@~Nu>VLfeZAAuIH+i7zd}Z~R zT2D1;D(w`NQ%qo@AN$);w{~*GkIsiX$4559H+Mrub$5;I4gOYj*$Unt33g*6f~P(4 z`zB}YOers4bDtXx%$exR>84yUc=&n0mYm!sSNqLBAnjfKoP&eVkUY7ioBLQ$DQLy< zQu4OgbSS(4w*E2{h1}q`*D!6jx%PE>*`90C@NDS<%TToDL7t;aO)o{eGg7KM`sl)) zvfOtlV}s@OwE1PBU1Co+;6}gx{s($6+x=83v2}+d!3ivT`p7`jM3&6!;**kGXLRW2 zL)XpEO?!zX>CNmZX?3l0mpgoB zB7UGlEEzzN+?5XJrv{I)HPZe11tJbtxr@08t7(7xu6_PYTT8I_qx&U>dE@a!)Bn*@ z=swNk(0kfE8HS=z*7Db3JR$1dSkInRrVPIqGpvT;Ll=f zIqqH|$mEhV@G3^>ncDNY>s|Q5C#`#z&weV{o$uX#(UZ_fk5U~GyKycxBtVYCq<;LLGHV@HE&T-I1gE6rw`uMLmG5>G&a6w2Eok^~C{qhpA zv$lz7eV!f1$VoKYFfkaxh{P>MJ89nE3H~y6-(BoOMV6&itgofUx4DjRR)aSfXTt}k zyslL4{p*>Qhy7Ja@|pub5azpq2)kMzJr@- zK+`C+xmu4^%7VOu(!la%^OJ;w_XZ!5;23My8-zWX`%0G#|Jcc?s*)s=#GGVmRklKI zzIxf*R>l<0@Y&qKwLi7#9&GA zC*S#SVZbxZ$biA*Xv#P(XEd7uYoNDbTz+}wYGz$lWkca{hWlph^-EpZ^SP+DXGWLV z^_*Fp5XJ*)PvX)(1gEOMjfnmY^H|;V2mY?7i}u~!U6??k2=Ge!_EM+seflJxG|?6A zz3J{;+4tDXjy4TQh#+@@OZ1=ddSIOM7L;K~&=`gL3SN1+?=fY# zjR~)!k-Y5T--M+qNlmrQw6MTCW;6Ym3%=Bt%(rU-;%<3FPYYl&puTFr2}(wE+6s%B z5W)D80}?spdF>wa^P#R3d^gP4_D&8qbA#lKp2g0bVQRN)<1vAD-fQ_p{dB%!mg?hzq9d6s*4qS_jVyH+oeF#o6e$XiogP)>#hB~t$fzM4<|tqP@YCP(m)*sj zG`eAowdfZ-kP9WxOlmG0P-m@}rrt)~91%n4{`*)M=YQR%>u0Y>@0a4yJP{b(L`C4D zSJjd0H^(XZHrlG8?g^*q68LO&4v&>4ty=cM7>B8WH?R78)RQ@Bp7u*io38$rbF=9f z&lFGO?6EPyekXri$~c6OoLY{UTAQ5RYhSH0&qGM5DDqpYA{nE`_b7NUJ-dNl1CI_{ zsjli>Ft)wPc2i%XD8$CN^FoXd4Rm}<}d4#ZVj9{moi|;dy*ddK)tCGk1ib?$Q&HPs%2ne?~`ljXWW}J*J z5lozqmGtadA_GqvwEeJ)IV>W+Rm81ko$8b2=u=Yt}myMfr;0+n4*2Np_ap zWw!(LQH$UETDzKw+l3xMp2~*X7QCa=W*fXSJDkRy|+t9K6WM4D2C%4wU?K zWk0@aZ;P@^2?Pp7H{X|wWakp)E|<|HU|C%9LEPxD~b!LaAJ zB2ul8%hsi3giVI^=AQrE&IfsZTNy;Z<=rWXdmfi7!-wr7`tyP@M^{2^L?Sb?Wv;OA zN$Ii2(cb#R0K@CT+=*pKeE;kcU%VE(4fIINDAu{jC*6u@Hsr8O54}B|yB{KHd;$OK z*DtgYCCDH_@^#04o?uatNLcs7;?7qh&Zo#V`?t0hh!FZ)cR(PiK?(gVlTkuUq;BEX446lTMuL%Z-yfStYNAWqZkJ)Nnn$e0#+^|!Ku~F}k2Z9Z$?9g74HCW3y>^(n7FEaiPbrHw5|Qc?TH36T z66=rdxqlP<59496j{t+jS-4nZrUpupTWBK#nu12OREbn?wH`Aauv&uiiJF_ma5%}H97jc<&Iu|{!+oe3l7WnIH)nmHJ z_=O};Cz zPWE9*Q&p^jRfDGK?CRsIlX_F$;YVLoBdV*IQ=GKVygYTj@HFo8@b<%(N@w(bvBD&F79Wp2U zqoqdNmTYve1&kK;H;pp1?nQ1 z?8X?=1(1c9sYhsZ_d|f9YFaHm(8*gcjR7?Zdv$D8C@v>WLh{t78qK0iA6A#903J$u ziSgPpSGOtn(Y(RQZsT63!|y-Y?Ny|6!&Y4)L`0{|;?Z!ua%Fr`~Md0xIJ)~lX?U^1e=NQa6ItvLDTp}N+gPr|7r6#n!ex{hPkOyQhMJBLZQX0&=6Z(JFM$n; zC?C)Ec2&NnP74+ex+wPS>xu>X%{xi!E<)ZnZ0kU+V0I6nf!491OT$G~gjw;pZf8LiD8rGh{fa(rWycmA8KlRbyx_a=KXEaC2e z&bzL>UJPf9tgON}RhI7pacKIq&eucn8cJ$CYFSoTtz3Pxh%-{|im4A7f~I z$7kfllisK#+9?4*;q$+o^fU0ZD+K@SA{`hRy}i{&x(IU0!PUF4BYz77&|yl2@QD;@ zYw_E5EaquOiZxB(JKsOZ)tD^qnagfVio$sw88^FaZJtaw+-3erX#`FDi0T$E7iqL_ z8$SM}FWOSQVa;;g;2x`@dRG`t`mkg1NmZ`5Yj+HAP}wVhf7>x&GhDy{{4$jrK?OP!lr}%U~ZvJlQ?mxzye>? z&`|G6(v0JuS3T`Lu+|nULZy#n@^7>`I-yD0qOgd#3wy%Tsi&_sgB++g+ej~M$wA)a z?{)sn4ceg5M&4p(>Vm&{gzrZg-f}|G@L#176l#1EL~Lp~BXJ9 zN^G)4bB|l(07?7Ym`TD!85>%l%xJCNlq#Ia+@X$B$gyWo6tYFZ<0P}?2>;Af{E^k zmF;8<_ZVo$=Y+`Xq7x_mUHZ^zd32cnHoFimIb=bm0#z__&db z>|-0HTbl>`Q%M}zyP>sE4_U#G*@)|GUoVSyP=KmCK1}ZmC6*2TM*~6uzo%+os@0`C z?Detx1ucZOSUTqS#0_4Hd)vPigZI%^e!uRp(}(t2@lWM-3tUwA98`zlHHb~)3nlwP zcM5B|TPxLt&DQ&Nv?Dc!P>|?AT`4M3;{f{h{1itMU(3hSDN3VXl%)FpF#uoB&t$VG-_q59C#`+ibHueEa(ZW@cQ&Zi%^;hGZ zD_}A&D`r8&@u(NKt7LzFEIZPR79<*r(l|!;4EQ6Ln}hUX%XS%o%i2J-_2NhDzyHlw z@OwuU(v=YT@UU$-IW3;>v%X?XAjBP*OpeQ=UeL*)!Hu~?oQSOd2hB$}I3`YYY9T^@ zm+t*sCguqI@|d1g7}3NE62*mQIDH{kUvqUL1@X??dao>qPJqPo#^X0*?E+(OHY){cX%(V3M z(mYAkWrtHJQ4EL50+mYO)wI>kQ!PDCDCKsBC=z)4%CX5WSIUrNpmbMvzu3BZV(xGoEQMJcFF;-MVoR$XBImN%i=VvaNRL+{W5usi|L|70J zC>X;I{4v{F{(Io`(&Rn-)_qj=myod=fIDNc;;OEX89I)y7ylF$wHe?|A+;4DTe;DF zCKo)QuPpjD?j;nkd}y0wIHw1Hqu}(A^W=$A%@wb2?Yd4=I%B>ywvz)P6jHP(3U8%_ z&EX$nK;cLk=O5e_%^fQ>fWtB|MSj%_2qpaD@ob#)i*YV3Dvoi~lxBZ32_aCc!OMO=s^-*WO5u-`88U6@C6_gbq@L#Cr8%ue?D zy9XEt>Hz(s>mhE=l}gdy3uO{7AXns>ksgB?y4n!_&Q%RuyNL7s(#;1xM*1SRrmMH* zBxSzhYS8!Sr6@#a9VYFAJbvnK>_yC+e`aK*D119j1u`hGmz}KZ;-err5|l z!U%$k@??iY!Dn~MN_D=*4u`2E>H5POsLNd*U4{yDV#5rX7$FU=5k#S`L4i0xjKtkCRZq{pd&K zr@`T=(fOW30sBF6A&-Rdr}Rd&%Y)`HWgR5{_N%fNKs?WQ?ZuIK03jkJV}~G1s$#l_ zWd9L!iwKTd8u4{^;Jzgl(trtcIMKizJ0~|&i=O*UPBa%M)u~=$93IYA6r?kD<{&Gr za=Q6LNRYNl<#-t1zBT+2RO;Rtg*|>tEzj;{2oR^3QG4kRVWC04cji2(rPlp4MI8|l zPtKX6_OD&TNmX<&h1K$~)#(dk8>*s@V8{0eq~C|ZiR1ZPV^#^=r|wSKK^Xy7-eeWF}|iPcI{}?wM`M) z#{cq%l+(#8)glUGQh6xihnE!YWgyAKbeYZfJUcNjGjOK|VocfpRQz9%xB7b1adk-C zU;A&x0O6!CJJ|KU;q=i|8$p5gB|~oA<>gUXs-7Y2bRjIwCs1+Uv?>gRp9XgxLfaHZs1=h5;SA; zgNjZt&mo7idOdGak-cbg;$Z2u-MdGn%&$-=aa`<2u2Ri@ds+@*iCu38Z$4EsLods0 zPS`b5jsAWh_}jjTH{|dNYF$omLBwO`v2#SxhQZMS&A@p&XE7k|`s7XN?@JRfsu@w( z13xW>C`L*M?*N#m0L`7MqhjJNwast6tHu~z-_BNTg4#483!L>bTlZRfcs@f2asndI zdpPr>{_&n5u60;OF*p~T&bFbMtGMDi$`5IS&`nl}1VqSN)>?kz%Wcl~6M!cfGBhqi z=M^fdp))dXJ-_q!BFwB4X*i2QHXP!-LB^UL>gtP>vcEpV#3)Ye+*M$pR+ojC`~MMn z3x#DIwo()XApYpvSyUIfUY~XVz>0;DFuIC&Ou>)D2RN8$D~@Zk` zc^TJTUPX4#o{wqg?91&Wl^E{S9*^gy3D22I5J|7!>KD5fu3hp_t9oA1zFUnO&7!YU zpp)8g^rBSkrxXa@dw)7}i`X60nX`gY6~u)x zJL3962)^sQfybWG?W%1xaDF$uDhb}({7d`q!(>v6?Qvm+9?ps;Xo$|7XlwGI_Y>~t z;)WS&j+g4{qLIv8-SfBJCPTDR0zs%lo?XHzQm(q+`g}3uEUUq#N0B8erV8a{^ODSd9V3|k9X8%&r zx&;Ktg&;x8TTyb-r&cAT%jV$~i47k9MBZe$u(>H+fiR0`GpNWrILvE9a@3r#8$!rB zQ3FCB73VwWoAn%?hN5VPaEmQ2=2fh+ zPX4v1>C)P%HM3;)bX|cW^LjWcElRPh-m{44qpRCKKf}icGJdA0K-xKxtF`#h@{6P7 z(-nE22dJx{2Iuo;?*Cklgm;pr)BT_2Z~2K!6+fH3CGF-e-5qQlS@>0kJA8wkID6LBEm6N2~<~oybCqlt-!m zh%i*_wpG<(*{bG{3x2w zG(*;f63-?|nw!>>dFRn}J}cYNlV$g^2@J~PPt9%~vitaP8Zw@}-)pBX5(}t5>e1i$ zaz+)dZdOJel2$;DVuuc8D+&uTiCWLzp(T^sveE6t4*WTFg2Gj{&X+1CZ}&%bDqRDo*8zDU z2m$7!e04N(sR2H+cPOi(g$J&d+zMDxY#NM_CirEA_wSeY2bd$lUGgF(!t_$Fll+RW zETFlKY+no%UPYv#Zp2(|&4UNtFkWo&#TAe&9))NETj7&S>Hk~B_mWK?-7hLCXLuS8 zt|T|uQTnG+e;Z$0({g7 z&GrXoicPy18@RyE>zOdm=H(1yA96A;{^)245m+|+^$aSZIJ4cCL)ZuG+1$a`pSUjh z@g>nz90gQ3%am{~CsMIH+AaCzR1ODgw@AIzC#Oaco;nxRpf>X}&uKz_`Y_2&!8^G# z{YBZmB881ZJ+lq+ANN^C@_QzIeERI2Fa1hLiL2Vu7}aDYjamiEW;);4zH2?Px_IHC zX;vb_-_%sjb#(nDmMF$Uh#qXWA@9NCIGOtRAA3TF|C*jfA`rD35cf?>S7dPC`uVfl zL+W3Tv!AuntZy2bZ%aw)uj@{^TxDNC+xc~99+nH7e6ZmR*r7Sk2bAWXfh>{qJk)|? zv`X^Uo@pjAKAsX{FL>M5Z>!>GA-|WT%(fDBHo?J+QXjf~EX^O%%%mGZ_ClCeM=Ngr zG2-&3f1_r@?GmSBjEicESh@Y?S8maj-AYr_7WA-(@v`4J63FdNhe7ckE0fL)rHyA3 zUqK4lQL3C;8RDq>iPDKCXl?(^3|!)e@OF~5aaIe8x^8_}RA+Efuj_+D$mrR~v3Cq_ z?A5Ow4)~d2`^Oq9&6!tcVNF?ZlQXHAj)}_s7bPkT9d+MgQlCqtbsVV~Y~o$y{>Wua zZi*R^bUL&;B3ckvOm+n?VCgWF-j0});@JB88N7mZaaItm_G)J^4^zuMGKP+t`t1^C8 zzy~r~9JM`lg$j4t^P%svJ72%ZrmgpBrC=4w)lcLoFNW_UdDaT|kcuuc+h5J;&Q{0b z-w;^q2s>;d&3)>ApO92Zrp313ZtGi~XiIp{#n(?q`M$Df5ba_8mGK!E>Jd8Wj`+EM zKF}6Kd>F95Rx~U{81UP@m5{~-0MOQq)ew1GnrFF)IqdMNlTObP7PCRb)YpgB=9KBA zsJ2xm?HIyjhinBqAKW!4)V@LYiDSdUVo-zYKuCgmP>wi!B6m2p{eGDn@@`dVvjaUz z2kLEiaWbBSawjoM6~pjS&9D6Mu)26+>a*wVZ;U-woLviCrvkbrkpyBeX{WM16SmM) z1H%myd`YM!3+JFYmDT#ZVC-4{YrCyStZzs?<0{F-%z|Fy1e1`CQ5hHSJ2#(@|Iziy zsA2nb{5^&J!8IqnAlo1rP779>aqS>Qh#+^%LWZZXjPdkB2eYjM!i8S-n2b+520Enh zs`rV)@Uf*jf7&s+FqpVtR>wfuLL8KryU*h?8NE7>*d>t{nS)l1B;bw-{@dnYF z^f`9VP-)=Hfm(yClnfm2Xn+0)_RpvFVH5#c7xZf|I3Q?&?tJq6kymwTrfdCXGwXYPV*D`w5Bhafl^^YLty@A?zy}j0M`(c)I`6Zx?Z>PEx_=K)3w|Ji z$IQl%R(v6~o(w3KBoT4LR6o6y^SPqhs97KUDx1tGab zRC68RSj)bW^UEMs*VFB^rO}vo4YsawADGN{R$q6~$lcM(W$R-nR8x$f7B?47=MHbl zk8*7-AD!kjJ8$aWCvr*6nB%jRp!=^wwwtl}j^4Ckc_+KcX(3&e3q+p%&F&hnxX6zh zYKY@ZHtVMWvU_bSnazeWuzQVe_{9eq=A=N4ziV&&X4t-uzf-eoB(wK|Ug_c-Cg_q8 z8Aw4v1MlU0?Z)$1PDuVmLF*{3-Rg@2+ByD$oJu^##}=w_y+~O$jb6RXnj)hjRP7rp zaZiqQ^i!OcMoE=g9@&Iy!QftMILbZi|lKC-mqWJZ;Tm5de<8f+?$ zDp-@I3id|q{n|GC_13H+NQckW18llbSnC0jixu){LiDuSOy9CDH`&&Bq-yHJN!TvI zHO+sx7>j$jF8OKnarL+_X&TeK4gILhgyH^I45(U_cos0I)=%Rvuz2(ux_?x#5Q8iO ze3IXznnKTIuZ0fU6>JW(Vr3(F9c?2@iV~`-pLuCa zCLUk-Q7K`(yEe0TWi&q68>u-1KlitqkI`{BD;s7i8s6o^d~m2Id~~qI5~ulm=JJwq z(Q5gU1>C}(aIyE-UPXx$8kKxJJdTHjv(Ea32dC<=1c{-i;ti(w*M6A^0>Ti1V&;1| zoP>KN{>SZX-FqAY}*rrfEZ7V!quxZID0dC^W$7| zBMrr0<0Y-Qg|Q3XxIHt~>8}R`Pb2U4l}j7>jkFw1T~Su1q@4SFY9z=j=gK*xpgtUh z*87ae^D?$0Eo0#r9Ff+bVr|%K)bdu*Mg@ zpf-9aTE;mFb)+n!LyLM9?JEr9&MTV@nX6mL48Wrrd-EuQoVto~Fh#t`wc>;fq^sh>q zcV0hpHdxoKFCM6~-&EmSxz-`2RmAoErNxYy?_3>H_WX!-P�QP{1ho7G3z|a#Bg& z6?{d+--vJZC6o@R;81x*_zol+*9N|vCSoVdwqd+*{-V~ z9N1y_quA^38C0K=={)l&4OY`eQjeZfMz0Ii-*%jfSvWPCSwH&ONK_#EUUfFr0CIpW zR)RD2?o#y%y;-d=dHqq0FxBY8p2l|b=FMBTB?%l#QJm=cp!yLDEMui``bc!VsIw;C zuK|qk4$3{L_O`Cc^KqWQwC_Yw&(02GtE+B{@@q73pjH*6_>}g|bUU*1)1J4?%1Oxh z?W`ePX6tYC_WB8A-_>=0p=SfPx%=i(Q_aH-w?7_yDBn{6L?ZD!o5d98h+rHl{}H`v z5`2vY{mn+p$`DdV@91F24y)(*T#MOuk5d~v7)BvxL8MJrQXU1}`Etqma+ozV4|Bw; zgA89*K6;saBt6(fgo%y0Cx#t)SACFt!8$5QZNo9t&zp+EviAj*lGdivHD&w)0}Dsl z#HFR(@b}YFaqj$)_p!mKgd*#ZA8uhrZIpIxx;EIOn*ByctoCZ<+G(QZdQim?SFzn} zEgZ#?OYPIfJCr$cU+kU^tc~ZQco7sm+d!Y*69>VD`=wazVBUVCSpUr`>fZ`6`qKeG06tM9ehvWU^I>lh*PaI^q9 z&xr8zJjsy9ADN#y>yIcDMyR=r+)9`)k$2y0RmsCd878l26?(7)nE3!c zN9@&yzfC2VJc<*bZ@DE<;O^Hqe3F!@>G1T+kDdXH(2w@@5LKJG=x zzdBJ+q^&K{1;BX*@rae+Uv+TnJ{8XLbLUTnOsB)9bpKdsDEOTu#UmhjJsH_b=_b-y z1*RPdgRq;K3X~A6uCR-;z6ym zJUv>g@ug<^*Ue$O5jLu=nFb$!|7=0}4_yzQ_V?qR^)!Z;TM{y+|M|mN^##C6*#X7< z1ZmI(>ayJtPGRtK`=Q^%p=So<+EdmYhE9jNTJPL)vzHx@6Dbg>5>-nWkvmh)Vtmg% zw!OV=*y76W_ddo!Yp>r)(nGaK$15V~@`Lgz%R+Ro5Z4Ukx?0qbBR|GcTuLhLZu>QV zKiNW{5TK!ESuWpTRprU7UVyfYDtg2o%b#zbfZJQwav*6;!u^}l^VT0bI~<_KEB8sF zBx^P4JG$xnvUz4DYmd5(!`%pri(5?%kV}TiNyw+X4ta*jD7#BT9pckbWi)>n165xI zIQz|5nM~B%So0k8NF5JrDqK-3tL~Fuzh$hJ!s*vjo@w&d2^pXlOAJ?ci7C_jeqQuJ ze8Tz)i2mUft02tkd6aXfI z6jnZAY9vDSBFf60YPotY-3Z-;d3XpBNx;!^>d6Kc1%+xrIR(?~zN==#T~w&mEN+y& z5Ysi>GQyxqX0h%o$BWy@V6|QCx^<|2Ko2UFa`RKfo{QW1fLIXY>~YT}OU7;_Y3pzit!|0M*0o%z1Wz&Uav{>9RJ&5%HEBKGb%19`6vVk*BWc^$otGo2p znIG74MNfTA^!R;l>H_a*pUj#P^ZK^I>3Qt=0Jr zF5XFHVcxzi7Yv*#XJ~SeoIG z$oS9x7iy}2ryo=9OUMx}j^gV;#}t%B^n6+44*e!U1rnVMI?1n#I)W?X&Sv@%d%++# z8>r;e5ct8_qiSt*r!AJ}n`2uANqew?A2sG%e$k;V)!795^lpif*a)01D$MFHEWyI( zy(GoK)%Q9Z7nN>=Ras!kONEoCMiDBL=AknLZlnTKF9P@l3w)nL%?p1(<^EZ|y6*c^@R5>!kQnT~|IViMa%otEcD{ie0>%FXKT+4`lAtQht zRGO2Z8~qhM*~;lyZ~j9s&%@bRYd*@jFS@wkZ2=L=xc;Lb&1uQ_8txhKdWX0E6TJOL z#7}h*2lGW=8EOC@0F2tl=xWdja0r3CtlevRU><+j`}3?7a|h643P6tq+Yf;_AOIp| z7+dJzv^x8{>j6JvjR)vF`R$(gzfS~U0Yw(bzYGA+3U2|r*#*GinqO*k8kNqIwJzUD z{x87{JobtJUhVsf>cEZ>{*v>1UjEm>1Hk36)YodIO1F16@Aba|(tk~2lnNEF`~8F8 z<9D2k!kg|7V8h~KL-QD!Lc#w?Z}qoXcL9YS08`IcCUtV^K=ibJzarb$u6sXPX-Ks_ z$_8rq*c04=idLW%q=UeE<3&Q_tf1W4+?-mxs||C@3t zoz4dY!UAA=O8NH+K!9lz->l`9DH@oT4XU^EPYKs|Wqv$gos$iq?{ zfSDC{#ot71NLKgBF*%yGK_YsoyD-P)tAON1t=JoqAKxG&3CB@h+K(j118GTCI z^T<9)?UjK_aZm^H_z>Z`cQZow27%7Z<6r7gIGGe$xxa#wiZ(*F&fN8gHtnbfZot}O znxN1)F$T_CGnJ@46qVy?T2KD!Ly(hnPQ(8+40s{lpuC!{Z4=<+<2-pN|Mvz<;;(7y z6T6R?w1-{}yT}WGRIul%|8KC0MLHHtz%3*5&Wl$?7SKXK23lj(om*NEJ*N%yHrjcG zAcCuxABC@hEaa&?ccK4dYV1m+Xbw0E>ogf1$BrP&E z|3?G)*yB9#7jUK#Jrjo#E#1E^*NT`wva`rb_v~;#=lD?4(DX;Vpn`iq5x19|kcV|_ zx8ZbLUloM5qtJ{CJm}4eK4oxMh>>|%esM$;H!bbZP)Op1L5N7VkiOn)X&y^2ON@lx zpF3B&<+dMhE2eC&3Z>|LFj)sTnPQFvk~5Euh*rYWi5h28kP$c-$b13ANe~D)(`&sJ z(Cv?k0>aC>&ptl*k$xW9?q0{7E>q%3%vzqpa%PIbLL5jbgFn#5{2nZP`_`N}4tLj< zl3C`RB=;mtWF=276y>Jc*30PFkUQ;&q7r#|6rN==u+L}EC6<3|w9A!P{pa4+82?8p ziqL|uw=WzpHqecUi0;O~sTYtr*BpWZ+wk}PEj$B>Vl!rXpf0RI%zvmG^Zo)Zd#HYq z8$28%K6Hm2%>6#KaqJzYQ(}Evbfw`I44n5U9kcR-&#-e|@HxUkd2~}npysXM+*?a} zF)#_QE3A&brjSFtF0Tv2)b%_c!97r%vI9B$k`>R1PiXhQm3PrdWQ;Sn#2!UJv0Vy} z8`jqG-jE3vEj4}f?*rLUv91M?kugu({Z{bXaSzzREJ_4rw060=g3TjldPPRdJ^mOd zCOKfiAk3yh-za8x=e-YC1VCUr(-g>RtCmkJjn4@~P{k666xvyU@7tn;tC~(q% zsuKnlE7TR%5zlUfc;@*~miqN8t&FCR|2k*7f&d5qVIJfp0Iba=sA%b!XH$dE#nJey z_a&pQ_ov5zbri)T5or9gBEO+F9?AS2P!3iI%GLu?+6{mt0j0Zvydl(AhiCoCv1WNRHSJ64!BTEd$)I>ZQFhP;YJ ze}$_s@X+q3M6R8fJfnxu*>Y-`K1O9z*hXEz6}B?5;bBRTnvtW+jg~i$KI}A#?QhR3 z^OWXyGV{Q$qu<$#&&`EJwp*kaMv!e>yo>l#i3Li@bK1jgXhV?rohd> zLk(B|g{pPKOG5!L47^C!d;5B?FWz+dK9jp(st??552GjnmkM%tpDwCy1)flVZynO`|E}%-L-%drMS#3k9+>U zZtkE5E!Vu2E=&z3lJg+GuJc4+Lu~6PiZpCezg~-&L9&(h9sJP$Y7JBgENqWrDtn3} zV*FBYJh)l`zCP~0Ms%9OEx8Mm@(>k$E1wKw`18%RHIMBQ!G71n>AL#jAGz|Nl6mZ4-D$>(M+xMq~fEip$V4e~Q z*#h#6LbUGe82fBnGkwsfwU@v0u6`TP5qZ=`-B)m2nXZ)Ir1o7-00WaD~4f%16`_E>ADP4*yA+K zww2AX(#J*d7!78zl63}gu(OD$Q5a&X&d2-gI4m;pSYExO-;zqUs+nw3W%?;3icavM zg2|%)xhno#c&98h0?k2(OU`Ns|VrUmgal(+p?pSsUi%AIes3?@jd+UZf3oX(8c z#L=~Fd`>gBc$lOF<1t-46C-U6xE?#w;KY=6vs!Luj~}K@>cEscj@ozg96pKO?qJL8 z4&i6Ko2^k2jQFX&28qjtGWMg(@eyCgdp40-LHI;vb8jb3BvPwtuWs283gy@8uI7P4 zZiMWoge)8(!Ix$DO$Zx{fcgqtSCnxMtekKtNIGyfF!bR5QNFlXJkAx#JZztuQKww~+=;$9E_9?1fi!+n-T!&o`zS=A&1ZtU}I8&bww*9t&3Z zHyva;1dfSlb*!+n!zF3m!MchYBpG<-3DOg_B?UXr%heKl+Ej?o0?Iqv4N0t=mWo=$ zT3XI~`HzZqt~SvP@vdC^%2_{Ou@DLqMCMs?Lt)Zp>b%i#Nrt!~yem)~8JQv%BU0^k z+sQ}RWZ>;%0Hm^6(v;J@J?EO`xshEI@$+*3bY${Gc{cp&Zr;%SG~Ag1J+;=btx=l`y2(WK+P<^VMuzFGoN`lD?X*v=voX@C3P_Ue#8$Wb2~ z&!EssyZWIZSO;kS$>yiR^_lDG`uNIbGMtVUj#)>UJw2=I>OZUBy7X6<_ zO)Rs=Ii5Z)6PKlfEWbSxF5+ev^gijgp_-AZVCEaq4{Y{a!CW!-oqIjlvad{PV{7uB zj(N_&_a@(geW*^M$k0M6Y1@12GJ^o#^3wGjC^vLXSHm*VsorYTt#9VtUV0u{BPKF( z{K*$5@wPq@yYLkjgxKh&rv#lAL_g%j1EZjE|9IoM!tvQttwq=c5u-gm#P#aJM<$nS zZtQ-GdY<1NKs&n8(3*E6q;SxQcWvFm1P{Z_7Bcm>@M%m+OlR&UY*r&UgWex|2^47> zYP++uv_0vtM{Jcil8jzJYO2#tYg?hN8d-(X$n@qZ$@4kaljT0?K%fCPRABA;z~MyA zS-n@K+d=P9jRh*V{w~j;l2Mz31aZ?~UZ(s?;sAm+>AwW>)jP20{nXo@X_!oOv}f}y zK@I=}_yvEN2w40|iEuDwEh)CW@k$rcz3W1$AXU6P5{%#bwm5M6CrdK96Zd__e9dGg z=f+Sxo=kY*1^#j0RFD1sqK;-TUMIxY-~YqPxV?F{VWePZzGy!gJ}Kd4MDWtCbOs8+ zFdEGy=W(hSaWwama7UNR6DcRAUBJ_^?@%_^J6xJ(aVhG!{ol0X`}MQ=2ZN+TBr-%J z$wEDOxAB8rPyXT5;#u@9AAWLu=!|j&vt=?6WJ6{JABQKd5T>R2%BO6F9-PS1A^DXW z)cwq*c$#=F64m=&N5q>Qtda|C9%UNrji2gVIPjw&jkBHa5lKb*{e@-1qAnDf=oYai z79Z2~O0S^+CaYLRVZz0wPa(v;jgct$O}3L4SJv7ne zXgCT_j3_qunO9U$eP7z1QoZ(m9fE%@7V~mPgzLXYLE(Z+q!}aowp{ zAAWkKz7Al`T2dW`gT{NA#c=Chp2B*6+ZbDHZ zqtC{dF%BNJiyt=5c99ve_6VY<8$z)yoDAMlGqN}JAD9dd+Oc+?e0S4O4RM*}+ z#i`u-!@H^8Nd-$&D@Mg+Sg9q^mF6MpYN0FN&q_>x0zkhgw;DKrP zF_b?ebJ~9yu4yiZmpS+$5WJB~lSC|z8TWmot1yi6ak+NUbEPoqgD&**+}?nLYOd;w z@JHu+5R;-$yAl*7tjH zNx_Qh?S`>K3K@gtLVH=k2cBZCAqPk4S>0B8nZQ8Uy)5JQFsCCiBuz!bdRMJJoS*MBaLKt-K_X)2w8q(9Q1TLR81#sb~hPH=##-|g`(-WlkPq|#O zWY*@Np5I5y?blWKGQY0x7b~*7wY+{>WY;#91Hr z(yuLzsz!U%{gF&w{i;GrK~zOLKb!WMzG3_ja(;&!+)&P^I7di0FHxuv z<{+pv`s+T2mn|NBNoXI}&1sIb(cK&F=dYQk+b4H}yfr)?H#NEE_t#yjW<}`~8X{U* zDKzCF5NPsJ9dT=KZx3#pg=1#(Kb(uW?f+fMT+b#JIKDFy+n-xoMa4Yy34(oF)|cJ% zzEigS+@Wn7k*bQx{gK~u$7ufFx2|K>*6#Ezmj-1|PO*d1p1UJ)c3QfYR9d{9fR>vX zCfg3Zy)md%l1~A>tHc1qAP||d#3|3w_=FNUx6L6+Hc>iZS~}Q#Myd*xN9usUc+%zP zUxe&YYw06yKi*=IO5u~2eZNd3nm}01K8nMp4~MaNy_5n~O9Fy>kIXPR@AqDs-VxDa zSjjD1yrL;X93Kom2p0(ad|Nev(JGc7JUUs5d+RU&UqX&`+{*}w($a0WZJPw*DOATh z-7&>}0zO-B2SZ4nS?8xKz}=|;%-4SH6?Qc{ZF0#Y{C-VQSCjpw;ov78=l2A&ILwm6KcOzKE+l_h&f;d6-S_F= zRuTz#8eP2-VpcdTA-2KZm8h$QU}6nPj2p_1+RbdUWbIVSvf*5)cxdfVbR%S$tQ9KB zBy>wjO~YyI^SE`1si;dA5ZVRCr+=@OSPlHn+r18pjqXG}PhJvKJ>S?^v(3Ey@%0Nx zlbHbU1%xLCl~z@8fX1*bZ5{{i=AlN4h2O`ObdHtEBtO4eog*A>(C7sJ$l1Bx2v0f-zVtPK?OCJy zf>Mb-eN(@2$>_QbJi)#8TZ|!uB5TlG&p8*I$id9oJlb>Y5XB5dS6b`zz{KI1j(WCY zHwK-U8P#h%f$Zv{ayhuvz?5G@SBad7lM^jC7+qez0{A~VS){#{tkbFK03ZA)gM18hVH8Z9YRppg3@nt2l_I+AtNZ~F=|p3>NB3$V;xVF$}o>gUx;61p*I zLvfq*d4Zw!^CCwAonjy3=p7y0wTw8`Y_ul?a$M-+56wE-u$A5J(UjiZsCfPL2_j~w z_bJ?dsj;3}aT=YXOCdV>o>k86{gzpq$8Ys=nH%7IB9``76eUKG%TOH_7}+kHe2 zeFHM?6cSKX@aFv6`Qg!Vr_b4dfd5*IS^c-0fg{ehG-47lzWDluY?QFD(e=Ii7m*%! zmgR3wHQA2P_%yo-zl{i7J`XvV*)sHBY$lwXu?Vk>N2s~0Xho~@pj0{P)N*^dg#;B7 z>3en*w=z8LZ?UR)+9aKmMK4E}%=c-l8DmVh=-)HexqeJi&0tOGyZcZ(n?9Vofm(r0tr`1^5x{xHBKmhSo zMGyCQKEdZTK3!{@i;*$J9*hGyZRsW2%P%mkC;S1~F@ATwXJVZvx78o-(?ZTVEe1+y zn$$x5$-|Otsx5idB}7lWk!r2+|G;!-pvn$hjktwzcFn^~nfJ%DpWB*nBT=k;a+lE{xBy+PzSF?&;~}+OvfX}3 zuLo*h+ATV8Nl!O*&uFAV`;5S|VHe}^?R2?z2?FkEmSuZWLY^2S!&IVxjZ{fxhWv5(yJ!sV-)Y~f^;Ry3TWOWU&ewKYvqF75g8yGP=l_(1I@fT{yKMpJT z@o+)B()f-n#BOq8#sfR&x9e<&9h6|q#x0=%A;ujf;en{wP2A9gSX34Hdrz}Ji2|n;|aOvdAtZYv!Dul}jN-e(IeVR(s4(p|fQV|E6=2!FgVYOQ~rjraKx+Tw!jAl}C1^i$l zAG>ml-sJtCwWCblMpzG$#zY)M2k1541M7;w`Xr#c2?CLp|1tO`q?1`zZQEW=UZ_d+ zl)b&ZZsafc@1qc4U-_fhOQHZ@JG(d8z?)aDi4+-jxM)zK)2~+pWrY zq<@Dg?~~6z%FBVGKF5AzU%=NcrvB+f2OC474H7I@iu&<6*Jg*l4O`Vxk6`kQ!Pv`s zjSTBG)kNNubKUjYNajp`MfHH-y(x%&e$XMDPNv1!j5}LBK2oNIunv)BThYufIfvwx z;k5{5NuvDrjlHzJ&X<vNMSdC;kVVdQ^Id4{ zZa(Dd$UJaI32o2wAf&%KJT>dt-V<%VMFss@vp?;=_jyYwIfN5?@_K&Ql)tt<>Z5#DFw#^rbTdrcf2bMW&Ng zxn*&Ea$pd0{xs8%ycaqW{T`RXyL-k+^Lu1l-G;Dzc;?)TvN z#qyr{m4?4?bB=sw>`Zmw`Py6pKkv?*GDpywRhp43aJxg>#}@uc{{o;2zY|v z&)gNR{3OD;idU^G(kX3X(s_J}$Jcc?RM}!49tX>s%4#Ng?Bs?Jcf-r#qEom+-Kf#N zB8>OmeL%!D)N>aEUCwUI?j0`F$=znPlyfQuHn}A{<2^F+b96N*8Fyxd4-O~*8w$24 z3dRO55A=fWW^wJSj6W{iP*&n#z${cnScm>53N&-~E?lf_6+AY`-8MiA9^%iCH&$@1 zwXJMJYTW_GayEk6-TIal*9E_WOcTB}#G;Su-TG+3O-0vbYn!Vv9GOEy>3neV3cNNz za5<2qmtZw3|tKg@Rw;3iHmoCe;uc@K;^n) z&!!zxeGMC09!=&tbGz?rxu?!{xrQDEv{)RT!b>Y9g;asgK?@@be2%4HW)J)Bc@IbY zJOg?)K*>KJBPa#gK><}3CR;}c z5EY1R;mu{j#rF1MQeWC{zyWVoJZjF6LaM|z%GAxZGuy}1tz#4;7m`S{ z=AZr1)eh;*+Ak1!$Xy$|N z$=^1C@&X7tSlc?m1Ahu$3e&cZYe4$n4^`G0+CQ;Bc!6Cty;r4c<88HPYBXf{GD%N0 z>400*NPRf9V_KrCE~Wpt>pa1kk~GZ#6*rWr)NZ&nB_f_IvEhTANzTH6j= z@fd>sszl`c%;p1l%_)WY2y=yB^Ph zAs66C9GB6?c(J5hLlH1&ShGu*!H^ns>n`uEI8H8eLh93bcd z?EPEpI+;z})jg}z!<~)Ah=O$sA%UB>%OMYZ2E!MWWVM~=?b|XMaq;#1_0n8PPDQF% zx*_ThS=KFEv=H0|GHqf?7H1Qi@getpR^TQ{vh9A$Z2E)cJBpbk7WY5Rx|r=|jWT&O zcU*^6CF2a%L7D;o0OkKPObtwwRo?yH<-=G7XO8C$y<1NfoU(JP`Y~qfuiWsoqE03$ z=T)aOt0XDtb>&u~Vn>44CYrg6*=MT{xTJMcajP}dSooF5p*Dm3YW?_PE#!Qq6l8Xt zHFCs=&z3Ef#;?ya+j5H2Q}58Po)|&C7%+eetxI~8p1Q4eX^*qiTbxtR;*^61%!zPgxsf z@Qb?QKcsEgr+DzD>2~fWbuX!v5f;X0NX-j ze`f22k*-2FZFRPMKdn+5T*el3lSkyTm+Y!0&_mPJqHB@hCrTgmo!gIB@s=MSt_ngP zZZ7-}^1wB%MtX^@N-zyg%*PbC4HFCR)(k}9!9tQK3@y_#gZ_WEQPwIVqt=Q6cR;_BPK z1+|&h9&u+67aMLXE~)o(3c#O9r|Ndw3~0`DSO9DCDfN<{_P|gj4i787eg6*B_UdMC zR90crtBM22b>*4pWr2%$F$UvY`TKnDmxpQ^wYc=jVR$^+ONL;HnTx+axNK2& z_7QIW4|1@N?^W0rHekX#_8zH5lQN<%fhl85%^{tdjH|iTGMr<|!^56BRhR3A{}|qH zS3ft4@9jm21#8E+ODcHI^~AO~BX@2j&~!HwoNfk_(&x#SDUAM+A#iKv~S2O$e6jV8>VInNIB$89*>l7t+2W-)t} ziIlj26p=sNlN69RdTh-!sbsBrPBWy1q`+M5yVBk9&(^%J_VV6a|<~KEfqF$m0 zYgcT2 zJmS=zmF~|+@^nUOW6OfW<~4jn)4|l8;*V^AC9lNS{RM!@CcGYS`pv-|+WQt3bKbou{3*Otney z8VHf`@p!l6f5#qI$3p%>L;j*F3k|TEX=fsVNNvD3Q_91K9I}Lq63A{gJ5+MCaSM2o zy!7#M)4TXi=+zyu87^G1NbC+KlTb(p0Q^3ks+K}gpnkc)&FI?BODe@lijXyzYM$Zx zugbj)@1`^~(5|1fbS9~1xn@ttG+j?zb?#L!-)WeVE?un)#csPz7LC61mYmgZ$biJ% z?F1~dsH*y+4C5gC`EYvu#LAAQzBg5f5e$oL6(@RT6{ei>zc&jOM^V?=wE)EA)hmEZ zk(7~1V?ABo*uZRKL#GJ*nFd>~#ChvQe&jPHk>E>BZ_P9Ah@WUQ;P8ei7?n_J<#Hzv zDNsC{_#iQ!4N5=TVt!z_#S={&|7S+;J}mDich z#&}z*$dw*%Dm<|7VdOpQx3L?QLwIQp9p?0Vu*kv_POIvmgDL0Qj?1~xJTcS~crz1r zJpfXCt36|aynW7VPfNt3>T$)CLR6Q+8rM2O+kVla{6-n{ZNJVC~1AUWf5s8UvTsqIHQ(_|rXg=SAM~ z%~HVf260F&2g^ILJM)&I<$@>TmUnn=-&hUt2$Ioug2u?2`vFOFs$1X9g%+15WT zIlKlgmCxQaG!UALaaQE%k%^&c82I85F~Kt3$8O9`ot3i^X@JB98~znQn&DkRHc4r! zvdg|R|5OJz@BIPh5my)*7~K*=TWLD<(zc5KUEgYA9&!FTlHS|e>?=ti*h=6No)%4MU4Am7pZ2=mSD?r0=CZOv(;o4qqRc<|u`u-DG;lJD>~Jh*f3ONXcHoLf8Em%I80RmM0#iWq z`221bj)$gKQc8CdKgH7n{M-4$~6j$EL1{7EX zn_;zn<+SUvacy-u6{+*eAFZ1SXMRIXMr%w@tHLY;H|?*{E}t&*jykr?+-|3Qm@|1? zw<=~#FPhzgw*rnRIjw0kuhUR|!O-R1)h_}TSk|_ucu?2f zh<~kR2Tg|zRwF(f7CpKD|J9{;QFUoMO_^EW#`Ck)A5702>SZO@?#$|C?5#T>g10he zO&i|bemNCa*wqoxm!xiN>b8GiI<(WwG&>pVxRglh|IPy31@&K^*?|^-#K;3mdx%r@ z9tLN@*Sr0}=r6h3Bp&0s5RLO6PXk%LHdh4>Dk}Z?#CKS?#%OaXPXh*iMZjP=jA*po&q%_g1SQ1d;l%QP>`}=_c0pFO_QF2>`ckrSL8e^^t zp}?AbeaO?rdKIKczpVZVn5_gcQf>#y>uWKrzxq63Q_v>bFnu~;ad}5yVCvsA^@Lv; z@E&!6&gT$ZP>_xAmjdnG8S7H$I?-%@npwA86c8gT?=v?BIQQU?IMJlBvE)h%eeZ6* zp6|RkIKDhRZzAMLzYaL^^Kp|c(FZXH&$o2mcU-jxSRzVZCa->6{;R>d#c*?U^et*U zPA)6#ZhG2qCZ|&j7G`lsW`A+ojb-Dx17q+~90!S)Jbgue5Yg*7FXVS4;q`rwB$W8^ zC5~l6xHy}>C1xoa?(j0hzmNkg_>YfRe!9kZ+O6=sN8ttigWFfdaQz2|TY&z?ZNI0i zB-6xJPh|-yz-T!;^#&~7*S7vWZv`t-P_eq4_!@2y$7fNgOWAC44inN=Dy+1v2~ zilh9{S4Mk^PyKTjl10D!us)^t!j@!U5CfR^F zgxG*HX7LHZH*{}s?JsjYLj0i%RrcK}aTK+&G|3zM3ExdfbQMA1rVfTG)6R4~d30aN@Xb+pwM zt3Z(HLO-AZ9Slh`ZJw#MYmcv&wTA}^4qq*PkQP#k=Xh6IpHyS2Olp5r(D$q#PfydU?BhOk{fA36&qqbSE(MhT z688ac5sGd_{;?*yeNJTl;m7%&n6otH>r*|S60l_}To9^A%1KxqC)pD#E>BbSgwrfm zUn9wsKEC zciwZP>)CXDgoUHZ6q2T0w2?)i`W2LK!u%?8i|pq4Ue@UI`^oih5%s@!5#kCoi?hH=|^$Vz|e>GMhu5oR7~#W%VW)t0Fr7% z)-1XVCQ@ktCs*%vb*^fs4+d1!-cTpffeOto0T1tadr@wA3}MB_CY=B@^oz|M)``eS#Vo!AxPSX9s1B z-Qi%M7Jhz~hUhP|9&%x=kDB}rl5wdaZ3Nud53+G&j!U+`P!BUcGBT2-Egpb&e23Ie z@K{~jq<|6YX)NjEW}$n?b1tUomm*CmlgXLd|7cm3zXmPJ>oM#u=#k#N9bED<*m~RK zoD>VO&?Lp^dbb?q*Ee&=z=vEWSRm_niyo<20Q5B{_^AVAGQbP*l=`UzY>W7;_la3A*#{>IFrXKct7Z4GBP4CZ9R(l zu&^ugr5*0)jf+&NPsh1dlG*d9M@Y-{Q~WfW!?)a}8Yg-hOP+KSzx$Uoq@zfKpxCb) z?=vP4`ESqMXh?D7QL2T-h22uqp;R1ODWJ(+BfVPePT zf=+C&P`lhV&-atd-gUhvIq1AzH+aC7h!hX_yi2IOE>wtS&D%E_K|@yfkjH)Cnaawn z&Nvu{ext)My%3+=B3`X*b(0mPpcJ3_s#KzO0=(sL`D3V*E;iRxnyD)_c2xpI)9zNQ zf7#I*-Y=VjO~_;gh7mWxw0Hpe#qpMx)z!lpqrK)2*W^nQ(kIdvbJhe5Wd&O+G!QN= z=1qbgjA8Fc@fi8%7*nytC_Pi6t;q@nJdPwP zx|%wpT5T<6KGhDx8Z9$j(|l=M8U{};@i^%mI5h_^N<n1l344Fe`UBt_E+6*kpr zwkMn-6z4CmQ{^`QwO9#Ixg?8FaphUzuCkgv1p%>mLv5IFd3Azu6x@LqY=9a)unM0B^vkiO0xIubqk6Z04fI(O6$G5>< z5h=52&07reBHgUK71Jo?yZ`SE{f8~hrlhI>f)WWan9^JKQd2M-N_1s##r8si4BBXn z4xVS|JUdj1>pO{E)yVzb{Z!M8mir z*T2P15J1hu2`MX08X0hty33yf!sWf7^#KaR1NmCz5@nJRPi}1R_=}}#<6y7?b;{63 zEkLqzW{u6d+NaIiMvK-1#t!%sh8H>dzdozAvX|v1ej(7mBtT837PBgb`+%k(kDSgE)P z#=t8fpOb8$|CzY;XQ97dRKZ_V2af0NF8XnL6eIYSUQU8#0s`Z;e7rwT8 z?tq5%Cnii)yLUR$R*sGiHAXHP*vuho)sYzA^{++=P`x$+xm{Y6NFJwdye@gJuz}?^ z=f56TBZNxtM%q`LikYfE_efSszLtbFR&;2Tq|56qBZD=6tGe+{Zt?&E6AyJ%C8tZO zvIvP{U*277TkT94W;5cbUutbmoX)hbw!VP%pWSp#vlvDM?iMtYru_4`7qJ2QNOcsH zQ-kMJ2@M>~N_VH2Xs*|Lv_{d{@g_K)&6+NK)S@-@48Ph*fH^DRV^ck@r)`^a`go4J zWWTqb~&FO9&@c#Rh8Z`gO2OY1q*+>)o3Y(@Y$hCg&Wq5hOryWm6eDJ@tc5f!6 zG==h&5j%1=4m7a=fMvGku%!#wNVNI;{CBgm|#W<(HkfW=+Jk7_6$2xmI z-h$6nnX1ly_CueGEH+ve7u=;p32f56kV(-J$Ao1=Y-wEGufqyx(#Q*6dcN2CtWeFx zfbU*v2FZy8mFB`Ev*~Me{2^)YMTaBe6qI`5;}TrT^oTBlY9|8#sRb!|u@(NSrWoN7 zP7&^yBxw5?Q%9re`_zF`=auAkI{e5U`# zmI2Z~Zy{8N{F009cnRtGYEPW^$=~3zY{65>7M5i}jcoLg&GeYJ(6@3>vU2XrFYoPHIO_e{`ip_Z!nJ?r>ar}@8P;ve>8wit z;jbfrRR4oHUy7zVa)=X`e*JnE)Pa;%zY4mRrG=Q9m?`9CZ#wv?!T4A zbs^YrG&_7%0o5Qz7z`huP{jNhG!oSb>Y}qw5Qwur@0(UYZpvmN;GO0WQH5mOvc zsL`dVu$jzvU1XLp6Nn0yZzlf4yiUtWBR=nEd6@P?q&<`c^2d#=syv9MkX^{=s5lo} zOGvyR#Qxpny5-X`Ob`6CxcukCdQV06Q>R zS>(b$v7wkc3|EnX3QWKm8!8o;u#VyI_g0ceY4SAjf`eq}!$)=jdEOeOzcDi9I zZ`G2gcW823!(&U^b&L(>W}QyzN|?@ybsc#=XdCjnXoK-z(8)801hN#i3$R9vK>mIQ z_VW?0T4#vw5dE9o1}YSg966*&@#FG5*iyt6=-145{?_?Pb&b7_NwC_LbJ7C((0@z? z+v-u5hriluxDLDCzZefycvs3iroZlnR$2SVI$5lyv;EFoFb;tNk28t z?V%hd$K-nb+9qSFoGmRyul4Pw#@&Is9q;eHi2|6U)&o_(aMxpv4~XAG?t?j%3l>{Pz@7NA+3GGdNoY)YDYAx4=Pz z`1?zpmOM)co_x>un+@2Ga&*@2RC1wqFKiH{;aV!!xS3E+d<^eDygd)kcDfy?8oa)Z z>&X?4t7LF5fx_u9tW?N$D_z9Gch%QMShi=sS~Iqt@oJhv?zlE)O9D0c{F=(r3TvkZ-9tn9Rk>}KwVj_+!cgeMSuWme0 z(g_-h01{Q_Zex>V^$MKQy~0UM8>?DCuyD?Hdl)DC5gTH zp0Oq4Fq!mlan>|3{Ftm|%uGs;G}{aITfO1Robxy6cq#hOBPo4Btszp;QCr3Y+EPD# z_BVUFQuh82F(g*(>H&4O)a^{EYJcHtK6Aj(*(QNgO}XnHvgp|m9NmqH8(6$b8(PV| zrvG__DfaGAp9Nz@YuTddW_;~+TrYO#aiMnZ7w5pClV<`fD~yS2o3_$<2tAJr&d%vX6r`t9!@W zdu-O62A(qV!+mrYwT)#+7m=5?vh+9ehOLfH;wW;+jiZSpIl^acn;S?kWWSO?DkE0! z=_%&*0ZHnq;=!s#iu&t^wt6Fj(pU5%f3m&heVYlAiCax|b1m>JE@cDdWO(8{k3&j`rm1$Z#EIq5NaUkzx?-m_VxEQ7Bs@{Myp8V8#8R~!sBVg*V0ef#7Bp=Sgnzu0rjQpy7+c6H=z7Yh9UoIC^0V;6+n zJ&{lVH*nJ!ecd^VSIhdX5i^;jXOp%xXJ??6CL{SAb~{%6*m|3OK@zn9(;gNh$L9-9 zCz)i(NtpZH{j*(otKxLFumr7Tn%HykZB6tH{qY-3rz?l|kWW`i?%bOoUmZoU1rFzk%RFb$cL1mPa^^UBjd#XKx68=yVyiWI&B~3*NW|TUgu}uR9-#GkDY2tAAgRK zKD`d#;q3YfJk$6&Icny`O8wc>CHFkYwd>9H!jWBcqntso%1;6shXNbN{4L?Ax*X^& zk=xEBF15qC0%D`0hS-B}j}u!Tj~#-ksR1DdZux@E~tc;#&rKzaJ-5 zNpZ6Dlg3*>pdLBGs8G+Ew6wt)4HhY)pCDq)YXc{wAQgxMJo<>BI}+e73VT%`>uZH1BP zczE(zjCjEHpY%2alb(6Moh8I=w8???3r>+{hoo%4C@K zjVqDk4z0)O?dWUclY*fA&M|OA?@=F4Nt{t&CHiO1;P=%Nr7QQ#fj3H-B)2vi6CjLn z!rogqJ(dcLPy1eva#7O|x6ZSziR7dEaJiSMSHW9t)f;IJlwt;;UoIxsF2J@umzXac zYnyo-VkL3Wzu?j>Z737k2;B5Mlnwx`zT>A&{rX*uqa0hYTMRKC6||@zMH=GyzxOD; zU&YqYdsVN_DEES3TY0tN_WIu9z?ApXdy#dfWV!7L7hF0zzdLkC)@132Fb#k+ml1D^ z{?H2Cc5F`neE%x7pKkxKf!bYs^lqNbDD7-PvPL_nMO5=t{;P-D2yp9*MCLo@*SIOc zU~vbh+ZtBwu58{gnsS1QtokpjS+7}I$lj#yy(^Yh3)sMccQU`|{N-jQ7H>aQ%y3r7 zfQ04!(2mRA&9T?*XH=fh`&sOy6TvFGy1x?;5Oi60Yg2Hed84oiI`77(3AvV|?BFaq zJs;ltl$BAkovHe`0RMCiy?_1XFXI~ydg3*a_&l8fb<)!NXLC9O!`GWqA)UIavvcav zyg~)4ymJrlyvLxxvxf=f9IDXnQ`uwkg)JN>@$z_>I5-8Sw9+5nMDcHM(4awq=9`q< z3_XHv7ze}8U+&1ATa}X5leH@Y*<6djRdmMFUN%{ZtPm0IM@!!H&#donP`}R@FQxms zxIT1PAmP~uZyVymK>26+XX$dsQM!)OV|lSEkh_dlgVw|Lq>d!e^hHV)zH;@5`YZ8i z$ys+rn1o7UwYQ|1{_SRWQU0$SB42`qEOak`rSY@6WUJ-Xs|znoyym(E%!2O^ewg0z{4}4LN@i?5Rn_=n(X_?(+cbw3#1pOys>oJ zl&x_W0@l&+8;tYvg?6GjRQ@CI8=vgeOi-K4#m*b4FPn(IiUD?L99@hO6J=fQ{uftW zc?|cJd@Y**oWD5X|D6Ts52@Fr66<+j(++<(JeIuH)hdCsw)yJm5#tTq-&_vd8Y9SP z?8}ha<%SN~<1O7{hX^ZnOWuJ~?zI90N?VBY_Dzd^edYGZ*j<-&;*GVz{YvMgBlg7jR7#;nyf20m4bPqyOyq%x%ZTJC zM5&9+IUHF2&Eax-bTkiuVof5C(sR%f5VnB$GwSO zbij#^g5#pSNVI&k5L7u>Vv?NEH%V(_$@K!yy~^QyPy`xN7d9)`Mkr-&3uiUM1UCk< zZnRtOb8%Pc$!m_{XVt*qE6fV3vDgDsc`Om!Ea@ z@SQFw{Gm(*E9dH8Ai}_g1%TS{Hj=1*C~jXbaXE7QU9mYrgiI-EmIVF9toCepuZ-T64SqWT;#WsoWJnli4 z^%#TMs7j5NXXFh^hPQLS7K6*E_0P%+y}v9JZK3rw{i!)gpTb@u64FcRW7&KoTFa1!Y51jx?6o~aV?d-x!o~8_3LDckNk6(Nk!Yg{ zb!C!z@$+{o3_Yjj6}Utl8do$IP&!|$VIF%ANqgeHse~jsj|l?(-*slWop+3H8;sty zOyrEW&rr*Sj4msfPEaSJA9u<^M|ixTjEu{^Tk|TL5~8zJAn4I;xLm$f@&%0fXAyLR z`Y5n%nKQVn!vc3U*G>e`Wgn#UFDBq zded%qB|lz3v7U#$aEoIM*(%?M5Na55KjL0jl(Wq{$FoP?tp{c59pY)q&NN78YrdNr z`qI=c#X?ni*PKV4#DcXzX>!XhxFNjgeNH)ZplGY=5{%KrPoQcLa4fkvfs8JbBy3Xn z6#&5^0tr^qFoXp@arK2XL#f!-<0fcQ$4yfZxPO!$ZreqD7a@#GR3X4Qci$b>6!shY z&EuHFdW(+fsLYKewaqQMF1gu3QJOn1?;}EB$KI^vk8ACmtY#tCX8LjO(<)p!N2@rU zCPFx#jwBDngWrDDRXnD={OV4bCiR&|_QuCGTgJPF3S|6%lv>Jy`R~|sBJT{!E8 zVHkYXdBi1aJ89+JC(7T#;DHa7OGh;Q97{eQGVvK(D5=(aN@Q3^MrH*zWSfc&mxPvk zLB79G38I@4C~v!)Sn}?%jXm~ip_O^rm=_$?c+{Gf8W8?g+Jj-Y^1#y2@8L&&T zUS@8cu9!%W! zdNe2oGmG9}@GugKy|29e!XL$wWcAFtXjK?Zo;10S?9@v;W$@3mARen8t&g?m@Q$~2NV5myLox29} z+~CivAQnJwb2DuowdySQtJuu<<31vJ=9d|~+IDZeMM!1F$4!S;@q#HY3&c$Rvy9%_E?#r}5tLk9wof zsV*e+8^z5g76W5v!WT@*oU^B+!=J!tNCNY}L9e(noChB!qahLm3yZ4Gj3td;rzJBo zKhtIFpxw#`k;mvPFiw~+|2fJW8T@B#BD|5|@Wjq*?qu1EmAXSBvY9|a0Ftwm>T)c#QnM8QT@6V^d+IK8-Hy;j=dFIQ zAf^9F5ukP0S2$QB>7JL)3)kH{%UPSf(qU=kdzakHu_$DVV ztxva#PnZdAJ8-dD<*_VQ034lCvrq-hT`(nwSYE@lgUivy=sL4$*9HZcO$z$>G$)|y zqSJ8$Y_EK|2iL!E!k&F1Pc3Y8b*dmbEN6aO%{E6V@%%*g)AEA0_}9mc?nMx5N%roh zcSV~Ascv<{RUrZvpGoa9aofexDE7#a259bhG4<^kuxz!7f`Q%1zJ237tBKcO8Iiv zZx9g5AvqUaF70CzV|0YF_+Ga7SOUVCCltY^x<*tb&i<#0dz54c&;c>ek7}4}^^IMh zQ^+8g-*kT8_+-SOst?>36=oO8?~To5(r>#^;UzhbvLC?Ha-_L%_1WSgl8ugL75~)) zG~h&CR4h4GiakDDztg0+jxSgiM zN6TC%{}AF4a`#Z%oE3NyOW?|SmNqonQ{64ua5VUT1P+v-@r+vO9IE(zQ~0J6Djt zt#?=H)828$yst@-JABivw(9)8yd$m5fPygrE}PE$FT9xj=Tc(ATQeU8i?$GXXgz}z z%f#unF2P5b88PXO`DsC}o~tp}lGU>RwNL?e`)Iz9@K8__GZOz0K{menP@M*7YC8^n zr_*LJDE?sHd8Pe)1giTWC4L{XM)gWQxn7Q3N?rU+U8|Z=$iy zA53RO(}lS#QKq`TE*#$gTUAab4PV%DGShy3EI+sQvk_a_G*mv|dUgB2_7%zY*2(CT*^r-+CEQ;2i_E{I{E*Y z`tE2p{HXo5+G?w)E@~E4joH@TZS7r&J&W2!h1j9fEJ|%b%~(k&u|l-9SJaG(y@J@A zAiwlI=l#CFoRf3%Z|?ov{oMOxgis~@dBH67uW%73?|lL7X8X^klQLfy60fAl3$&J_ z7-QK6(L5y&_!Cw4BRFW+J-7@wQlTn}`&F>@zjDH?N>nsK{2uLIoa-S$<-c^|+rKV5 z8&D2@xJ2LibZt|$d#m7n3VVXT8)Bk;{q)C_fuI9%vT1innX9`)q^3i7p+6Xx*Rdv* z65!U9Qn>L&$Pkwr$t>HB&^#lIiHyj{NlzC43@^9;Bo)jQ>qU2nsT zH$LKBGz_mwJv>uAjNwoib3;syQ;P6wxYt>u zVRc=_#Fs?4`(KwomsN_bgXtzFmi$oGl?J2rt=9jX)UEmzy`-ac1NX)9a9;PKJ@ey6 z$8>0i-ue8JUq$kWWR<^wQIJmkvcOM7SCE>KBsXoY?J3tMDd(WfbyB_mAr`gDKi3_( zJvjID+v94-N`IfKaH3V|L*2Ajf9gZ2NTf|K=I5`QzVGCc?v##r?I21B=lwD{uZTE zw8OG`08{NvIMZcS7hA2m-gz`29c1$_QB>?)E`nOI&JX>9i;6!jQ4$vzdhc|0&d}Cm zAo_tnlZ(Im`W!zu|G5cOmimcm1&hooEs2ni&OhLdngb8qg&4x%B=_^qM5C0khNNtTJCSrSYiWb&u#OjK@z#=;W*sqk z#?}A%OK!R6DC*0KdcjeK=DTZrn_(p9_LCdDSCSRdce5Ay1}RI$Hv67`+!&7-H%`}9 zCc-@R&;m6LbtTp;{p;+qKnBfkod~(pYR+fMc5dfYovL`Zr!+#3QWE~Ex?eKhs}5=n z%P!}DX0o3UC?+4hPSLb$oyaEMb)yyM zRe8;Z+0BuOE4ZU6En`vjt(xH4j*>WaNiK;=J27py>d8;|{NyF=9sai~-wTR<-Y&m% z&fwOZNs>Yx{J`|&MHns!llCK&P`ghp2WA&=23G0OaP<&bd7K_Nkc4|f%ZcAa_+H1F zJuC?v{1wG&Ann9a#`;9 zTd}f^|Lh-p{0~%jd5lY}arGzPsWKNdRBch?p`GJppBTkQL&iCOhi*v!jL=&05?695$4+yfU9%Bx9GoHy2Nes{O=#;ER zj^5vh*QR^Sjfah(X9`Z%E^k%M`(!gtkrz~w>je>Ig}uRUcGu@xQQo{s8P!RJJixyR zeHFR74LYT2UV#|ej-({oz%-Y{5XIy9@SsoSg9F5kAf7jq0+5=Aj=mdOg|Ct&?zwD> zPHsuXaa`aIzg#lQYTup!>17NLc2xfFkN%*gmRvi{er3GA+~;n>++TP_?ZFc1ok3w)|n zA3?n@#Br=O@s9s*owx#lT2CFHO-(i&&;CyRA(rOT*&+pEkcrX*Q=tfN*6dQ8+Y5U> zCn_5WNQ8xHDnrlv8pjmfA_+|!<_Nr#SfHOv&iyP_-gf7jmzqumqyn$XeYq5jXw@ab zSU|EE(^P50XRiHMRD4LNI7?0NB^KPZp}wqZUN^0C)J60RMw5A&zz)w&NmK09diKi0 zdoc-r_Z+TrLRWI)+#{Yg-QG=?lgV^^x?!vDm}B3lNnG?1aM^lxtf$KQjiv|mi5d22 z@UBXIU>8*3c!)|p=X*#6>ck4MQ+1TYGMuL$G8#IrQ_gRmX2S2ZYBW*loBdhwy1H(Q zT*dqYhmcsltn0Kl5LvXJW$whXGcAV)g23)u2h~{34StJl8n+v23EY~U^T$G^N67UPot5(lYeS;`0CG@XTdF7&1)7e2d|Kx&7FV6g8MUP=0IM4OgGa0(o%A;S;+{k7CATSr*)Y76s@I1Hh`dxOb0Zs19c>(I8|--QB$7~ML1V++`)=KNJ| zpN5ADNQ0up#1kK*%BVfDsP(sZYK8^e=@=*eXffSf2K=Pg9Wwa9J0CGLjHVcBZ;F?3 zieGoTjy~Q0N+tdf+2f@QfEWu(MKq`G{7k`~{n>0uL3Q2e?eM1cfBFNY>o%PHsqRcV zdqpDl`HkXexrAkrhFT$m@6>KA9OG{HOU~R^)}OGB&dBh*({ul_=}Fe7Rl|%Q9G@uS zBZa93@%)5uC%3DyK2(4jbHCR4B*Y7GC4_j<-cI-2<^Q$?Z~S1R4t|cl?v_hk4yO6l zsB&lTnh)JY>g8u7YSM?zH{hoXJUlO{UXS#`@T!i4W;=FFqxL}TWhlh7OGM! zBQmD~Zl#T}VXKC$ZSe3#YGu+T__XG)9f>$ zv3QMDxnreiO(pzG^nByL#ya&@si+ATfK2#PY!PUg>xh3rFU_^9~btXVS!X}dcWK~1a5U9B?mVcPipH)yhF zuyBfG<_hyPdQ|63uhV>cL*#Lhw|Sr5@ufmJ4|LFvwci-=@EN-BvR=fPg8x=QzL9+ToZ^6f zJwQaEs}C(n*eJUERg*^!k#^jk(>_~MJ-z0`Kk?;(8Mw2$w?%p2OV?YvHU~MWzr}^E z3gSBUotmtyZ!BQad*yWWc~9dwZgPL}`BRipA@-7TbUFvD*qQK6z$mr-5i%$ZRgUWF~0{24!%-GVX~ue}wpE!?52 zLmF-uRb6^n6LseX;u!VB>=L>EU;`yG3klY^4XKO#5E8FDQyk@aRx*;%xRfYMGiLvz zL@AtJ)K$TPu4dBLd*^*;AdrC(P~%Q~vbZmyKGt`o3x4By|D&Z8l|Ni%fA~0j_)1FJ zG={C;`KD!aUW7+cFIc=dN3yK56uF;d&6}P%f=dF4^PlyDl3F(k>Q0-3q~x6?zP*~8 zhrGck|9I1-GdttMX^(!1N!V*omiw7SGsS)OXJ{|<#@O$dG(`6MuHPBXu6`6KziA>X zSS{{gtHqCeE8zHqtx@70eW(M~1Y0N~4lD461Hk|F8jGJ(p+^c{mnEhaI2Eb4TkT@M z_?<;%=NFi}K9Ik3Be-a`UFL4k(_0?^uU{sL8yjiIJWNJT88k=$XZuV~QPT6tC9!*T>Ebz)jb9!bC3tEujqRFsN zz@T+~xFGl@>xZ)?NYu-W3%Tb`e%_!iuew}^$sspI(Dw8=>{**AWIwZ(IQD#n)9=++b#PT9@$!{F#EL@rL$vE{RGA|nr9AM1phDh zBbp8EAuCEEcj-X4H7io`sfj22?mc`U!Yw%Z`IR(5&C1eaC5Edd{GT=N{(sx%0#yI} z_s?zEWf0r5?=PKG-^d>?N6P8J?roob4-WIcQKIKUslG`t>Mlk4X$-6>f>tzn&@Lpo zike$>vJWobixhrc73T3EJ?qb!#X*)KMRG;C{9LpKY7#oKH!!Jjec#*~zEq5diPNhY`EV8n-DZ-wP$}yrbE$j3Q@_@8wq4{|6h3dR zbk4wN4Ka9H{^Pq$rp~MV(v7AM38bl$W0ue& zhOY0Y(~^&L^3XpU8uW~+s%JE{eE0M~1)T6l{O;54Z|y72=ilX~vSS<8RMou77iL$v z4&0@>49fDs*>it__hsZZgzggL@t94o5xAcL(MsOhw@)`{JP2CzPCZSaW znUdmu;mp%~y%W-}bOgM@nrL*wI1813REOPdx?_@i{Ol1kIua%-7kN{n@$xnMAr?v& zcu?>ej5GYk3r8IiGxOe~9KkJ%|69@`U8go`6)!@rj%nxb%hKO`n3lO`Hsa^x=w)rS z!U+%b@Y2Lo5Z58;I*oT0Mug)k)7120KbpL9MhHfZ4LwV6DE$nsKyL#lJ-SOtig~64( z8WM`mGb!p<(%53!`@plq9iG=mG*#2!(b zn>TYJ3=-e`NTnBib-#-z>W9|t2hZ-^HFJ1EH)8e}sF8od`2M|>3 z+&4~kH_6n$>yR>`q=zXbOo;e3S&Q`@_+r+!y{P+>B`a3h-V6D9W>L`5`AxE6tzFr8 zjnZ)HzF4dXsl!str{3keLBRiF0m^+tUNaqeh%bLNkzJ8-$%+3A5NE-Boy;6{!5$pF zlQwKoP()|#vvn&^eDN!S$h!Y-zdK(+!&UFez;Wo34PIzblzm$(@ah^X$DM~3o2?f% zAFdBA$Y~v@cLD5XR3~tIUV9axNqH>IRd}BhO0-|CqflGg`NA#T`dH?ln8=8VqBGke zHnLT5GySqZNS0o(4ctUdyHI=W35Q=AmhbKv`bzMNCr~sy#~sb(vznLR^g@)siUCDDLYgvH+3GFELg=|D;gs3WN*& znX%i9=qN5U1eS!~Yul0L-k1YLS-U#+3CjH4s?h!HVJBK}TjJQ9m#D!c5oR6^2e7j^89w9P@M(Ir~V*q!Dp!jq$RK)Fz7Ry zOzfL@Pg$Qjw4t0Somc=0^f8xNV+$)4R(|@qCRqJdefU;{3>qH%?rpN;#Z@1j=hghX z3SOLrANnV#d+isGr0wd-u9F+qYdn74#XKBn?I-z$y!7$aOc@bIC3VT>z$kem#1|O2 zOUBM@`HS~j(DsXf)Q~SO?D3!>b1+h7x+s<#*$!NKV*lU zm=8iadu`?(Z#7Fu;}7m{p0T#Sx7n0w%yPd=71d8~jZ82-&+OqRYoU-p0}=a_!3OW{ z=Ipx*A?k`f>1U&wRiCj}L>_E-2OSKkgWiM+Y?0fnh(+I*XOb&cmc5#{oi=`kQn=0# zO=PLFUj-HwkG7_j$S?Z5QeRtogzGQ(Pd|lT0Y+&^tc5pKO!vB!x_CE5;LtFA7o`yS zA^B{io0iw@Et{UjJ)E<@(q+Z#pLYz4An{vImj~zw%00$>0(*sh1MQf+oDSdWvi&2sct`$c-$8srzHrqY>6t@hy$dVFJt^@$ z2F}by4r0&zRbS;|ybKk1#gBJEB2HbZ<@Kx?)EUs3`^#Tgl#kF1${e{WLrZQ-DqM9V z5sA5p3EG|EviYJW_7Xz`LpzJm+P}ercvR_LV8o;1Liu50j0S)ROSyL^z%MQ&iYkcH zwW(85_T!kqN2XZOBsq`s;pXkJ>=LdV)lA9&fGbB3s0%Z5THBWTNVkr2@(>B(`7|20$ z>gdAb_5lwWQFozA{Pk!Y0uorb5UeGmU!Zf4qu!_&dP74WuW&p7BA?CYoPg1h~gtF4MY zpVN=FdcQw6GrHcD4UPYNszC2S{cG<8`5|4it8|<5#nsEr=I~-@mbg@*Sw@ico@MvU z={&|ero9n-0fk!gcl2{hThsr+Wpau!QP3pLjZUPtHU612unCN-)&UgfRW^G$i5)Ko zZET$3DBI-FO+WL{Kw_KF^L(p??YWqJ`_G8jzOG;VTh6)0Rn$P^6>9Of2(l8074$kd z{nDY{dfxAnUR>S|ejAI+L=m;D?*?DWj$)9_IJL^Y=Q5AR&nLPy1uF_7^ zfk$(qAY-!9e#k(vl@ZGf4KKg8zs=m!LFfDYJWRU{%s$TL4cq%=;}SWiI2i0wsuWMo z4y(7;^vo1H8e`pALAc)1v%gPks-qO>uC+<>M zqD1a`duKej7XXYU6YyJh@3f)z?MT@L|Na?8U)lY`tspy_rMH^trEa!sC$)B3G_8~V zJ0H#Ao$EtM()pEbHgN~xaWCNgdQi~;3G|&>()H}ATC%tN8S_7zcjJY0+0CorytA#- zdEf)uRTE0;d(#`?KuztpO|J)28@rZo+)VWdC(mx>?`2-mWS=2x2`^|aOCa~6h(ClL4dN0*CA#1(zdc=Knmu6$`X{q0;V0o;?);BhH z#fnsLfB0-+_-gT~sv=6xq~pu*_`3DyJ4|A+*v)16D^FWa2`QNO6Am=(B^1o>uw^}? z=7s80q?-#7Etl1PxGt+yKl-*az-`^Ez!Qj6KANc>aX)(qheRdLxy6VAh&N@nJs9oB zWrx%d>m;H!XEN$Z%}-mQY(JAkJd8*6_-PA1y=f70cC37FyC$?@jdZ*fNk>&w-|AzU zO~K^NyU|vO&`bGoJ5keGnwdXt8|0CUW#A#BBYOgV1$|IlfwoL;Eb&g;t#uh95R8b) z+wApBPE%j&L$l*n=KsumZPNf0Sh{fm)Q4D=RfMf@GW6)atE{7^@PMD za4d`$s9Rhpu2KR}*NdnA%r|Tw-SfvM^5jY;4{C(;1gCk=jiVJOIVbybe2%TP>bP95 z$MdM?7oi!Lisuuo%VC9>cxz8}qw^A}#TSz+7gQ4+@hD2WY*6 zCPgnB#mb=K`EK9%)U%EFrU~8ezaR1J%fz1wAISbml>P%fl%Jhc!YmJPl|s_T>VA!= z`K@ot^quV9%d)XnoGj<09>JBq9@Tzh<-$~{wCllP&^)HnI=GOgP@do+77(mGe$P_= zB$6+hwuy7Qkg>UF(&$w`SSy}awJRXBZxeAgW;q?NiZ18?r+EWYjXW2nuG}*G=2vG2)z|A+H4rDbF~rH<$z~XN(CWCfmckWQ zu!%YeK}|41gwJ_`?6<0{_sJ{;u!>xX+du1%|^6~MlP*Ki0;aL~GDT}Wd?ZeJYqoou2aa3wj(x(|`EE+2g$_mi+NU?X6Ia=uVT#VltX6!18f~(Jiyk zx76EXcP0(>0}V_5T-K^D%w=+*P?8=5zrWi|S7rL6_8WI>BCrHdc<;Ka%8+c94od^# z=k^!;BxllVY|!TXTaE@{DwFk}2Wm%EjIiR*Bpyf?m_6m;y}oEYcm$6tg8J4Vum~wR z`ZG<5Ig@aq?U~RDIWPIo$+2$NR`oO&<+F+#ewNQquD%basHhA1W)6VBneur<@=&r&eSPiy!?-7V_(c$+5wirM6wrJ>Y1{edM zZ6T#?D2E{~JkDh}$q3*Q;m+k?WUMU0mP-dnrFJYo zu2a`qUeY@Bnvx6`<);?4W%-ZaA5i_?5BBy8gZ+IFE^5v@yfCUu=y4j9y)SoH?j8lU zgMI1IWxv0x=aS*#I<{QheMfcz?=hx-{$4yNsz|0wsjyReUQ!Z({zrh@IYEGpZl`v`5gxKHaBhG({78HIQw-m|V|?f$K-bZyL+mNDWNw}q}0AE2>hN5i~k&+Hg z3mUVb+lfuD_6-1&_Wz=5$YyJun7#d1M|iC0ujnd~zoivr@e>vsC4CAX3CHqT$Lt&m z0`SCb-D0bu#6dh)%|zfZWt1_#M4y*xe!i)fS2(h_mf5lgv(z_2Jv-G0eXV}FSuc*G zw?3#VyqRndqC3?1=Vp6dGlBUavhWC?R@0i4 z6dzBR?NV1Em+La8lHiUbCp44%vr|0im6nVHKhUNqAZ)seaUBn^f)W?OC%qv^t!(TrBH>zkVF%5U}JU||VGXF?7fWpzx#N9^sV}I+kIq6ZH(QxAz7zV~e{Gn~A zPEGQM617*ueqkCQxVl8kjQ6EAy_wczRUv#rr3bn)tw%6CK*-Lp&|(&M3` zxsPrL!imK8OR#l&NhzP|kbI&gXsn^Nd*)JoqIP~mc0l0CmNS< zG2_5RFlNpWpcKMhcvPlM{_1VeYc+R*YyYKZI+kTERv=rMV~|(K9^bBO(OK7BXEEAE zwF;5-)&)JAs|F9FZJFaVh-NfaS& z_1KvqMu-6)+QR&tPjVn%o9YhJEcVwem)pdk&xdj#k_7?lC@*pYepoRuD9dvRXzWt< zDZ#tt1~eZC?8@kMq*9I;TLJhAh7L{xIh=w(Swv|L@)DQ5-&qxB;jP!$5%rxhx`%kH zHA3)iQ(~K9D6wD-cr(YfdCWW^Yb|TZ2ck9SIy-;|7x|e9OwA7o>G^r`4kQ1ocSQ^}|F4unj z{`V0Uw+uA_8L(!ZwgVr8%H1fx4DHIqF2~M*_hpII^Ol04#zT8Y-N9xBM$&Rr+2;z9 zEbAl286g?r<4H!HrQ@ocoQ;(6JR;(jHp1=LDU{TMgw&Tc7u7M4_!Z2 z8VvYqRSqC_6px6jtcB-rh0T!Gd ze)*9pxS@qmt1H2yI?o;-t~jhntQRTh3(x?l_8RPn^cYqHCaSUm4la_TSHL**di2I( zLl?SRM!geq2V#_$mxs&B z1JICB88#VNS|Kt~hzf1M*4-N@%txO-P)sFD6t~m8Y`ZXE(6$j(gjSocSls&D_6=`+ zP+>+QSy_06=v(zdEWgSZTw2g;kG5mzA5CntE0X~$T2}tR+$>!z5D)S+L%3k}eXE^> zmCndHB^xtd%X(9+D@!4lAj!Pyt1BssHw#K9N_?%>x3_{B{3aX38k2fA&}~~qb>Pa( zI3+JJ7loZi9x|Yqwz}XJ>&0IE3+TfB+GD0aI+gq;t{g4qF5laDY$HrC9pNU7u>AHt*C>})hW38U<&0{ua`I-a%6?X+b z@zfhHd|D~>M$5)B1EvFu20H^Wy>7=CwQ0vimz}z)hX#EvWQC>l&%PFw%Myxo zy~pU7{hn2w9sDR=Y-e^e8$L3|(b{KnC)s#A$noSUI1(z(+m^QG&8procyw4<_V@Jq zh5;jobb%#ifYp5Irzn_@qt*f~yE(q^18DskCSSNh4Wi&K$m$gJeAALb-L9|DbwvV4(QaKm2JgGy~iDG!ub%3#v4q`C@g zJ+e@K-jH|S`yI7xWFPOAz)sINg-#1*_<)Z@-=Y-sMNeeXaLa8{F)oV74Sm7FD8`0* zz0?|N_W}4O++FDnxgJrVUod3YF1;HfRrMr_?*m0bd1?Rc>;@gRFdU;|gA zu7Zqr>ylX5XWDeGDmP;Emk`^NKDa(I9@jBW3v(acsm?|_0^0X!IPV+?j$;jxm>wW9 zK0N)HmB3y7q?cdTXdq}W{7utO^FidnqNT;963BFlxhbuO3yclc*!-=l)}0;ik8mmK zXEf**@k`&|L*f27nj&it2&tDlTtfSMM81G4s4JGuTO)w?-Y$K~A$+3WZMiHvme-Si z2wG{WZ($r7d!)~7m9#p^=X`bJ=MI0NCo#Riopl-V%bx*v2Nyip;z9Mj0U0}AcfRI9%Wt1M_lo$s zb`!e&9rZ;%>&eDp&z0q9Ht+2uT-P)X>gR}F`=TAj{7u#Y;DI%B$NEgjh8-R^<54xu zFYA$9xsb4Bot(kN4=dx9%wjbIDIL;^3z2RQIU5^|=&J9WxN>N?i&AvHfz$zf@I+S* zU{r)`zWYkGQpo96I9JGFXCHRixHN~sfkn&2{3@|VEXyR$l2^S;A}L+lwc38sr@Hs= zZhB1Gy|E0)Mj|j>>iltCf_UAQt{*nX$nC;bz}}m&%11a4eLX-yM?4Vcpi$Q%5*6rk z;p`8LnXPYzIJ!4!>8)9;vTT0G&}TZu)SRl!8Yf3NQtgqb)ylxv6;qV#MwDEk)#mzG zDbsIgxUK#!z%}Y7I$GAcTWmg~*WJ_!%cRE&!|l$hnl zJK(DC&G0_0J551SI?%Q~?u&aixELMVJe$L{&7B(<@T67uplQ+S(oRGXV8Ardd*TIcT+^h%oB^!#rpBUR{o<{|dRgH1pG6$jtz zikJVTIgFGw$^nF2nn;G#5N7t>DE2igJP_!P(C-F+m(t5>ilE+pZTI57y#~ZP6U=ze z9I3K}`VF`XuRGac_eT(9M`UA)>gJJx@p)y(*-*;q5{m5 z7uA8wt7u82U@B=jU6Q`Ofd!1UHGH*<4M0mep^%Pb3;oTuoO*9zMX8aU9&=r*xt`e* zao2g+&Y6mX31~TQh$SxwFd^4`wvE0K@I^O{Lz;(C0uOT~j~6qXJf$Q3q(?j=oM@N< zWQZbKxZ?bDuo=-KXl;*nrmm|*&??1y(n{c#fvXM39EI~n0|lW2kT_ALnhU2f@2$ip z!1XSkvj|$hUa!Nnwu%Lvji5*kfcku5`{p9jXPt*#Rd2&kfure}t4fOqBps-C1myc= zj<*vMsrtLwW<`CRkcezZ&?Kdj%XlM@Jmj{WDAgNI+cMk`ll@}e(wh~$!plRi#85n? z#$|&U(>K!dmSq?9Ck?qEh-v+b!vQ7)Nw-?u1fPpPNl)qE!VBuC^X8rx!e`mPcpu!8 zmHc}DR!?vvqIB0uq;P~A7+Tp?$55AO4))=bxI9C3(e2i0Zt^K94z^QO3!YV*_&$dz z^HsCE;K}3SO)csmvsG$p@+4B}XyYWD(w|Lft!c^%L)myz+~>uO-v#fUdArfk$E3Bo z3UWc}I}gUh`s!kTXOjeZ%$?lQTZ>u0+0_hO?PcXeuo^mM_H8 z+XqvjTn27KuzF3@bdU%i5$2}SG~q!;otF0&BwFsbzTeLIEP7g`yO+x|%zYf9 z(XT##Mp}!DQKtsk%5sKra~)E5;Cfr|qk_al&=5Cp$aX25>-czXefwR-zEzZ|p7k}H z0GDilN^Byv&)}`=q(xJuwI($vj2K)l@RBeo#rcUD?HtZpOrE{!s_QcBYY25)|9q79 zu5Fu_N1c@i7!y(iwIO3GymxW4{WiWzDk>#RWH271-;Sx?uq9+cc4n)T=(>+(-O-gv zlIsj>Q`559x+Bxz>Y1;4uW@e+=7t|D-1FotZD6pnPpvdJy;kkw_=Exx zc0eC{jkeWy+l++D!j;HG%6MJce6$(N|7*(k!e8To`m`wL;kT|MeW_+P{9(%J;>03I5xVW={=TYy z_M6_yEC4)#w;)3HI)N36gz6Gx#cgKhYDho%h017Zk_V;vl$vPbQm&7fhr>X)Vy^0V zPi+%0Kn7mXvc5MT{3^?qB}{gxDBcZ+F4L;vq}$1K0{s!twzMctSEDC8rp<>r-dU~7 zNH;skY64_resG^q6w@7O5Sr7GH~~}3rPy>(rvx!!gW>XIvk!}hPHIee9~j4%n{Np0 zDjpf#M|U&HB+0XL6-yhsiuMKw7eW+!8x$tb{DT}XtEMkr4tL~odb2y@JfizX-qXIZ z5u)VG!S9X?Z@Y$wnNblBSqtX^Q{57b_c)}8P*fox#U!yn#Wr?{ERP~4Pn(}L`};VP zyR*+Qp%aO0HxyC8J z-<#EYO^jceI=fBrk(U}{2{)&*aSXebY0I`Ge$q;tYb{PG_JVxA=m+42Q+3%97$)tD~QQZWWFW}qUhj^6PRkGA0*Or&zhHe}l;fM7rlK*4e z6;%x511mqh^@rnZ^K@ysvb>>9o#lxl%MA;= zYd);|jIwi*P8d{`@(Y*p#`p@x$a+4}t#m_IAFJVE8g?VI8Ifrt!!Hs0;%%k9z$L_j z6uz%v&zOM>iucw8;8~$ct0lYY9Ik6TK&|G-Dl3F$lS$1<^02$`)Y-gK=!*U@iog|m z;&nKTIxd28Y!`@Vc+h)k0(z&6gC!AL&-jf~fq}EzT_f)xwvK(kA%vR=P|Kll9ZO#C z?sYs}=x#cjA&EAPTOLk7plXqxvsZ$8*r~0$j?rqnHBMT|LaUXPRbB%F)xtypv|O)d2C%E3%(%4IvC5P0g#b!|NR+b7j@eC!#r->qck<}=ajxW~r>{Pf~^ z@Z&lX7*IT~fkr_m_Mt1hS}g%MY#*v}^f1AB$l86_<_*-)iAYIFmd!LX0k7|5m0q;h ztO1~0dkYA=(58vWeKc3Hfkv5NMuN8%UqJ%6vo4?NM;sR4M~yF)B5vDzPe{6b&sruO z%I6IF>JFw^6-uBrsJk9_-O-emqp6Xk4i(QzCZ%MpSOJbL^JZGAe+tV9{y%4j-s zYx2cR>=V}FY?>xRPRAf|cpQwBhkfoX?5@n)6lcN}Oy)^4iZyNeIb z9`E|sD%RAFlI3fal32*+B4)@d{+$M@MF9ZSHr zQyVD*WsK0mjRQBSD(tnp1~I2Hjv>r`RztOBD9@1$kp*3|P|eZ|7GfcwJ)89xh&rG! z@Jugnn4I`3WiIUP*PG?hhK8+uX8tO>@Vl_M4}-Ko;pb#FD!P_aqZ4Eo_6pApvUsf5 zuTyn#GIJ_;O~;l*ASfXrOZDJNGkqc!gB%J(%8GQea%7cS72JHn;SmL)Wy zqp@Q*4B8`;ym3~V69V-{K2|5&_z)=Cd=DDx?d{Eu2xD}tUo0t<9Wu|;mpJCmbbGo> zSew(tIx74&cCYgf7X1;|zA=UDmiCj}tV5d<-CqzivF(j}B=gK-fzbSP9(r`)c!9X} zMvAA02kytFiGUTr3Q(G0B15eabsaja*2B4+g!xmRhAHt39O9Htt*gHQe- zdurqCp;N=IMs6HZh&f>yqAklnG!TwqI9br{a$z}^y)NOZMFMv9rsz)fMMuhS=@89u zX_h4t(WD|_BI)P1IlIO=qeo0nJlguUEz2*??V;x0){yFfc*-xELr@c0=`yBSVzbd)#-DHpRXYS2zBqrrEJl zlNvM8BgVaBH8%n@_`t;y9!-;H{dj^+5|_8YlLMY)%k4v#h&+lmz}#kf&4^rGsoKZk zCox!n7+M`auRXV}Jf-zjY4U7@qK%;=>kywD9hh3t1ef^_ZKa-4Ym-&&(gMx!ypNnHYmu62i1@z+QhztiZiH7MH_f|?v)hFv9wBg@cOp++glG^$34L3s+|;9aQ)sJ6Nn#_c-P8(@rJkT)MO zcb0Ra#gRRdyIB&}jZ2Xv$&6m9sbDd+qN&Pf5)H+3mEAH#YB5s1(WDPJoh92)<7FfD zGr^$Dg&68yRbj@@TV~V(m{PUxNx^MAJVr=+y}iA)biNx`Cd{&S)3B3gTQ{h!hnkWK zYHa3$M99y3D7eWu95g;&)NR*)CN2ioA3AW?{~%tfARORvI#vg{=!Atrd9B8@IBV`I zN$FZ-Xrk3hApftu_l#<43m!+KUd4iP6%kPp6-A{g2okEIQlyELNDBf&1SBA#*C+~t z6cOo7YJgDGP(xJ|lt7T)NsyX^UZwx{3EtnjAKv@&)?07A-&%J*u);a}%$_}aX7+%;nNy zr_KmRNx>CMTTmMz_v&)fjI+nzJWp_&vQ6iUTKIULM0}A2fl`;_quk!6OVcNm1uD0mkjQe9R1|A z&X$f_q;4sD%5?qWRNWp%dp3jEZaojp+REI8^lOn5y0h;>ADu{fQe1rbTcc$-hFf+Lpb5LxBmB(+^40VPjp&RnbS8?(iv|@^PTz$6Vb@782?8?v)DV|>jJ6hD@ zUga@rU-#7xDGUWywqe;G_Ppa}+th^v;ni@Lj9cg8^sZRrWkZlKA!jObM*G>>+!j(k zbLQ(_SSeA2Qa{mr-A#Uy>aWLp(8v++?RKKqStTdc%R^r?E~j6uxXyYjFjT+V&dN9K zf+M#0@5>pY24UyM`XcfiEePGZqSBl9SZii}y;C8($*{|iT~CLvULC?l(W`k1Q;ULj zKXgua*CtnJ>i64ksZr(1m=v;9dswPuB1lCmXV7?#hw}ys%4ngE(OU;medNU%eqaNYqLm` zmrt35xzd)ro$Im|Opn)^;1b@=B2*lyJ+e~eR+BBOXej0J<7r#5eQj6f^;c|7S?-a) z1}`VMNHc!0I2)-_KMBF*q9hWvc}Qv@@$wJdR9qS>N9MO`eK&7dl9m6s z{9)I!mptE{+V8ZkXW`9a`I!9U14xhqN%Kn9<~l4FeVLQvaLrHLQM_){yn1KEqPwn5 z&^7;ss4P{^cRLdYi4lJ2g5DV2%0AN+lEO+bG4P!=U?X1L40RaDN%DBu4X zjppwW@q@}6^Bl)m

bZ0N-jU<`PkF2X|HN-_vZoqlpN|XndZK0!%B~*txpkJJdOcF9OMH)9qQ}KU zjZ;7%1%I-K)rA%un0Nd{;1F@!{9@9TlX^jBOl3q{e{YsHmQ=#|Y(v>xTzK3RyfW8U ze7{QNdVr$2!5#WLG56#0g;~S9;@p1&J@5cfR*_p6ndb;nw{&9O^ceT})0{zbNd(<7 zP&`OJNWbahFWS*^>7l)YkLE)dYZ`?J9RI`+D{S>j{`KHf89|FtA||!JX|C-_H^1%d zR@x)?!79!&9#oOVe>0pgl4%h2#twWhiAF3kexjFI?UqVdd$1&}`cv-)>Nb-cToEGc;KoyRP^9-b*2R8( zQjE2x1};0X1>|?RydSL~Fz3pVC@;H_DlkJstgf54<@>lGf66@A8*?#|WcjYMEDt%n zE|u@%*|B8$t+m)S#p6I{Fg%sf<5%-q*8Rco@7hL7%rnbbEt&OtxkS(P!O3a!*i}!@ z7GOt?;D)OF*vo4xOlKb4cd1Vdj2CW{Mp1Sg8)-h^Zp*dm?ItliaBUf-|pB42e{B~K3e#vFPcD*x_&?FX99BLp36NWrj-xs0r@IL^x9 zT}2|_-zMU}(z<2kd&-7gUNmLsoBk$v{8lMSft47rX_KSShZ}w_d&xP_Mq&1+dnYB* zkGfpg#ep3AZ5A;URuk<|>GC6qya!-~%?PGA_FZu5p{4?smh+ZbmcP8bKU%p6p3Au1=D7BIdUo;(!iEe!&>E??Jc|st%WV7b@@-m) zD!t&d63`47HC9Co2pN3HOCt%sLO4jUdsaE zg#4}bkpeIR}n8y-F@RV9w>*rq9P3U4b^^*T_;hZ2R5RzfEa?hGG&u(S6Z zXnGR0S-2;{&Po(BteyFB)~7`b9W*DuHzMwUCA~hg6ISiNaI$K#GiU)z`ozKH0hK!w zBKX2adev$f;LFVCjd`EBHSnuiTC0Vr7ue#Aj{jRN=%Ke9gjG+pRL6;xU4tkFFysDj z&f3RH@$n8ow}?Cv&ldb^CI&%FnoMa>DM2qw)!&@%>Vzp^&dC>pU6fL(Q#W{ zsJv^wl(orOf69u-*1{(tNMo^xx7+Ip^;Xy%$icy|*Y9sHyWqIjB1_eBuXZ(40jV{A z7DZQ%&)SLaXZRtRt-1p7hRGS^adi3Ypsb;)^1N6`sN6S0Nv=h3YFIy?qqq-crpaU$M zO0G66ua;+hz%F#lhvrvqs~R~kDt{hT4s850WMqMd>yYSj+G&ZkN2Am5P_F}+IQONw zk4+6latjNwp6-D7E(_<j!!Pxf3J=RRKanH5BzkUozez5?IVYp+cW!QdS_xvwNvU;} z@nMgLgAKhVNo+FAm62_BWc(29XRA%buZ^lj-0Nd2;`}F)WTQ$wyvu0(C%ihZv{Ym> zR7REY{@vbtFb%@F7G-c*R$S&d*UObMon>4>MDsEj+dX=3sL6C_pKqe;>D84DM$WfX z_aoU1YbP^NpVPve^$n+b5F@1L znA9bbI-VA}>vo2B?(hgM7?*Ssi=hM)=Lgakn5_85BM(PW1+FxbMUhMCFvFb_uO zlE!bVDk5G;%h8i{ccreWh>gTU3|?SQ^}wsnV;4Y=)UDBT~7D< zoBh1fMS*F44x@twn8NG=YuZl+q0_3qZ?nM36S6|%%JidDvcoTQfTTHjzf!Zq9pf@m zd(@OFCte9zbiX-#;YK!FrFeMj@UNe{+iEScF-381Tu-{`z4QRdbyl#NiwXIhwU4JE zf*j|j?SqYTkB2<@m7Uy)%YuTP_fbu$(y;1F?E<$9H9JV%vKUIOv&bM|zI4ubL0jr% z*SOr+RHic~ZB4IWsO=yc$f{&q0+1n=FwL!r?q{Bybb7FE)5`ePt~Z+_DgY(y^c_I* zQ-_YTify8_c41SM=;T({Hn`M$p_Z4(DTh5fVAPZ&Cj3q7YX+#P-iEWf4^>^PtnwD3 zouc~2Me}eKDPR(_UkCwI)wh6z_qD!PqB>cvHrTM?jLYFw(&<{pfOh-SgS>}|?p{IL zR#hQROmB>hPo*u;t@B^m=i7Ob6xpNHNf$c1@N{klQK#owxJd;>+k_&B95oi+J0BVb zXZ5l3ab9|CHO{1kVRX_`@fV+qtjQA2h3! z5kf-st~}Mh119;>PTso$VI(DY1U=3lav^1EkMSPE_?s};_p2N4H$Tqal-ek*FpKJ6 zU*B9jFT1aiNL<}*z1V&Xj*_3>yApMC@d9G`&ZqHJL2ivTt61A`^tomXgdcqi5V=|7 zkUO%N#%4#CV==_`u?Go#m#4#IlCq%Jj$@D@-leY#2zo9k_ z3L7}GD&b#15)FAk*@W`dx&XB?(UG_sA7A;5m`jY4L^v6iDXYx3NJl zXIjf`twxf?!REkYU{h4QqEnBn`O6`_sc1?QGPtANRH#24UDwj8LktFA!~_sJ=jO-) zqXxO>MtQEyl3GYka2GIRlANoxPm}W!pV64z4}k6;Cg`S|8*{t%$V7NoNnR4As&eyG zf0)xn@Vbx>zA5KY>xlOd%oVp8G)@!?@iMtQKYl2i)jmHKOC07R&w`F zq6_7RdaPx>IP$S+fpTn@Q=RC=Sr#}@5wFRW(7muL3X5a&Us2d@1eNGJY{T`1Y|IRT z^E80AR4`wyq8S`>iz>7o+ zmyMmO8hPhrHESLvwzmKiz7u8zr(|iq9V)+v&}2kV#8n{<$~*)9t>!g>!jjmyeTcgQ zEI%j}s$~SPHN9y3IH(tGNjIBQHAWv4L-Da>NluFqxW!PZ75$#l*Pc?j{&LqUKHf$7 z!9($!oBDhfSzJRe{=!QPcSvS>5wJS2gu71{3M+ zFM78M;!i-NlYxj*_3m<>P}JU`5lI^+>Knjf z!eAk@?%uP46oO~wtRC!fWRQ`U6TUfi3SDwr&Z;n+wr~Br+|4_ae!+ZFMxAC_Wj~`- zrvl@}nF!9P(~n}MGd0F!9_jb5S6jU-Mv?an=C1ZUye;EcxOcqUA(OV5cJYISV1QSR zaK#q#8XoVY+vF_8d>Z&mkUNO=9cdFVM$dbTYn^sl1$EVPxl`&4U*VI+leLF_d~ewQ z3BER}9A6grou+gRPvfTKJLfxs1L_dSFkQt{moM%vAvRv~bA1wPFK%GKi8*yG@HU%# ziiU*q<$lNh5FzekG8USKTC~n4oV-zPTbX-iJEAq0bMp8=BE0J28;VhxJ>AkUPwyU5 zmUG4F{cA<{Qm$?GTLMKZ*`-Rhnw&THGxdr2{Pm=ayzIrnHnT045AkZc6n0MXpsX+l zdNkr0vO*L$J3g|9^pif<{#BJjI>UA{8lBhQ(UyMFIAJM8#+}Bc;!=|LEyWp9Vi>kk zE)?=2We`rut!iUzCr)?OG>20vrTdW4e;>TQH=UG`w>bk=n0$G7or&ItOxjngIt0)v zyM-fSP*4q|Lkp6FDZZ`Q*|Dbq8asI#&|9?LP6yw>4^}Bp=yPKP?$(zt*rmPIo)d-! zC`B20W|UKgLkHt3r&zZgdQ~X6tUlPNV305G+tcITGpF>Zc zcVDh`ylzQk%XeDC$K^Z6|Kf?oQRH)Y$j-~c+|o77$EqVmlz=&e9k(d->wE8iSY($< zd-}AiK!R@gkArGSM2)QYZU%B33=@FsQ7B13-Sn$fLnKAV>nGoHx5}{48$8>$mw6w? z!c>gYruSB=5$mdZb3_RHgXsfPk?HR-=jQkcqhg>_G4PgPk^HLlrM0BGCCJmBgR%@T zT%>Yu{MlF9&Hf1o63~nG{@r*qk!Xi1IZu5cU*#iIaX4f8PODe{y^84V0hh2di3!R` zSBd&ID7R_z0HrU5ZW4_lbloG;Ziy-e(A{}G`o0WnVnmF z3PNAB26m&+#p36MLIofX53fU^sr?Q@-=pKPp0*zfRXGh+>efq!=~KQfcUt%LiM@x* z9)?dY#kL2c9@HcpHKw0sT;7Gfjt(%TM0?MJ+G5mSrHPvkl@A!eDJ1z?yNE$aP_>foB zE)4;0c!GNczX#NhG&2|L_xJG=pK}yK^v{WTbw26WTX~jkah#EQMG1+LYLKOHWehc1 zEfd998_EZqi>AgKo=@TBHLG?Bp48pVb^4sVg8`8X;QFZmG2pnu>BoN&_U~(b&|(d* zh)|FfGRQP1<`5v zgQazf>PqhLL}IC(c`Cqr?>2-tvzSBV??aDG^^$w^magWc#&q#LWxV{H^>oK=ASEM3f>jHT6@DUml>9+_6GD7C zTk6Yiu&z7a{M=p3p?zpE{p#_$URUfi+DG1X4d-Lfe4JD?aLJBvI|k^H}K23 z138b~o!O^aRw zLx~Q9Vt(u4uLp*A-Hp+eOkP6Og6ym3T|YBDMn#`i zI~vkp<8$d&`W;^@@$yZ5oS=7pD4wgnwP;Yq6SnJ((3M?ah!>^t)t#?_Kug^{x`X>@ zzGrcCCV#B*%M5%Z-_pUga5+n|B{Ttg83JqY zzKr6%g;_!sJ1<*7hKLLTA6Ut8E^T1rkzsWsI6sm9nJ`cT^5uWk0FR0JC-F)plwI zcB`R2q0&6#OU8|?DXw~?TjTlz>z+@|G)>Fg7h!#0D*@)8<0Ob*0H{UC&#kv>9V69t zyRHGT!qI+MycLx{y;^6obsr()1e~l>V>UzG_!SFnT!P@;NDSTw{J{OU-i*w@vnz#M9qJ4TC%%x zzY~hc0NlF`!~pg<;uY)W`lhb#_n3J2kG>3dUoSE#MkyA3efF&b&R#zM`d`<#{i!#% znC(Sh)4mT|fcdcT9_-51Zc>PV;0n8|w^nSy~oJh79@}=2c&pX&~*l>{rt$aA#z@Qg^?>_&UOM$WMv!QSArb z4_&EA4L+I0fL=@ogDL*rc2l>K7m{a&+~-86tVpPnm(QOU?gU|sTxrUD_MgFXlT|I* zm4dJJqkpAaBv>(@ey9iyT$$^gv?sR&^euEW*Q+ey57!HFrPAxF(9MlwLGNDoxR<^8 zp{m-K9pKW|t-8Vjr+51&8MNfb zAw3M-HsZwLNGVj_IGlH6z2);Ntx&3$x|pO%PCQnDLfd|j!nZc+*-eIwU081nB$^5r z!yl!!8b|heF!OORtkkwVpi_jsA_fFxEbj=4Z?#)kX4>7rZ9Il6WomqL62y4Sg%!Cv zjL&Et3Ag-KD?QKz#eI#XHqa|?@n z35+vyyFBXhsh~8nh^{ldC}NFXtUT4L=MS9<*0sHeP; zQ&;bYX-8UqyUUo0?G{cqZC$3!-%5w;w*!7&*D`+DX&)zS)wVR>a&DfdE>Uq31x0b4$Q558Z0 zPxCbW^?2oKoyAC7d_}f+VwANs+kEP>vV{s5GRPYBGZzi)y!DUPoQ|p|#Z9e)ELoZQ zl6h>mP7?c+J!Ea-3=M?1iJDqXYU!NzC0>?pR9aF?f3I#*ROnkSY0qf&PoJsg6mx2%n9g$E7zi;CCRdP_WOv<2*|_jf9ahFieupId zw2Vt*s2`GWH7@*CJ?)^Z$QakCQm=AF=MJ_g{Q&4iS1<=?zYB(P>|CU-)8pVxUQ=yZ zXN9lczbeR|qn9vYQ(RVNevL5Hthk&^?Ca<9>mE2b?ZoyD(`aX`rCIjyi!}bRLW>d! zuCwOWEwy(2c-Cvko?v$|J@VA}nZeQY#(v%hk(8kP&Zih{p>_}r}#boO?;z)MAu+>yjvPgkzM4n z3*;@{5P{;J8|mvuRo#6p3Q2*I4#y%gF3>vvL^?TgrCe z|FZa~pK{4kNg!7hF*wX=-~Xm{Y$Se#bePvxMzZPSB6+A@<@?t7+$V8-z)<{fxsh2K z>3U84{Z)uh+a9Gsqk;?vX|T0$FtF|uXQAYQXv;{GY_hZ;OA@!~vAX!ew-5SFWPdxx znGf;ePS8YS-*i2&ezwt1%~qw%rE5r^#edGw4lY1^No3shF;g)*i~2od|K6Thl;-2} za0QN9v`y=D`>|5)-XEq>Y=Rbag@#&vZ`*8XJWV>Z*4RBtkKS9y=N&e_{bOzn&$8nNDC$s(VLl+YR zuAE&?aWg>U$p_CbcE-o9c=`KOQ<4KsRv#-vS0xgZ3kiy5cV7aLNVFZ(h>4 z+R$KT$gy}^HEB%RgCJ!6G;$9~@Vh~R3oDzP^cTSpxJ~+{Qys2IDT9r=+3GN|#9m$! zEp_&9j-**+Sq}0c-cGPJs_0NjA;OFjSoFn@9^}d?HHMlV3xYg1SP@|88v!FPO&zBb z?Kr}IM6#6Lk~LiU&h;ZB_3q+YUhzazB6^2wj$@j4OoqXRl9;jAir0EPHv$tFuz4PN z@K*5P($FJ~iMm?mL=h~LlD=9ICOq0*g@ClJQ{HihS{>z0YgZ<`p0VGdg-&pPQ9 zWy4oQ$V}XuoCiA<_UyE`LM$CfDIBzp^WkzM`A$qqv;>-F^s0{;hTKBTX?XI>%Iwj@ReB zBoJq{aFz?oWvpUVTk61$l*zBv zH3) zO>GJt1I|TnG{6f2E8tbw3kS2koJJezml1-GI$K^nj`hmCAKzruukx+azg_8q4B_Yk zU1XD67mFEpE3H#z`o*xW7~n&Hy!kqx^fG>7zN6Jkpa-9lOZUr;IK4&0Cqr5g|8or? zy?)@p%*U{GhE0-5CZoOn5PQqVlR{f-zYKWQCzuJkROZS*m5SCHPH=cImFODZ$4GBS z)cF5wFVtW**kV>Onl$8e0rISmX~#)<-|-_k9d}V+%YHUm=l+ZwrWli)t{tR~vpeSzluMj@2V!x97z z@>O;SS$Y5|U5sIH;cc|?t0v^n-qLJzQ|u8{3j^-HYpi~7L*Uz#>FGl;Yvjtr;bO@( zzX<(cCjoHSFaoux+EL6?Wl3RaiSPOQRkb=k2{yEy9d!>Cz zDW|=~yY8~1Cm*cN#~-}A_NLp66avqU3c0jJt&l-Mkvm8>fWW5qZktV(gfvwzI2@@_ z+0c5QjIp6$MnxEkv2MGO*S>;OZo%WNdTsX?k*sD~x4@g<(ZF6Uc?ncD8at*1+j_+> zlH?$4QP9>sr}JVx&!F$&*YR%rK)|e)$ub}qyb;!L@rpfLWg}!%s^vf^Aemp5cfd05 zMgMz+u?vd)P(aOuH!485KWZFL5VS=xCvgA1>^?+@wWrm|0)U4Zwv}tEC=CWq%ezy%Vq0@LJMyUVG`vb?so{4>dHOi zHDe(_8nEPZ$7`yK+)^@-YUtiWn;f|d#-#B*s!(k|Sa*SC3xmv)%e5;BU~bi?(-Gns zbxqwa;@Q#TEgh<+nOFO~;~N4tx)OVd}eiEvkc8q+ox1 z;8iGaH9|&TYSi!T+JBVqTm(mgiru{)|Au3D7qDoh+r@zIL63(eJ_2^Nn!UWz>~|!@ zWSC4Ou&|ClEh=&s&In!on&QXr{G+c@Dzvxaq6o(~BTdm3ZZa(h#}3g90b3fFJ^g`Z zqHL0Alh*mmOeEm?gFn?X%tmLR+AU8{*GHcFFw8g%T$Kq211=rdQRXrXDjT-JHH4Wp zm)vb3Ew)|m0$rDh1TA-eov1ec(`@^Sf7rlwvL8(6fj|36e;OEJ!4v-jSN~nXYW64l z!o2$x3NHVFSO2cu{QKX9u1xa(X?8;mN=p6#Z1jH}0apAkV%^8>eHjqBNBgXG`oM|X zn{KCWK)ITKzzhnbAn;tLY;9D9FqNvhn;E|SY4bl~AX(*jbfk8`6Q)fXi&nMDjrn(KWY>7 z?<&k26aO;|=rQ{p|LGQB!++KS5(e0Rh8E(&f5HH9;Xh$ua^XK=_)i#^9Dx4(?-7QX z>B*jF5XsmxK8(Z1E`?xGf7~PJ;!MuJ9H&GmZ~h0W3IB4gUH@Iv-URK}{sF2!*qZnU nWT3jAKk#2C|8U~}6LyId_U=5dJFCJD^{R45<943H!{`48TmKV~ literal 0 HcmV?d00001 diff --git a/racs2_demos_on_spaceros/racs2_demos_on_spaceros/__init__.py b/racs2_demos_on_spaceros/racs2_demos_on_spaceros/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/racs2_demos_on_spaceros/run.sh b/racs2_demos_on_spaceros/run.sh new file mode 100755 index 0000000..5b36331 --- /dev/null +++ b/racs2_demos_on_spaceros/run.sh @@ -0,0 +1,16 @@ +#!/usr/bin/env bash + +# Runs a docker container with the image created by build.bash +# Requires: +# docker +# an X server + +IMG_NAME=jaxa/racs2_demos_on_spaceros + +# Replace `/` with `_` to comply with docker container naming +# And append `_runtime` +CONTAINER_NAME="$(tr '/' '_' <<< "$IMG_NAME")" + +# Start the container +docker run --rm -it --name $CONTAINER_NAME --network host \ + -e DISPLAY -e TERM -e QT_X11_NO_MITSHM=1 $IMG_NAME diff --git a/racs2_demos_on_spaceros/worlds/mars_curiosity.world b/racs2_demos_on_spaceros/worlds/mars_curiosity.world new file mode 100644 index 0000000..a5c036f --- /dev/null +++ b/racs2_demos_on_spaceros/worlds/mars_curiosity.world @@ -0,0 +1,64 @@ + + + + + + + 3D View + false + docked + + ogre2 + scene + 0.9 0.753 0.66 + -5.0 0.0 -6.0 0.0 0.0 0.0 + + + + + floating + + + + + + + + + + ogre2 + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + 0 0 -3.711 + + + model://curiosity_path + curiosity_path + 0 0 0 0 0 0 + + + +